From b9f0c68e3c686a7eb0a7e01284ff395a994d3960 Mon Sep 17 00:00:00 2001 From: Vovodroid Date: Fri, 28 Nov 2025 00:41:20 +0200 Subject: [PATCH 01/47] =?UTF-8?q?=E2=9A=A1=EF=B8=8F=20Minimize=20M190=20an?= =?UTF-8?q?nealing=20code=20(#26888)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/temp/M140_M190.cpp | 14 +++++--------- 1 file changed, 5 insertions(+), 9 deletions(-) diff --git a/Marlin/src/gcode/temp/M140_M190.cpp b/Marlin/src/gcode/temp/M140_M190.cpp index 1a179873cc..7d2de2084a 100644 --- a/Marlin/src/gcode/temp/M140_M190.cpp +++ b/Marlin/src/gcode/temp/M140_M190.cpp @@ -93,7 +93,7 @@ void GcodeSuite::M140_M190(const bool isM190) { #if ENABLED(BED_ANNEALING_GCODE) const bool anneal = isM190 && !no_wait_for_cooling && parser.seenval('T'); - const millis_t anneal_ms = anneal ? millis() + parser.value_millis_from_seconds() : 0UL; + const millis_t anneal_ms = anneal ? parser.value_millis_from_seconds() : 0UL; #else constexpr bool anneal = false; #endif @@ -110,15 +110,11 @@ void GcodeSuite::M140_M190(const bool isM190) { #if ENABLED(BED_ANNEALING_GCODE) if (anneal) { LCD_MESSAGE(MSG_BED_ANNEALING); + const millis_t wait_ms = anneal_ms / (thermalManager.degBed() - temp); // Loop from current temp down to the target - for (celsius_t cool_temp = thermalManager.degBed(); --cool_temp >= temp; ) { - thermalManager.setTargetBed(cool_temp); // Cool by one degree - thermalManager.wait_for_bed(false); // Could this wait forever? - const millis_t ms = millis(); - if (PENDING(ms, anneal_ms) && cool_temp > temp) { // Still warmer and waiting? - const millis_t remain = anneal_ms - ms; - dwell(remain / (cool_temp - temp)); // Wait for a fraction of remaining time - } + for (celsius_t cool_temp = thermalManager.degBed() - 1; cool_temp >= temp; --cool_temp) { + thermalManager.setTargetBed(cool_temp); // Cool by one degree + dwell(wait_ms); // Wait while going to the next degree } return; } From e3ef8d2089b008b8ba8ad3fa2b519e9820db8a03 Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Fri, 28 Nov 2025 12:28:32 +1300 Subject: [PATCH 02/47] =?UTF-8?q?=E2=9C=A8=20BOARD=5FRASPBERRY=5FPI=5FPICO?= =?UTF-8?q?=20(and=20other=20RP2040=20updates)=20(#28181)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/RP2040/HAL.cpp | 173 +++++++++++++++--- Marlin/src/HAL/RP2040/HAL.h | 10 +- Marlin/src/HAL/RP2040/eeprom/eeprom_flash.cpp | 42 +++-- Marlin/src/HAL/RP2040/pinsDebug.h | 117 +++++++----- Marlin/src/HAL/RP2040/temp_soc.h | 30 +++ Marlin/src/HAL/RP2040/u8g/LCD_defines.h | 28 +++ .../HAL/RP2040/u8g/u8g_com_rp2040_ssd_i2c.cpp | 108 +++++++++++ Marlin/src/HAL/STM32/pinsDebug.h | 9 +- Marlin/src/core/boards.h | 3 +- Marlin/src/lcd/marlinui.cpp | 6 +- Marlin/src/pins/mega/pins_GT2560_V3.h | 3 +- Marlin/src/pins/mega/pins_INTAMSYS40.h | 2 +- Marlin/src/pins/pins.h | 2 + .../src/pins/rp2040/pins_RASPBERRY_PI_PICO.h | 171 +++++++++++++++++ Marlin/src/pins/rp2040/pins_RP2040.h | 28 ++- Marlin/src/sd/SdBaseFile.h | 13 ++ Marlin/src/sd/SdFatStructs.h | 4 +- ini/raspberrypi.ini | 5 +- 18 files changed, 646 insertions(+), 108 deletions(-) create mode 100644 Marlin/src/HAL/RP2040/temp_soc.h create mode 100644 Marlin/src/HAL/RP2040/u8g/LCD_defines.h create mode 100644 Marlin/src/HAL/RP2040/u8g/u8g_com_rp2040_ssd_i2c.cpp create mode 100644 Marlin/src/pins/rp2040/pins_RASPBERRY_PI_PICO.h diff --git a/Marlin/src/HAL/RP2040/HAL.cpp b/Marlin/src/HAL/RP2040/HAL.cpp index e8d0eea7cd..9341480078 100644 --- a/Marlin/src/HAL/RP2040/HAL.cpp +++ b/Marlin/src/HAL/RP2040/HAL.cpp @@ -32,17 +32,123 @@ extern "C" { #include "pico/bootrom.h" #include "hardware/watchdog.h" + #include "pico/multicore.h" + #include "hardware/adc.h" + #include "pico/time.h" } #if HAS_SD_HOST_DRIVE #include "msc_sd.h" - #include "usbd_cdc_if.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 + +// Core 1 watchdog monitoring +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 +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"); + + while (true) { + // Update heartbeat timestamp at start of each scan cycle + core1_last_heartbeat = time_us_32(); + + // Scan all enabled ADC channels + for (uint8_t channel = 0; channel < 5; channel++) { + if (!adc_channels_enabled[channel]) continue; + + // Enable temperature sensor if reading channel 4 + if (channel == 4) { + adc_set_temp_sensor_enabled(true); + } + + // Select and read the channel + adc_select_input(channel); + busy_wait_us(100); // Settling delay + adc_fifo_drain(); + adc_run(true); + + // Wait for conversion with timeout + uint32_t timeout = 10000; + while (adc_fifo_is_empty() && timeout--) { + busy_wait_us(1); + } + + adc_run(false); + uint16_t reading = adc_fifo_is_empty() ? 0 : adc_fifo_get(); + + // Accumulate readings for oversampling + 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 + if (adc_counts[channel] >= OVERSAMPLENR) { + adc_accumulators[channel] = 0; + adc_counts[channel] = 0; + } + + // Disable temp sensor after reading to save power + if (channel == 4) { + adc_set_temp_sensor_enabled(false); + } + } + + // Core 1 LED indicator: Double blink every 2 seconds to show Core 1 is active + 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 + } + #endif + } + + // Delay between full scan cycles + busy_wait_us(10000); // 10ms between scans + } +} + volatile uint16_t adc_result; // ------------------------ @@ -118,9 +224,28 @@ void MarlinHAL::reboot() { watchdog_reboot(0, 0, 1); } } 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 + } + 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, ")"); + } + #if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED) - TOGGLE(LED_PIN); // heartbeat indicator + // Core 0 LED indicator: Single toggle every watchdog refresh (shows Core 0 activity) + TOGGLE(LED_PIN); #endif } @@ -130,43 +255,35 @@ void MarlinHAL::reboot() { watchdog_reboot(0, 0, 1); } // ADC // ------------------------ -volatile bool MarlinHAL::adc_has_result = false; - void MarlinHAL::adc_init() { analogReadResolution(HAL_ADC_RESOLUTION); ::adc_init(); adc_fifo_setup(true, false, 1, false, false); - irq_set_exclusive_handler(ADC_IRQ_FIFO, adc_exclusive_handler); - irq_set_enabled(ADC_IRQ_FIFO, true); - adc_irq_set_enabled(true); + // Launch Core 1 for continuous ADC reading + multicore_launch_core1(core1_adc_task); + adc_has_result = true; // Results are always available with continuous sampling } void MarlinHAL::adc_enable(const pin_t pin) { - if (pin >= A0 && pin <= A3) + if (pin >= A0 && pin <= A3) { adc_gpio_init(pin); - else if (pin == HAL_ADC_MCU_TEMP_DUMMY_PIN) - adc_set_temp_sensor_enabled(true); -} - -void MarlinHAL::adc_start(const pin_t pin) { - adc_has_result = false; - // Select an ADC input. 0...3 are GPIOs 26...29 respectively. - adc_select_input(pin == HAL_ADC_MCU_TEMP_DUMMY_PIN ? 4 : pin - A0); - adc_run(true); -} - -void MarlinHAL::adc_exclusive_handler() { - adc_run(false); // Disable since we only want one result - irq_clear(ADC_IRQ_FIFO); // Clear the IRQ - - if (adc_fifo_get_level() >= 1) { - adc_result = adc_fifo_get(); // Pop the result - adc_fifo_drain(); - adc_has_result = true; // Signal the end of the conversion + adc_channels_enabled[pin - A0] = true; // Mark this channel as enabled + } + else if (pin == HAL_ADC_MCU_TEMP_DUMMY_PIN) { + adc_channels_enabled[4] = true; // Mark MCU temp channel as enabled } } -uint16_t MarlinHAL::adc_value() { return adc_result; } +void MarlinHAL::adc_start(const pin_t pin) { + // Just store which pin we need to read - values are continuously updated by Core 1 + current_pin = pin; +} + +uint16_t MarlinHAL::adc_value() { + // Return the latest ADC value from Core 1's continuous readings + const uint8_t channel = (current_pin == HAL_ADC_MCU_TEMP_DUMMY_PIN) ? 4 : (current_pin - A0); + return adc_values[channel]; +} // Reset the system to initiate a firmware flash void flashFirmware(const int16_t) { hal.reboot(); } diff --git a/Marlin/src/HAL/RP2040/HAL.h b/Marlin/src/HAL/RP2040/HAL.h index 11472f72f5..206847053b 100644 --- a/Marlin/src/HAL/RP2040/HAL.h +++ b/Marlin/src/HAL/RP2040/HAL.h @@ -40,6 +40,11 @@ #include "msc_sd.h" #endif +// ADC index 4 is the MCU temperature +#define HAL_ADC_MCU_TEMP_DUMMY_PIN 127 +#define TEMP_SOC_PIN HAL_ADC_MCU_TEMP_DUMMY_PIN // ADC4 is internal temp sensor +#include "temp_soc.h" + // // Serial Ports // @@ -85,8 +90,6 @@ typedef libServo hal_servo_t; #else #define HAL_ADC_RESOLUTION 12 #endif -// ADC index 4 is the MCU temperature -#define HAL_ADC_MCU_TEMP_DUMMY_PIN 127 // // Pin Mapping for M42, M43, M226 @@ -164,9 +167,6 @@ public: // Begin ADC sampling on the given pin. Called from Temperature::isr! static void adc_start(const pin_t pin); - // This ADC runs a periodic task - static void adc_exclusive_handler(); - // Is the ADC ready for reading? static volatile bool adc_has_result; static bool adc_ready() { return adc_has_result; } diff --git a/Marlin/src/HAL/RP2040/eeprom/eeprom_flash.cpp b/Marlin/src/HAL/RP2040/eeprom/eeprom_flash.cpp index 89e882d77b..bf52109173 100644 --- a/Marlin/src/HAL/RP2040/eeprom/eeprom_flash.cpp +++ b/Marlin/src/HAL/RP2040/eeprom/eeprom_flash.cpp @@ -31,28 +31,48 @@ // NOTE: The Bigtreetech SKR Pico has an onboard W25Q16 flash module -// Use EEPROM.h for compatibility, for now. -#include +// RP2040 Flash-based EEPROM emulation using internal flash memory +#include +#include -static bool eeprom_data_written = false; +// Flash sector size is already defined in hardware/flash.h as FLASH_SECTOR_SIZE +// Place EEPROM emulation at the end of flash, before the filesystem +// This assumes 2MB flash, adjust if using different flash size +#define FLASH_TARGET_OFFSET (PICO_FLASH_SIZE_BYTES - FLASH_SECTOR_SIZE) #ifndef MARLIN_EEPROM_SIZE #define MARLIN_EEPROM_SIZE size_t(E2END + 1) #endif + +static uint8_t eeprom_buffer[MARLIN_EEPROM_SIZE]; +static bool eeprom_data_written = false; +static bool eeprom_initialized = false; size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } bool PersistentStore::access_start() { - EEPROM.begin(); // Avoid EEPROM.h warning (do nothing) - eeprom_buffer_fill(); + if (!eeprom_initialized) { + // Read from flash into buffer + const uint8_t *flash_data = (const uint8_t *)(XIP_BASE + FLASH_TARGET_OFFSET); + memcpy(eeprom_buffer, flash_data, MARLIN_EEPROM_SIZE); + eeprom_initialized = true; + } return true; } bool PersistentStore::access_finish() { if (eeprom_data_written) { TERN_(HAS_PAUSE_SERVO_OUTPUT, PAUSE_SERVO_OUTPUT()); - hal.isr_off(); - eeprom_buffer_flush(); - hal.isr_on(); + + // Disable interrupts during flash write + const uint32_t intstate = save_and_disable_interrupts(); + + // Erase and program the sector + flash_range_erase(FLASH_TARGET_OFFSET, FLASH_SECTOR_SIZE); + flash_range_program(FLASH_TARGET_OFFSET, eeprom_buffer, MARLIN_EEPROM_SIZE); + + // Restore interrupts + restore_interrupts(intstate); + TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT()); eeprom_data_written = false; } @@ -62,8 +82,8 @@ bool PersistentStore::access_finish() { bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { while (size--) { uint8_t v = *value; - if (v != eeprom_buffered_read_byte(pos)) { - eeprom_buffered_write_byte(pos, v); + if (pos < (int)MARLIN_EEPROM_SIZE && v != eeprom_buffer[pos]) { + eeprom_buffer[pos] = v; eeprom_data_written = true; } crc16(crc, &v, 1); @@ -75,7 +95,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { do { - const uint8_t c = eeprom_buffered_read_byte(pos); + const uint8_t c = (pos < (int)MARLIN_EEPROM_SIZE) ? eeprom_buffer[pos] : 0xFF; if (writing) *value = c; crc16(crc, &c, 1); pos++; diff --git a/Marlin/src/HAL/RP2040/pinsDebug.h b/Marlin/src/HAL/RP2040/pinsDebug.h index f3842c4aff..8f58089fb1 100644 --- a/Marlin/src/HAL/RP2040/pinsDebug.h +++ b/Marlin/src/HAL/RP2040/pinsDebug.h @@ -25,7 +25,7 @@ #include "HAL.h" #ifndef NUM_DIGITAL_PINS - #error "Expected NUM_DIGITAL_PINS not found" + #error "Expected NUM_DIGITAL_PINS not found." #endif /** @@ -74,6 +74,27 @@ * signal. The Arduino pin number is listed by the M43 I command. */ +/** + * Pins Debugging for RP2040 + * + * - NUMBER_PINS_TOTAL + * - MULTI_NAME_PAD + * - getPinByIndex(index) + * - printPinNameByIndex(index) + * - getPinIsDigitalByIndex(index) + * - digitalPinToAnalogIndex(pin) + * - getValidPinMode(pin) + * - isValidPin(pin) + * - isAnalogPin(pin) + * - digitalRead_mod(pin) + * - pwm_status(pin) + * - printPinPWM(pin) + * - printPinPort(pin) + * - printPinNumber(pin) + * - printPinAnalog(pin) + */ + +#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS #define NUM_ANALOG_FIRST A0 #define MODE_PIN_INPUT 0 // Input mode (reset state) @@ -81,66 +102,66 @@ #define MODE_PIN_ALT 2 // Alternate function mode #define MODE_PIN_ANALOG 3 // Analog mode -#define PIN_NUM(P) (P & 0x000F) -#define PIN_NUM_ALPHA_LEFT(P) (((P & 0x000F) < 10) ? ('0' + (P & 0x000F)) : '1') -#define PIN_NUM_ALPHA_RIGHT(P) (((P & 0x000F) > 9) ? ('0' + (P & 0x000F) - 10) : 0 ) -#define PORT_NUM(P) ((P >> 4) & 0x0007) -#define PORT_ALPHA(P) ('A' + (P >> 4)) +#define getPinByIndex(x) pin_array[x].pin +#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) +#define getPinIsDigitalByIndex(x) pin_array[x].is_digital +#define digitalPinToAnalogIndex(P) digital_pin_to_analog_pin(P) -/** - * Translation of routines & variables used by pinsDebug.h - */ -#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS -#define VALID_PIN(ANUM) (pin_t(ANUM) >= 0 && pin_t(ANUM) < NUMBER_PINS_TOTAL) -#define digitalRead_mod(Ard_num) extDigitalRead(Ard_num) // must use Arduino pin numbers when doing reads -#define PRINT_PIN(Q) -#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0) -#define DIGITAL_PIN_TO_ANALOG_PIN(ANUM) -1 // will report analog pin number in the print port routine +uint8_t get_pin_mode(const pin_t pin) { + // Check if pin is in alternate function mode (I2C, SPI, etc.) + const uint32_t gpio_func = gpio_get_function(pin); -// x is a variable used to search pin_array -#define GET_ARRAY_IS_DIGITAL(x) ((bool) pin_array[x].is_digital) -#define GET_ARRAY_PIN(x) ((pin_t) pin_array[x].pin) -#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) -#define MULTI_NAME_PAD 33 // space needed to be pretty if not first name assigned to a pin - -uint8_t get_pin_mode(const pin_t Ard_num) { - - uint dir = gpio_get_dir( Ard_num); - - if (dir) return MODE_PIN_OUTPUT; - else return MODE_PIN_INPUT; + // GPIO_FUNC_I2C is typically function 3 on RP2040 + if ( gpio_func == GPIO_FUNC_I2C + || gpio_func == GPIO_FUNC_SPI + || gpio_func == GPIO_FUNC_UART + || gpio_func == GPIO_FUNC_PWM + ) { + return MODE_PIN_ALT; + } + // For GPIO mode, check direction + return gpio_get_dir(pin) ? MODE_PIN_OUTPUT : MODE_PIN_INPUT; } -bool getValidPinMode(const pin_t Ard_num) { - const uint8_t pin_mode = get_pin_mode(Ard_num); +bool getValidPinMode(const pin_t pin) { + const uint8_t pin_mode = get_pin_mode(pin); return pin_mode == MODE_PIN_OUTPUT || pin_mode == MODE_PIN_ALT; // assume all alt definitions are PWM } -int8_t digital_pin_to_analog_pin(pin_t Ard_num) { - Ard_num -= NUM_ANALOG_FIRST; - return (Ard_num >= 0 && Ard_num < NUM_ANALOG_INPUTS) ? Ard_num : -1; +#define isValidPin(P) WITHIN(P, 0, pin_t(NUMBER_PINS_TOTAL - 1)) + +int8_t digital_pin_to_analog_pin(pin_t pin) { + pin -= NUM_ANALOG_FIRST; + return (WITHIN(pin, 0, NUM_ANALOG_INPUTS - 1)) ? pin : -1; } -bool isAnalogPin(const pin_t Ard_num) { - return digital_pin_to_analog_pin(Ard_num) != -1; +bool isAnalogPin(const pin_t pin) { + return digital_pin_to_analog_pin(pin) != -1; } -bool is_digital(const pin_t x) { - const uint8_t pin_mode = get_pin_mode(x); - return pin_mode == MODE_PIN_INPUT || pin_mode == MODE_PIN_OUTPUT; +#define digitalRead_mod(A) extDigitalRead(A) // must use Arduino pin numbers when doing reads +#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%3d "), P); SERIAL_ECHO(buffer); }while(0) +#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0) +#define MULTI_NAME_PAD 33 // space needed to be pretty if not first name assigned to a pin + +//bool is_digital(const pin_t pin) { +// const uint8_t pin_mode = get_pin_mode(pin); +// return pin_mode == MODE_PIN_INPUT || pin_mode == MODE_PIN_OUTPUT; +//} + +bool pwm_status(const pin_t pin) { + // Check if this pin is configured for PWM + return PWM_PIN(pin) && get_pin_mode(pin) == MODE_PIN_ALT; } -void printPinPort(const pin_t Ard_num) { - SERIAL_ECHOPGM("Pin: "); - SERIAL_ECHO(Ard_num); -} - -bool pwm_status(const pin_t Ard_num) { - return get_pin_mode(Ard_num) == MODE_PIN_ALT; -} - -void printPinPWM(const pin_t Ard_num) { - if (PWM_PIN(Ard_num)) { +void printPinPWM(const pin_t pin) { + if (pwm_status(pin)) { + // RP2040 has hardware PWM on specific pins + char buffer[22]; + sprintf_P(buffer, PSTR("PWM: pin %d "), pin); + SERIAL_ECHO(buffer); } } + +void printPinPort(const pin_t pin) {} diff --git a/Marlin/src/HAL/RP2040/temp_soc.h b/Marlin/src/HAL/RP2040/temp_soc.h new file mode 100644 index 0000000000..e182fb88dc --- /dev/null +++ b/Marlin/src/HAL/RP2040/temp_soc.h @@ -0,0 +1,30 @@ +/** + * 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 + +// RP2040 internal temperature sensor +// Formula: T = 27 - (ADC_voltage - 0.706) / 0.001721 +// ADC_voltage = (RAW / OVERSAMPLENR) * 3.3 / 4096 (RAW is accumulated over OVERSAMPLENR samples) +// T = 27 - ((RAW / OVERSAMPLENR) * 3.3 / 4096 - 0.706) / 0.001721 +// Simplified: T = 437.423 - (RAW / OVERSAMPLENR) * 0.46875 + +#define TEMP_SOC_SENSOR(RAW) (437.423f - ((RAW) / OVERSAMPLENR) * 0.46875f) diff --git a/Marlin/src/HAL/RP2040/u8g/LCD_defines.h b/Marlin/src/HAL/RP2040/u8g/LCD_defines.h new file mode 100644 index 0000000000..acdd94b477 --- /dev/null +++ b/Marlin/src/HAL/RP2040/u8g/LCD_defines.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 + +/** + * RP2040 LCD-specific defines + */ +uint8_t u8g_com_rp2040_ssd_i2c_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); // u8g_com_rp2040_ssd_i2c.cpp +#define U8G_COM_SSD_I2C_HAL u8g_com_rp2040_ssd_i2c_fn diff --git a/Marlin/src/HAL/RP2040/u8g/u8g_com_rp2040_ssd_i2c.cpp b/Marlin/src/HAL/RP2040/u8g/u8g_com_rp2040_ssd_i2c.cpp new file mode 100644 index 0000000000..ea42bf190d --- /dev/null +++ b/Marlin/src/HAL/RP2040/u8g/u8g_com_rp2040_ssd_i2c.cpp @@ -0,0 +1,108 @@ +/** + * 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 . + * + */ + +/** + * 2-Wire I2C COM Driver + * + * Handles Hardware I2C on valid pin combinations. + * Wire library is used for Hardware I2C. + * + * Hardware I2C uses pins defined in pins_arduino.h. + */ + +#ifdef __PLAT_RP2040__ + +#include "../../../inc/MarlinConfig.h" + +#if HAS_U8GLIB_I2C_OLED + +#include + +#include +#ifndef MASTER_ADDRESS + #define MASTER_ADDRESS 0x01 +#endif + +/** + * BUFFER_LENGTH is defined in libraries\Wire\utility\WireBase.h + * Default value is 32 + * Increase this value to 144 to send U8G_COM_MSG_WRITE_SEQ in single block + */ +#ifndef BUFFER_LENGTH + #define BUFFER_LENGTH 32 +#endif +#if BUFFER_LENGTH > 144 + #error "BUFFER_LENGTH should not be greater than 144." +#endif +#define I2C_MAX_LENGTH (BUFFER_LENGTH - 1) + +uint8_t u8g_com_rp2040_ssd_i2c_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) { + + // Hardware I2C flag + //static bool i2c_initialized = false; // Flag to only run init/linking code once + //if (!i2c_initialized) { // Init runtime linkages + // i2c_initialized = true; // Only do this once + //} + + static uint8_t control; + // Use the global Wire instance (already initialized with correct pins for RP2040) + switch (msg) { + case U8G_COM_MSG_INIT: + Wire.setClock(400000); + // Wire already initialized in MarlinUI::init(), no need to call begin() again + break; + + case U8G_COM_MSG_ADDRESS: // Define cmd (arg_val = 0) or data mode (arg_val = 1) + control = arg_val ? 0x40 : 0x00; + break; + + case U8G_COM_MSG_WRITE_BYTE: + ::Wire.beginTransmission(0x3C); + ::Wire.write(control); + ::Wire.write(arg_val); + ::Wire.endTransmission(); + break; + + case U8G_COM_MSG_WRITE_SEQ: { + uint8_t* dataptr = (uint8_t*)arg_ptr; + while (arg_val > 0) { + ::Wire.beginTransmission(0x3C); + ::Wire.write(control); + if (arg_val <= I2C_MAX_LENGTH) { + ::Wire.write(dataptr, arg_val); + arg_val = 0; + } + else { + ::Wire.write(dataptr, I2C_MAX_LENGTH); + arg_val -= I2C_MAX_LENGTH; + dataptr += I2C_MAX_LENGTH; + } + ::Wire.endTransmission(); + } + break; + } + } + return 1; +} + +#endif // HAS_U8GLIB_I2C_OLED +#endif // __PLAT_RP2040__ diff --git a/Marlin/src/HAL/STM32/pinsDebug.h b/Marlin/src/HAL/STM32/pinsDebug.h index b14c9c721c..89e2514af0 100644 --- a/Marlin/src/HAL/STM32/pinsDebug.h +++ b/Marlin/src/HAL/STM32/pinsDebug.h @@ -136,10 +136,8 @@ const XrefInfo pin_xref[] PROGMEM = { #define printPinNumber(Q) #define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0) #define digitalPinToAnalogIndex(P) -1 // will report analog pin number in the print port routine - -// x is a variable used to search pin_array -#define getPinIsDigitalByIndex(x) ((bool) pin_array[x].is_digital) -#define getPinByIndex(x) ((pin_t) pin_array[x].pin) +#define getPinIsDigitalByIndex(x) bool(pin_array[x].is_digital) +#define getPinByIndex(x) pin_t(pin_array[x].pin) #define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) #define MULTI_NAME_PAD 33 // space needed to be pretty if not first name assigned to a pin @@ -229,8 +227,7 @@ void printPinPort(const pin_t pin) { calc_p -= NUM_ANALOG_FIRST; if (calc_p > 7) calc_p += 8; } - SERIAL_ECHOPGM(" M42 P", calc_p); - SERIAL_CHAR(' '); + SERIAL_ECHO(F(" M42 P"), calc_p, C(' ')); if (calc_p < 100) { SERIAL_CHAR(' '); if (calc_p < 10) diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index f22c9fd1f1..6c51cb01a4 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -578,7 +578,8 @@ // #define BOARD_RP2040 6200 // Generic RP2040 Test board -#define BOARD_BTT_SKR_PICO 6201 // BigTreeTech SKR Pico 1.x +#define BOARD_RASPBERRY_PI_PICO 6201 // Raspberry Pi Pico +#define BOARD_BTT_SKR_PICO 6202 // BigTreeTech SKR Pico 1.x // // Custom board diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index f4d4c28fa7..8a6d18dc2d 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -260,7 +260,11 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; void MarlinUI::init() { #if HAS_U8GLIB_I2C_OLED && PINS_EXIST(I2C_SCL, I2C_SDA) && DISABLED(SOFT_I2C_EEPROM) - Wire.begin(uint8_t(I2C_SDA_PIN), uint8_t(I2C_SCL_PIN)); + #ifdef TARGET_RP2040 + Wire.begin(); // RP2040 MbedI2C uses pins configured in pins_arduino.h + #else + Wire.begin(uint8_t(I2C_SDA_PIN), uint8_t(I2C_SCL_PIN)); + #endif #endif init_lcd(); diff --git a/Marlin/src/pins/mega/pins_GT2560_V3.h b/Marlin/src/pins/mega/pins_GT2560_V3.h index ae4614eedd..81774006df 100644 --- a/Marlin/src/pins/mega/pins_GT2560_V3.h +++ b/Marlin/src/pins/mega/pins_GT2560_V3.h @@ -162,8 +162,9 @@ #endif // -// LCD Controller +// LCD / Controller // + #define BEEPER_PIN 18 #if ENABLED(YHCB2004) diff --git a/Marlin/src/pins/mega/pins_INTAMSYS40.h b/Marlin/src/pins/mega/pins_INTAMSYS40.h index 83a77ec98c..cfb4d0186e 100644 --- a/Marlin/src/pins/mega/pins_INTAMSYS40.h +++ b/Marlin/src/pins/mega/pins_INTAMSYS40.h @@ -116,7 +116,7 @@ #endif // -// LCD Controller +// LCD / Controller // #define BEEPER_PIN 18 diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index e73a00ae81..56c4b78dff 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -949,6 +949,8 @@ #elif MB(RP2040) #include "rp2040/pins_RP2040.h" // RP2040 env:RP2040 +#elif MB(RASPBERRY_PI_PICO) + #include "rp2040/pins_RASPBERRY_PI_PICO.h" // RP2040 env:RP2040 #elif MB(BTT_SKR_PICO) #include "rp2040/pins_BTT_SKR_Pico.h" // RP2040 env:SKR_Pico env:SKR_Pico_UART diff --git a/Marlin/src/pins/rp2040/pins_RASPBERRY_PI_PICO.h b/Marlin/src/pins/rp2040/pins_RASPBERRY_PI_PICO.h new file mode 100644 index 0000000000..daede9f560 --- /dev/null +++ b/Marlin/src/pins/rp2040/pins_RASPBERRY_PI_PICO.h @@ -0,0 +1,171 @@ +/** + * 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 "env_validate.h" + +#define BOARD_INFO_NAME "Pi Pico" +#define DEFAULT_MACHINE_NAME "Pi Pico" + +#ifndef MARLIN_EEPROM_SIZE + #define MARLIN_EEPROM_SIZE 0x1000U // 4K + #define FLASH_EEPROM_EMULATION +#endif + +// +// Limit Switches +// +#define X_STOP_PIN 0 // GP0 +#define Y_STOP_PIN 1 // GP1 +#define Z_STOP_PIN 2 // GP2 + +// +// Steppers +// +#define X_STEP_PIN 3 // GP3 +#define X_DIR_PIN 6 // GP6 +#define X_ENABLE_PIN 7 // GP7 + +#define Y_STEP_PIN 8 // GP8 +#define Y_DIR_PIN 9 // GP9 +#define Y_ENABLE_PIN X_ENABLE_PIN + +#define Z_STEP_PIN 10 // GP10 +#define Z_DIR_PIN 11 // GP11 +#define Z_ENABLE_PIN X_ENABLE_PIN + +#define E0_STEP_PIN 12 // GP12 +#define E0_DIR_PIN 13 // GP13 +#define E0_ENABLE_PIN X_ENABLE_PIN + +// +// Heaters / Fans +// +#define HEATER_0_PIN 14 // GP14 +#define HEATER_BED_PIN 15 // GP15 +#define FAN0_PIN 28 // GP28 + +// +// Temperature Sensors +// +#define TEMP_0_PIN A0 // GP26 - Analog Input +#define TEMP_BED_PIN A1 // GP27 - Analog Input + +// +// Misc. Functions +// +#define LED_PIN 25 // GP25 + +// +// SD Card +// +#define SD_DETECT_PIN -1 // No pins left +#define SDCARD_CONNECTION ONBOARD +#define SD_SS_PIN 17 // GP17 - SPI0_CS for SD card chip select + +// +// LCD / Controller +// + +#if ENABLED(U8GLIB_SSD1306) + #if !IS_ULTIPANEL + #error "Add '#define IS_ULTIPANEL 1' to Configuration.h to enable Marlin UI menus and encoder support." + #endif + #if IS_NEWPANEL + #define BTN_EN1 20 // GP20 - Encoder A phase + #define BTN_EN2 21 // GP21 - Encoder B phase + #define BTN_ENC 22 // GP22 - Encoder push button + #endif + + #define ALTERNATIVE_LCD // Use default hardware I2C port +#endif // U8GLIB_SSD1306 + +/* +┌───────────────────────────────────────────────────────────────────────────────────────────────────────────┐ +│ RASPBERRY PI PICO - PHYSICAL PIN MAPPING │ +├──────────────┬───────────┬───────────┬───────────┬───────────┬────────────────────────────────────────────┤ +│ Physical Pin │ GPIO │ ALT0 │ ALT1 │ ALT2 │ Marlin Usage │ +├──────────────┼───────────┼───────────┼───────────┼───────────┼────────────────────────────────────────────┤ +│ 1 │ GP0 │ I2C0_SDA │ SPI0_MISO │ UART0_TX │ X_STOP_PIN │ +│ 2 │ GP1 │ I2C0_SCL │ SPI0_CS │ UART0_RX │ Y_STOP_PIN │ +│ 3 │ GND │ │ │ │ │ +│ 4 │ GP2 │ I2C1_SDA │ SPI0_SCK │ │ Z_STOP_PIN │ +│ 5 │ GP3 │ I2C1_SCL │ SPI0_MOSI │ │ X_STEP_PIN │ +│ 6 │ GP4 │ I2C0_SDA │ SPI0_MISO │ UART1_TX │ SDA_PIN │ +│ 7 │ GP5 │ I2C0_SCL │ SPI0_CS │ UART1_RX │ SCL_PIN │ +│ 8 │ GND │ │ │ │ │ +│ 9 │ GP6 │ I2C1_SDA │ SPI0_SCK │ │ X_DIR_PIN │ +│ 10 │ GP7 │ I2C1_SCL │ SPI0_MOSI │ │ X_ENABLE_PIN │ +│ 11 │ GP8 │ I2C0_SDA │ SPI1_MISO │ UART1_TX │ Y_STEP_PIN │ +│ 12 │ GP9 │ I2C0_SCL │ SPI1_CS │ UART1_RX │ Y_DIR_PIN │ +│ 13 │ GND │ │ │ │ │ +│ 14 │ GP10 │ I2C1_SDA │ SPI1_SCK │ │ Z_STEP_PIN │ +│ 15 │ GP11 │ I2C1_SCL │ SPI1_MOSI │ │ Z_DIR_PIN │ +│ 16 │ GP12 │ I2C0_SDA │ SPI1_MISO │ UART0_TX │ E0_STEP_PIN │ +│ 17 │ GP13 │ I2C0_SCL │ SPI1_CS │ UART0_RX │ E0_DIR_PIN │ +│ 18 │ GND │ │ │ │ │ +│ 19 │ GP14 │ I2C1_SDA │ SPI1_SCK │ │ HEATER_0_PIN │ +│ 20 │ GP15 │ I2C1_SCL │ SPI1_MOSI │ │ HEATER_BED_PIN │ +│ 21 │ GP16 │ I2C0_SDA │ SPI0_MISO │ UART0_TX │ SD_MISO_PIN │ +│ 22 │ GP17 │ I2C0_SCL │ SPI0_CS │ UART0_RX │ SD_SS_PIN │ +│ 23 │ GND │ │ │ │ │ +│ 24 │ GP18 │ I2C1_SDA │ SPI0_SCK │ │ SD_SCK_PIN │ +│ 25 │ GP19 │ I2C1_SCL │ SPI0_MOSI │ │ SD_MOSI_PIN │ +│ 26 │ GP20 │ I2C0_SDA │ │ │ BTN_EN1 (Encoder A) │ +│ 27 │ GP21 │ I2C0_SCL │ │ │ BTN_EN2 (Encoder B) │ +│ 28 │ GND │ │ │ │ │ +│ 29 │ GP22 │ │ │ │ BTN_ENC (Encoder Button) │ +│ 30 │ RUN │ │ │ │ Reset (Active Low) │ +│ 31 │ GP26 │ ADC0 │ I2C1_SDA │ │ TEMP_0_PIN (A0) │ +│ 32 │ GP27 │ ADC1 │ I2C1_SCL │ │ TEMP_BED_PIN (A1) │ +│ 33 │ GND │ │ │ │ │ +│ 34 │ GP28 │ ADC2 │ │ │ FAN0_PIN │ +│ 35 │ ADC_VREF│ │ │ │ ADC Reference Voltage │ +│ 36 │ 3V3 │ │ │ │ 3.3V Power Output │ +│ 37 │ 3V3_EN │ │ │ │ 3.3V Enable (Active High) │ +│ 38 │ GND │ │ │ │ │ +│ 39 │ VSYS │ │ │ │ System Voltage Input (1.8-5.5V) │ +│ 40 │ VBUS │ │ │ │ USB Bus Voltage (5V when USB connected) │ +├──────────────┴───────────┴───────────┴───────────┴───────────┴────────────────────────────────────────────┤ +│ Special pin notes for Raspberry Pi Pico │ +├───────────────────────────────────────────────────────────────────────────────────────────────────────────┤ +│ • GP23 OP Controls the on-board SMPS Power Save pin. Should not be used for other purposes. │ +│ • GP24 IP VBUS sense - high if VBUS is present, else low. Should not be used for other purposes. │ +│ • GP25 OP Connected to user LED. Can be used with board modifications, is not broken out. │ +│ • GP29 IP Used in ADC mode (ADC3) to measure VSYS/3. Should not be used for other purposes. │ +│ • ADC4 (Internal) is connected to the chip's internal temperature sensor. │ +├───────────────────────────────────────────────────────────────────────────────────────────────────────────┤ +│ Marlin pin notes │ +├───────────────────────────────────────────────────────────────────────────────────────────────────────────┤ +│ Shared enable pins: │ +│ • GP7: X_ENABLE_PIN. All stepper drivers use a shared single enable pin X_ENABLE_PIN for pin conservation │ +│ │ +│ Hardware I2C and SPI configuration: │ +│ These are hardcoded in: │ +│ .platformio/packages/framework-arduino-mbed/variants/RASPBERRY_RASPBERRY_PI_PICO/pins_arduino.h │ +│ • GP4: SDA default: "#define PIN_WIRE_SDA (4u)" │ +│ • GP5: SCL default: "#define PIN_WIRE_SCL (5u)" │ +│ • GP16: MISO default: "#define PIN_SPI_MISO (16u)" │ +│ • GP18: SCK default: "#define PIN_SPI_SCK (18u)" │ +│ • GP19: MOSI default: "#define PIN_SPI_MOSI (19u)" │ +└───────────────────────────────────────────────────────────────────────────────────────────────────────────┘ +*/ diff --git a/Marlin/src/pins/rp2040/pins_RP2040.h b/Marlin/src/pins/rp2040/pins_RP2040.h index 6a4e54f0bd..95de85b4bf 100644 --- a/Marlin/src/pins/rp2040/pins_RP2040.h +++ b/Marlin/src/pins/rp2040/pins_RP2040.h @@ -89,10 +89,7 @@ #define TEMP_2_PIN A2 // Analog Input #define TEMP_BED_PIN A1 // Analog Input -#define TEMP_MCU HAL_ADC_MCU_TEMP_DUMMY_PIN // this is a flag value, don´t change - #define TEMP_CHAMBER_PIN TEMP_1_PIN -#define TEMP_BOARD_PIN TEMP_MCU // SPI for MAX Thermocouple #if !HAS_MEDIA @@ -560,3 +557,28 @@ #endif // IS_NEWPANEL #endif // HAS_WIRED_LCD + +/* +┌───────────────────────────────────────────────────────────────────────────────────────────────────────────────┐ +│ PIN CONFLICTS and ERRORS │ +├───────────────────────────────────────────────────────────────────────────────────────────────────────────────┤ +│ │ +│ VIRTUAL PINS - NOT REAL GPIO: │ +│ • GP40+: E_MUX pins, TMC_SW pins are virtual/extended pins, not physical RP2040 GPIO │ +│ • GP64, GP66: TMC Software SPI pins - these don't exist on RP2040 hardware │ +│ │ +│ MULTIPLE ASSIGNMENTS - REVIEW NEEDED: │ +│ • GP4: Z_DIR_PIN + Z_CS_PIN + SPINDLE_LASER_ENA_PIN (conditional conflicts) │ +│ • GP5: Z_STEP_PIN + FILWIDTH_PIN + SPINDLE_DIR_PIN (conditional conflicts) │ +│ • GP6: CASE_LIGHT_PIN + SPINDLE_LASER_PWM_PIN (conditional - both PWM) │ +│ • GP21: FAN1_PIN + FIL_RUNOUT_PIN (may conflict if both features enabled) │ +│ • GP29: ALL assigned to same pin: │ +│ - X_STEP_PIN, X_DIR_PIN, X_ENABLE_PIN, X_CS_PIN (4 pins) │ +│ - Y_STEP_PIN, Y_DIR_PIN, Y_ENABLE_PIN, Y_CS_PIN (4 pins) │ +│ - E0_STEP_PIN, E0_DIR_PIN, E0_ENABLE_PIN, E0_CS_PIN (4 pins) │ +│ - LCD_PINS_EN (CR10_STOCKDISPLAY), LCD_PINS_D7, DOGLCD_CS (ELB_FULL_GRAPHIC_CONTROLLER) │ +│ → 12+ critical functions sharing ONE GPIO - PRINTER CANNOT FUNCTION! │ +└───────────────────────────────────────────────────────────────────────────────────────────────────────────────┘ +*/ + +#error "Pin assignments for this board are not for practical use. See comments in pins_RP2040.h" diff --git a/Marlin/src/sd/SdBaseFile.h b/Marlin/src/sd/SdBaseFile.h index dc31e8492d..e2dbf489f1 100644 --- a/Marlin/src/sd/SdBaseFile.h +++ b/Marlin/src/sd/SdBaseFile.h @@ -46,6 +46,19 @@ struct filepos_t { filepos_t() : position(0), cluster(0) {} }; +// Avoid conflict with RP2040 / newlib fcntl.h +#ifdef __PLAT_RP2040__ + #undef O_RDONLY + #undef O_WRONLY + #undef O_RDWR + #undef O_ACCMODE + #undef O_APPEND + #undef O_SYNC + #undef O_TRUNC + #undef O_CREAT + #undef O_EXCL +#endif + // use the gnu style oflag in open() uint8_t const O_READ = 0x01, // open() oflag for reading O_RDONLY = O_READ, // open() oflag - same as O_IN diff --git a/Marlin/src/sd/SdFatStructs.h b/Marlin/src/sd/SdFatStructs.h index b3f94b57a0..bacff4e1c0 100644 --- a/Marlin/src/sd/SdFatStructs.h +++ b/Marlin/src/sd/SdFatStructs.h @@ -32,7 +32,9 @@ #include -#define PACKED __attribute__((__packed__)) +#ifndef PACKED + #define PACKED __attribute__((__packed__)) +#endif /** * mostly from Microsoft document fatgen103.doc diff --git a/ini/raspberrypi.ini b/ini/raspberrypi.ini index 059f4d1821..2ee74631f9 100644 --- a/ini/raspberrypi.ini +++ b/ini/raspberrypi.ini @@ -16,12 +16,13 @@ build_src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} arduino-libraries/Servo https://github.com/pkElectronics/SoftwareSerialM#master + #adafruit/Adafruit TinyUSB Library #lvgl/lvgl@^8.1.0 lib_ignore = WiFi -build_flags = ${common.build_flags} -D__PLAT_RP2040__ -DPLATFORM_M997_SUPPORT -Wno-expansion-to-defined -Wno-vla -Wno-ignored-qualifiers +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 -custom_marlin.HAS_SD_HOST_DRIVE = tinyusb +#custom_marlin.HAS_SD_HOST_DRIVE = tinyusb [env:RP2040-alt] extends = env:RP2040 From ac0fc603aed0fcd3d77a15d8d4cc8e6e3037ce56 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 28 Nov 2025 00:53:52 +0000 Subject: [PATCH 03/47] [cron] Bump distribution date (2025-11-28) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 1cf1b23558..d9a83e4abe 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-27" +//#define STRING_DISTRIBUTION_DATE "2025-11-28" /** * 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 e768d28ce1..a0b4e56863 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-27" + #define STRING_DISTRIBUTION_DATE "2025-11-28" #endif /** From 12ac09499258c299feb14d986e9c728569b69140 Mon Sep 17 00:00:00 2001 From: Vovodroid Date: Fri, 28 Nov 2025 03:27:48 +0200 Subject: [PATCH 04/47] =?UTF-8?q?=E2=9C=A8=20PLR=5FHEAT=5FBED=5FON=5FREBOO?= =?UTF-8?q?T=20(#26691)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 2 ++ Marlin/src/feature/powerloss.cpp | 15 +++++++++++++++ Marlin/src/feature/powerloss.h | 5 ++++- Marlin/src/gcode/feature/powerloss/M1000.cpp | 3 +++ buildroot/tests/rambo | 2 ++ 5 files changed, 26 insertions(+), 1 deletion(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index c5ed503b4c..57c8305e04 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1795,6 +1795,8 @@ //#define POWER_LOSS_RECOVERY #if ENABLED(POWER_LOSS_RECOVERY) #define PLR_ENABLED_DEFAULT false // Power-Loss Recovery enabled by default. (Set with 'M413 Sn' & M500) + //#define PLR_HEAT_BED_ON_REBOOT // Heat up bed immediately on reboot to mitigate object detaching/warping. + //#define PLR_HEAT_BED_EXTRA 0 // (°C) Relative increase of bed temperature for better adhesion (limited by max temp). //#define PLR_BED_THRESHOLD BED_MAXTEMP // (°C) Skip user confirmation at or above this bed temperature (0 to disable) //#define POWER_LOSS_PIN 44 // Pin to detect power-loss. Set to -1 to disable default pin on boards without module, or comment to use board default. diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp index bb4ca0dbde..6925ed7a34 100644 --- a/Marlin/src/feature/powerloss.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -141,6 +141,14 @@ bool PrintJobRecovery::check() { return success; } +/** + * Cancel recovery + */ +void PrintJobRecovery::cancel() { + TERN_(PLR_HEAT_BED_ON_REBOOT, set_bed_temp(false)); + purge(); +} + /** * Delete the recovery file and clear the recovery data */ @@ -366,6 +374,13 @@ void PrintJobRecovery::write() { if (!file.close()) DEBUG_ECHOLNPGM("Power-loss file close failed."); } +#if ENABLED(PLR_HEAT_BED_ON_REBOOT) + // Set bed temperature and wait. Called from M1000 to resume bed heating. + void PrintJobRecovery::set_bed_temp(const bool on) { + PROCESS_SUBCOMMANDS_NOW(TS(F("M190S"), on ? info.target_temperature_bed + PLR_HEAT_BED_EXTRA : 0)); + } +#endif + /** * Resume the saved print job */ diff --git a/Marlin/src/feature/powerloss.h b/Marlin/src/feature/powerloss.h index eceb862779..0fcd167d78 100644 --- a/Marlin/src/feature/powerloss.h +++ b/Marlin/src/feature/powerloss.h @@ -201,10 +201,13 @@ class PrintJobRecovery { static void close() { file.close(); } static bool check(); + #if ENABLED(PLR_HEAT_BED_ON_REBOOT) + static void set_bed_temp(const bool turn_on); + #endif static void resume(); static void purge(); - static void cancel() { purge(); } + static void cancel(); static void load(); static void save(const bool force=ENABLED(SAVE_EACH_CMD_MODE), const float zraise=POWER_LOSS_ZRAISE, const bool raised=false); diff --git a/Marlin/src/gcode/feature/powerloss/M1000.cpp b/Marlin/src/gcode/feature/powerloss/M1000.cpp index c70bf7667f..c85817cd3e 100644 --- a/Marlin/src/gcode/feature/powerloss/M1000.cpp +++ b/Marlin/src/gcode/feature/powerloss/M1000.cpp @@ -72,6 +72,9 @@ void GcodeSuite::M1000() { const bool force_resume = TERN0(HAS_PLR_BED_THRESHOLD, recovery.bed_temp_threshold && (thermalManager.degBed() >= recovery.bed_temp_threshold)); if (!force_resume && parser.seen_test('S')) { + + TERN_(PLR_HEAT_BED_ON_REBOOT, recovery.set_bed_temp(true)); + #if HAS_MARLINUI_MENU ui.goto_screen(menu_job_recovery); #elif ENABLED(EXTENSIBLE_UI) diff --git a/buildroot/tests/rambo b/buildroot/tests/rambo index 06037a838f..6ebb26a177 100755 --- a/buildroot/tests/rambo +++ b/buildroot/tests/rambo @@ -14,6 +14,7 @@ opt_set MOTHERBOARD BOARD_RAMBO \ EXTRUDERS 2 TEMP_SENSOR_0 -2 TEMP_SENSOR_1 1 TEMP_SENSOR_BED 2 \ TEMP_SENSOR_PROBE 1 TEMP_PROBE_PIN 12 \ TEMP_SENSOR_CHAMBER 3 TEMP_CHAMBER_PIN 3 HEATER_CHAMBER_PIN 45 \ + PLR_HEAT_BED_EXTRA 5 PLR_BED_THRESHOLD 60 \ GRID_MAX_POINTS_X 16 BACKLASH_MEASUREMENT_FEEDRATE 600 \ AUTO_POWER_E_TEMP 80 FANMUX0_PIN 53 FIL_MOTION1_PIN 45 opt_disable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN USE_WATCHDOG @@ -34,6 +35,7 @@ opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER LCD_PROGRESS_BAR LCD_PROGRESS_BAR_TE FWRETRACT ARC_P_CIRCLES CNC_WORKSPACE_PLANES CNC_COORDINATE_SYSTEMS \ PSU_CONTROL LED_POWEROFF_TIMEOUT PS_OFF_CONFIRM PS_OFF_SOUND POWER_OFF_WAIT_FOR_COOLDOWN \ POWER_LOSS_RECOVERY POWER_LOSS_PIN POWER_LOSS_STATE POWER_LOSS_RECOVER_ZHOME POWER_LOSS_ZHOME_POS \ + PLR_HEAT_BED_ON_REBOOT \ SLOW_PWM_HEATERS THERMAL_PROTECTION_CHAMBER LIN_ADVANCE ADVANCE_K_EXTRA \ HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT HOST_STATUS_NOTIFICATIONS PINS_DEBUGGING MAX7219_DEBUG M114_DETAIL opt_add DEBUG_POWER_LOSS_RECOVERY From d061e6dbd65e6f601b5c90b5c4a3e432604bcb71 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 28 Nov 2025 13:27:33 -0600 Subject: [PATCH 05/47] =?UTF-8?q?=F0=9F=93=9D=20Motion=20comments?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit w/r/t https://github.com/MarlinFirmware/Marlin/issues/27918#issuecomment-3145339116 --- Marlin/src/module/planner.cpp | 2 ++ Marlin/src/module/planner.h | 6 ++++-- Marlin/src/module/stepper.cpp | 2 +- 3 files changed, 7 insertions(+), 3 deletions(-) diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 7bb078be16..acd576c9b3 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -2542,6 +2542,8 @@ bool Planner::_populate_block( xyze_float_t junction_unit_vec = unit_vec - prev_unit_vec; normalize_junction_vector(junction_unit_vec); + // TODO: Don't limit acceleration on axes with very small distance relative to others + // See https://github.com/MarlinFirmware/Marlin/issues/27918#issuecomment-3145339116 const float junction_acceleration = limit_value_by_axis_maximum(block->acceleration, junction_unit_vec); if (TERN0(HINTS_CURVE_RADIUS, hints.curve_radius)) { diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index d8d0e053e7..891357dbe3 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -1157,12 +1157,14 @@ class Planner { vector *= RSQRT(magnitude_sq); } + // max_value is block->acceleration FORCE_INLINE static float limit_value_by_axis_maximum(const float max_value, xyze_float_t &unit_vec) { float limit_value = max_value; LOOP_LOGICAL_AXES(idx) { if (unit_vec[idx]) { - if (limit_value * ABS(unit_vec[idx]) > settings.max_acceleration_mm_per_s2[idx]) - limit_value = ABS(settings.max_acceleration_mm_per_s2[idx] / unit_vec[idx]); + const uint32_t abs_vec = ABS(unit_vec[idx]); + if (limit_value * abs_vec > settings.max_acceleration_mm_per_s2[idx]) + limit_value = settings.max_acceleration_mm_per_s2[idx] / abs_vec; } } return limit_value; diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index ca6f027ade..8b3a60e048 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -253,7 +253,7 @@ uint32_t Stepper::advance_divisor = 0, #endif /** - * Standard Motion Non-linear Exttrusion state + * Standard Motion Non-linear Extrusion state */ #if ENABLED(NONLINEAR_EXTRUSION) nonlinear_t Stepper::ne; // Initialized by settings.load From 578ee04243631e4978400648aa66a392c8c2b525 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 29 Nov 2025 00:31:12 +0000 Subject: [PATCH 06/47] [cron] Bump distribution date (2025-11-29) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index d9a83e4abe..b42ab23151 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-28" +//#define STRING_DISTRIBUTION_DATE "2025-11-29" /** * 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 a0b4e56863..9e1a60feeb 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-28" + #define STRING_DISTRIBUTION_DATE "2025-11-29" #endif /** From 58bce3781eb7d9884550a6b595d203adb0b783ef Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 28 Nov 2025 18:53:07 -0600 Subject: [PATCH 07/47] =?UTF-8?q?=F0=9F=93=9D=20Usage=20for=20run=5Ftests?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/bin/run_tests | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/buildroot/bin/run_tests b/buildroot/bin/run_tests index 9a03be3cc7..206325417c 100755 --- a/buildroot/bin/run_tests +++ b/buildroot/bin/run_tests @@ -1,6 +1,13 @@ #!/usr/bin/env bash # -# run_tests +# buildroot/bin/run_tests +# Used by Makefile tests-single-local, tests-single-ci, tests-all-local +# +# Usage: +# run_tests path target "[only this title]" +# +# With make: +# make tests-single-local TEST_TARGET=mega2560 ONLY_TEST=2 # HERE="$( cd "$(dirname "${BASH_SOURCE[0]}")" ; pwd -P )" TESTS="$HERE/../tests" From 7b70e39ff6ea753190def28b3986268878de11e0 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 28 Nov 2025 19:57:52 -0600 Subject: [PATCH 08/47] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Clari?= =?UTF-8?q?fy=20PID=20tuning=20macros?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/planner.cpp | 14 +---- Marlin/src/module/temperature.cpp | 101 +++++++++++++----------------- 2 files changed, 47 insertions(+), 68 deletions(-) diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index acd576c9b3..59c7c3638b 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -2519,18 +2519,8 @@ bool Planner::_populate_block( if (moves_queued && !UNEAR_ZERO(previous_nominal_speed)) { // Compute cosine of angle between previous and current path. (prev_unit_vec is negative) // NOTE: Max junction velocity is computed without sin() or acos() by trig half angle identity. - float junction_cos_theta = LOGICAL_AXIS_GANG( - + (-prev_unit_vec.e * unit_vec.e), - + (-prev_unit_vec.x * unit_vec.x), - + (-prev_unit_vec.y * unit_vec.y), - + (-prev_unit_vec.z * unit_vec.z), - + (-prev_unit_vec.i * unit_vec.i), - + (-prev_unit_vec.j * unit_vec.j), - + (-prev_unit_vec.k * unit_vec.k), - + (-prev_unit_vec.u * unit_vec.u), - + (-prev_unit_vec.v * unit_vec.v), - + (-prev_unit_vec.w * unit_vec.w) - ); + #define _UNIT_VEC(A) + (-prev_unit_vec.A * unit_vec.A) + float junction_cos_theta = LOGICAL_AXIS_MAP(_UNIT_VEC); // NOTE: Computed without any expensive trig, sin() or acos(), by trig half angle identity of cos(theta). if (junction_cos_theta > 0.999999f) { diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 96ea110963..964e473361 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -824,41 +824,34 @@ void Temperature::factory_reset() { raw_pid_t tune_pid = { 0, 0, 0 }; celsius_float_t maxT = 0, minT = 10000; - const bool isbed = (heater_id == H_BED), - ischamber = (heater_id == H_CHAMBER); + const bool isbed = TERN0(PIDTEMPBED, heater_id == H_BED), + ischamber = TERN0(PIDTEMPCHAMBER, heater_id == H_CHAMBER); - #if ENABLED(PIDTEMPCHAMBER) - #define C_TERN(T,A,B) ((T) ? (A) : (B)) - #else - #define C_TERN(T,A,B) (B) - #endif - #if ENABLED(PIDTEMPBED) - #define B_TERN(T,A,B) ((T) ? (A) : (B)) - #else - #define B_TERN(T,A,B) (B) - #endif - #define GHV(C,B,H) C_TERN(ischamber, C, B_TERN(isbed, B, H)) - #define SHV(V) C_TERN(ischamber, temp_chamber.soft_pwm_amount = V, B_TERN(isbed, temp_bed.soft_pwm_amount = V, temp_hotend[heater_id].soft_pwm_amount = V)) - #define ONHEATINGSTART() C_TERN(ischamber, printerEventLEDs.onChamberHeatingStart(), B_TERN(isbed, printerEventLEDs.onBedHeatingStart(), printerEventLEDs.onHotendHeatingStart())) - #define ONHEATING(S,C,T) C_TERN(ischamber, printerEventLEDs.onChamberHeating(S,C,T), B_TERN(isbed, printerEventLEDs.onBedHeating(S,C,T), printerEventLEDs.onHotendHeating(S,C,T))) + // BED TEST ; BED VALUE ; HOTEND VALUE + #define T_BH(T,B,H) TERN(PIDTEMPBED, ((T) ? (B) : (H)), (H)) + // CHAMBER TEST ; CHAMBER VALUE ; T_BH(...) + #define T_CBH(T,C,BH) TERN(PIDTEMPCHAMBER, ((T) ? (C) : (BH)), (BH)) + // CHAMBER VALUE ; BED VALUE ; HOTEND VALUE + #define PER_CBH(C,B,H) T_CBH(ischamber, C, T_BH(isbed, B, H)) + + // Set a field value in the pertinent Temp Monitor + #define SET_CBH(F,V) PER_CBH(temp_chamber.F = V, temp_bed.F = V, temp_hotend[heater_id].F = V) + #define ONHEATINGSTART() PER_CBH(printerEventLEDs.onChamberHeatingStart(), printerEventLEDs.onBedHeatingStart(), printerEventLEDs.onHotendHeatingStart()) + #define ONHEATING(S,C,T) PER_CBH(printerEventLEDs.onChamberHeating(S,C,T), printerEventLEDs.onBedHeating(S,C,T), printerEventLEDs.onHotendHeating(S,C,T)) #define WATCH_PID DISABLED(NO_WATCH_PID_TUNING) && (ALL(WATCH_CHAMBER, PIDTEMPCHAMBER) || ALL(WATCH_BED, PIDTEMPBED) || ALL(WATCH_HOTENDS, PIDTEMP)) - #if WATCH_PID - #if ALL(THERMAL_PROTECTION_CHAMBER, PIDTEMPCHAMBER) - #define C_GTV(T,A,B) ((T) ? (A) : (B)) - #else - #define C_GTV(T,A,B) (B) - #endif - #if ALL(THERMAL_PROTECTION_BED, PIDTEMPBED) - #define B_GTV(T,A,B) ((T) ? (A) : (B)) - #else - #define B_GTV(T,A,B) (B) - #endif - #define GTV(C,B,H) C_GTV(ischamber, C, B_GTV(isbed, B, H)) - const uint16_t watch_temp_period = GTV(WATCH_CHAMBER_TEMP_PERIOD, WATCH_BED_TEMP_PERIOD, WATCH_TEMP_PERIOD); - const uint8_t watch_temp_increase = GTV(WATCH_CHAMBER_TEMP_INCREASE, WATCH_BED_TEMP_INCREASE, WATCH_TEMP_INCREASE); - const celsius_float_t watch_temp_target = celsius_float_t(target - (watch_temp_increase + GTV(TEMP_CHAMBER_HYSTERESIS, TEMP_BED_HYSTERESIS, TEMP_HYSTERESIS) + 1)); + // BED TEST ; BED VALUE ; HOTEND VALUE + #define W_BH(T,B,H) TERN(THERMAL_PROTECTION_BED, T_BH(T,B,H), (H)) + // CHAMBER TEST ; CHAMBER VALUE ; W_BH(...) + #define W_CBH(T,C,BH) TERN(THERMAL_PROTECTION_CHAMBER, T_CBH(T,C,BH), (BH)) + // CHAMBER VALUE ; BED VALUE ; HOTEND VALUE + #define PER_WATCH_CBH(C,B,H) W_CBH(ischamber, C, W_BH(isbed, B, H)) + + const uint16_t watch_temp_period = PER_WATCH_CBH(WATCH_CHAMBER_TEMP_PERIOD, WATCH_BED_TEMP_PERIOD, WATCH_TEMP_PERIOD); + const uint8_t watch_temp_increase = PER_WATCH_CBH(WATCH_CHAMBER_TEMP_INCREASE, WATCH_BED_TEMP_INCREASE, WATCH_TEMP_INCREASE); + const celsius_float_t watch_hysteresis = PER_WATCH_CBH(TEMP_CHAMBER_HYSTERESIS, TEMP_BED_HYSTERESIS, TEMP_HYSTERESIS), + watch_temp_target = celsius_float_t(target - (watch_temp_increase + watch_hysteresis + 1)); millis_t temp_change_ms = next_temp_ms + SEC_TO_MS(watch_temp_period); celsius_float_t next_watch_temp = 0.0; bool heated = false; @@ -866,9 +859,9 @@ void Temperature::factory_reset() { TERN_(HAS_FAN_LOGIC, fan_update_ms = next_temp_ms + fan_update_interval_ms); - TERN_(EXTENSIBLE_UI, ExtUI::onPIDTuning(ischamber ? ExtUI::pidresult_t::PID_CHAMBER_STARTED : isbed ? ExtUI::pidresult_t::PID_BED_STARTED : ExtUI::pidresult_t::PID_STARTED)); + TERN_(EXTENSIBLE_UI, ExtUI::onPIDTuning(PER_CBH(ExtUI::pidresult_t::PID_CHAMBER_STARTED, ExtUI::pidresult_t::PID_BED_STARTED, ExtUI::pidresult_t::PID_STARTED))); - if (target > GHV(CHAMBER_MAX_TARGET, BED_MAX_TARGET, hotend_max_target(heater_id))) { + if (target > PER_CBH(CHAMBER_MAX_TARGET, BED_MAX_TARGET, hotend_max_target(heater_id))) { SERIAL_ECHOPGM(STR_PID_AUTOTUNE); SERIAL_ECHOLNPGM(STR_PID_TEMP_TOO_HIGH); TERN_(EXTENSIBLE_UI, ExtUI::onPIDTuning(ExtUI::pidresult_t::PID_TEMP_TOO_HIGH)); TERN_(HOST_PROMPT_SUPPORT, hostui.notify(GET_TEXT_F(MSG_PID_TEMP_TOO_HIGH))); @@ -880,11 +873,11 @@ void Temperature::factory_reset() { disable_all_heaters(); TERN_(AUTO_POWER_CONTROL, powerManager.power_on()); - long bias = GHV(MAX_CHAMBER_POWER, MAX_BED_POWER, PID_MAX) >> 1, d = bias; - SHV(bias); + long bias = PER_CBH(MAX_CHAMBER_POWER, MAX_BED_POWER, PID_MAX) >> 1, d = bias; + SET_CBH(soft_pwm_amount, bias); #if ENABLED(PRINTER_EVENT_LEDS) - const celsius_float_t start_temp = GHV(degChamber(), degBed(), degHotend(heater_id)); + const celsius_float_t start_temp = PER_CBH(degChamber(), degBed(), degHotend(heater_id)); const LED1Color_t oldcolor = ONHEATINGSTART(); #endif @@ -905,7 +898,7 @@ void Temperature::factory_reset() { if (temp_ready) { // Get the current temperature and constrain it - current_temp = GHV(degChamber(), degBed(), degHotend(heater_id)); + current_temp = PER_CBH(degChamber(), degBed(), degHotend(heater_id)); NOLESS(maxT, current_temp); NOMORE(minT, current_temp); @@ -915,7 +908,7 @@ void Temperature::factory_reset() { if (heating && current_temp > target && ELAPSED(ms, t2, 5000UL)) { heating = false; - SHV((bias - d) >> 1); + SET_CBH(soft_pwm_amount, (bias - d) >> 1); t1 = ms; t_high = t1 - t2; maxT = target; @@ -926,7 +919,7 @@ void Temperature::factory_reset() { t2 = ms; t_low = t2 - t1; if (cycles > 0) { - const long max_pow = GHV(MAX_CHAMBER_POWER, MAX_BED_POWER, PID_MAX); + const long max_pow = PER_CBH(MAX_CHAMBER_POWER, MAX_BED_POWER, PID_MAX); bias += (d * (t_high - t_low)) / (t_low + t_high); LIMIT(bias, 20, max_pow - 20); d = (bias > max_pow >> 1) ? max_pow - 1 - bias : bias; @@ -950,7 +943,7 @@ void Temperature::factory_reset() { SERIAL_ECHOLNPGM(STR_KP, tune_pid.p, STR_KI, tune_pid.i, STR_KD, tune_pid.d); } } - SHV((bias + d) >> 1); + SET_CBH(soft_pwm_amount, (bias + d) >> 1); TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/%i"), GET_TEXT(MSG_PID_CYCLE), cycles, ncycles)); cycles++; minT = target; @@ -1016,7 +1009,7 @@ void Temperature::factory_reset() { TERN_(HOST_PROMPT_SUPPORT, hostui.notify(GET_TEXT_F(MSG_PID_AUTOTUNE_DONE))); #if ANY(PIDTEMPBED, PIDTEMPCHAMBER) - FSTR_P const estring = GHV(F("chamber"), F("bed"), FPSTR(NUL_STR)); + FSTR_P const estring = PER_CBH(F("chamber"), F("bed"), FPSTR(NUL_STR)); say_default_(); SERIAL_ECHOLN(estring, F("Kp "), tune_pid.p); say_default_(); SERIAL_ECHOLN(estring, F("Ki "), tune_pid.i); say_default_(); SERIAL_ECHOLN(estring, F("Kd "), tune_pid.d); @@ -1052,7 +1045,7 @@ void Temperature::factory_reset() { // Use the result? (As with "M303 U1") if (set_result) - GHV(_set_chamber_pid(tune_pid), _set_bed_pid(tune_pid), _set_hotend_pid(heater_id, tune_pid)); + PER_CBH(_set_chamber_pid(tune_pid), _set_bed_pid(tune_pid), _set_hotend_pid(heater_id, tune_pid)); goto EXIT_M303; } @@ -1136,9 +1129,8 @@ void Temperature::factory_reset() { wait_for_heatup = false; #if ENABLED(MPC_AUTOTUNE_DEBUG) - SERIAL_ECHOLNPGM("MPC_autotuner::measure_ambient_temp() Completed"); - SERIAL_ECHOLNPGM("====="); - SERIAL_ECHOLNPGM("ambient_temp ", get_ambient_temp()); + SERIAL_ECHOLNPGM("MPC_autotuner::measure_ambient_temp() Completed\n=====\n" + "ambient_temp ", get_ambient_temp()); #endif return SUCCESS; @@ -1223,11 +1215,8 @@ void Temperature::factory_reset() { #if ENABLED(MPC_AUTOTUNE_DEBUG) SERIAL_ECHOLNPGM("MPC_autotuner::measure_heatup() Completed"); SERIAL_ECHOLNPGM("====="); - SERIAL_ECHOLNPGM("t1_time ", t1_time); - SERIAL_ECHOLNPGM("sample_count ", sample_count); - SERIAL_ECHOLNPGM("sample_distance ", sample_distance); - for (uint8_t i = 0; i < sample_count; i++) - SERIAL_ECHOLNPGM("sample ", i, " : ", temp_samples[i]); + SERIAL_ECHOLNPGM("t1_time ", t1_time, " sample_count ", sample_count, " sample_distance ", sample_distance); + for (uint8_t i = 0; i < sample_count; i++) SERIAL_ECHOLNPGM("sample ", i, " : ", temp_samples[i]); SERIAL_ECHOLNPGM("t1 ", get_sample_1_temp(), " t2 ", get_sample_2_temp(), " t3 ", get_sample_3_temp()); #endif @@ -1390,9 +1379,9 @@ void Temperature::factory_reset() { if (tuning_type == FORCE_DIFFERENTIAL) { #if ENABLED(MPC_AUTOTUNE_DEBUG) - SERIAL_ECHOLNPGM("rate_fastest ", tuner.get_rate_fastest()); - SERIAL_ECHOLNPGM("time_fastest ", tuner.get_time_fastest()); - SERIAL_ECHOLNPGM("temp_fastest ", tuner.get_temp_fastest()); + SERIAL_ECHOLNPGM("Fastest rate=", tuner.get_rate_fastest(), + " time=", tuner.get_time_fastest(), + "temp=", tuner.get_temp_fastest()); #endif // Differential tuning mpc.block_heat_capacity = mpc.heater_power / tuner.get_rate_fastest(); @@ -1435,9 +1424,9 @@ void Temperature::factory_reset() { // Check again: If analytic tuning fails, fall back to differential tuning if (tuning_type == AUTO && (mpc.sensor_responsiveness <= 0 || mpc.block_heat_capacity <= 0)) { #if ENABLED(MPC_AUTOTUNE_DEBUG) - SERIAL_ECHOLNPGM("rate_fastest ", tuner.get_rate_fastest()); - SERIAL_ECHOLNPGM("time_fastest ", tuner.get_time_fastest()); - SERIAL_ECHOLNPGM("temp_fastest ", tuner.get_temp_fastest()); + SERIAL_ECHOLNPGM("Fastest rate=", tuner.get_rate_fastest(), + " time=", tuner.get_time_fastest(), + "temp=", tuner.get_temp_fastest()); #endif tuning_type = FORCE_DIFFERENTIAL; mpc.block_heat_capacity = mpc.heater_power / tuner.get_rate_fastest(); From 3d7f84dbb618314defa615f668c5cd605ad43f9a Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 30 Nov 2025 00:38:07 +0000 Subject: [PATCH 09/47] [cron] Bump distribution date (2025-11-30) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index b42ab23151..e04bcf0334 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-29" +//#define STRING_DISTRIBUTION_DATE "2025-11-30" /** * 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 9e1a60feeb..d97a80ad36 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-29" + #define STRING_DISTRIBUTION_DATE "2025-11-30" #endif /** From ec8a6fc7e2ea02a330953198dc7a639c0430d115 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 30 Nov 2025 08:43:23 -0600 Subject: [PATCH 10/47] =?UTF-8?q?=F0=9F=94=A7=20Uppercase=20PID=20options?= =?UTF-8?q?=20(#27891)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 24 +++++----- Marlin/Configuration_adv.h | 36 +++++++++------ Marlin/src/inc/Changes.h | 12 +++++ Marlin/src/module/stepper.cpp | 4 +- Marlin/src/module/temperature.cpp | 74 +++++++++---------------------- buildroot/tests/BTT_GTR_V1_0 | 2 +- 6 files changed, 72 insertions(+), 80 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 2d816d9e46..ea307f126d 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -718,13 +718,13 @@ #if ENABLED(PID_PARAMS_PER_HOTEND) // Specify up to one value per hotend here, according to your setup. // If there are fewer values, the last one applies to the remaining hotends. - #define DEFAULT_Kp_LIST { 22.20, 22.20 } - #define DEFAULT_Ki_LIST { 1.08, 1.08 } - #define DEFAULT_Kd_LIST { 114.00, 114.00 } + #define DEFAULT_KP_LIST { 22.20, 22.20 } + #define DEFAULT_KI_LIST { 1.08, 1.08 } + #define DEFAULT_KD_LIST { 114.00, 114.00 } #else - #define DEFAULT_Kp 22.20 - #define DEFAULT_Ki 1.08 - #define DEFAULT_Kd 114.00 + #define DEFAULT_KP 22.20 + #define DEFAULT_KI 1.08 + #define DEFAULT_KD 114.00 #endif #else #define BANG_MAX 255 // Limit hotend current while in bang-bang mode; 255=full current @@ -822,9 +822,9 @@ // 120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+) // from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10) - #define DEFAULT_bedKp 10.00 - #define DEFAULT_bedKi 0.023 - #define DEFAULT_bedKd 305.4 + #define DEFAULT_BED_KP 10.00 + #define DEFAULT_BED_KI 0.023 + #define DEFAULT_BED_KD 305.4 // FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles. #else @@ -905,9 +905,9 @@ // Lasko "MyHeat Personal Heater" (200w) modified with a Fotek SSR-10DA to control only the heating element // and placed inside the small Creality printer enclosure tent. - #define DEFAULT_chamberKp 37.04 - #define DEFAULT_chamberKi 1.40 - #define DEFAULT_chamberKd 655.17 + #define DEFAULT_CHAMBER_KP 37.04 + #define DEFAULT_CHAMBER_KI 1.40 + #define DEFAULT_CHAMBER_KD 655.17 // M309 P37.04 I1.04 D655.17 // FIND YOUR OWN: "M303 E-2 C8 S50" to run autotune on the chamber at 50 degreesC for 8 cycles. diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 57c8305e04..f0b685ba19 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -415,14 +415,19 @@ // A well-chosen Kc value should add just enough power to melt the increased material volume. //#define PID_EXTRUSION_SCALING #if ENABLED(PID_EXTRUSION_SCALING) - #define DEFAULT_Kc (100) // heating power = Kc * e_speed #define LPQ_MAX_LEN 50 + #define DEFAULT_KC 100 // heating power = Kc * e_speed + #if ENABLED(PID_PARAMS_PER_HOTEND) + // Specify up to one value per hotend here, according to your setup. + // If there are fewer values, the last one applies to the remaining hotends. + #define DEFAULT_KC_LIST { DEFAULT_KC, DEFAULT_KC } // heating power = Kc * e_speed + #endif #endif /** * Add an additional term to the heater power, proportional to the fan speed. * A well-chosen Kf value should add just enough power to compensate for power-loss from the cooling fan. - * You can either just add a constant compensation with the DEFAULT_Kf value + * You can either just add a constant compensation with the DEFAULT_KF value * or follow the instruction below to get speed-dependent compensation. * * Constant compensation (use only with fan speeds of 0% and 100%) @@ -453,21 +458,26 @@ #if ENABLED(PID_FAN_SCALING_ALTERNATIVE_DEFINITION) // The alternative definition is used for an easier configuration. // Just figure out Kf at full speed (255) and PID_FAN_SCALING_MIN_SPEED. - // DEFAULT_Kf and PID_FAN_SCALING_LIN_FACTOR are calculated accordingly. + // DEFAULT_KF and PID_FAN_SCALING_LIN_FACTOR are calculated accordingly. - #define PID_FAN_SCALING_AT_FULL_SPEED 13.0 //=PID_FAN_SCALING_LIN_FACTOR*255+DEFAULT_Kf - #define PID_FAN_SCALING_AT_MIN_SPEED 6.0 //=PID_FAN_SCALING_LIN_FACTOR*PID_FAN_SCALING_MIN_SPEED+DEFAULT_Kf + #define PID_FAN_SCALING_AT_FULL_SPEED 13.0 //=PID_FAN_SCALING_LIN_FACTOR*255+DEFAULT_KF + #define PID_FAN_SCALING_AT_MIN_SPEED 6.0 //=PID_FAN_SCALING_LIN_FACTOR*PID_FAN_SCALING_MIN_SPEED+DEFAULT_KF #define PID_FAN_SCALING_MIN_SPEED 10.0 // Minimum fan speed at which to enable PID_FAN_SCALING - #define DEFAULT_Kf (255.0*PID_FAN_SCALING_AT_MIN_SPEED-PID_FAN_SCALING_AT_FULL_SPEED*PID_FAN_SCALING_MIN_SPEED)/(255.0-PID_FAN_SCALING_MIN_SPEED) - #define PID_FAN_SCALING_LIN_FACTOR (PID_FAN_SCALING_AT_FULL_SPEED-DEFAULT_Kf)/255.0 + #define DEFAULT_KF (255.0*PID_FAN_SCALING_AT_MIN_SPEED-PID_FAN_SCALING_AT_FULL_SPEED*PID_FAN_SCALING_MIN_SPEED)/(255.0-PID_FAN_SCALING_MIN_SPEED) + #define PID_FAN_SCALING_LIN_FACTOR (PID_FAN_SCALING_AT_FULL_SPEED-DEFAULT_KF)/255.0 #else #define PID_FAN_SCALING_LIN_FACTOR (0) // Power-loss due to cooling = Kf * (fan_speed) - #define DEFAULT_Kf 10 // A constant value added to the PID-tuner + #define DEFAULT_KF 10 // A constant value added to the PID-tuner #define PID_FAN_SCALING_MIN_SPEED 10 // Minimum fan speed at which to enable PID_FAN_SCALING #endif #endif + #if ENABLED(PID_PARAMS_PER_HOTEND) + // Specify up to one value per hotend here, according to your setup. + // If there are fewer values, the last one applies to the remaining hotends. + #define DEFAULT_KF_LIST { DEFAULT_KF, DEFAULT_KF } + #endif #endif /** @@ -486,15 +496,15 @@ #define AUTOTEMP #if ENABLED(AUTOTEMP) #define AUTOTEMP_OLDWEIGHT 0.98 // Factor used to weight previous readings (0.0 < value < 1.0) - #define AUTOTEMP_MIN 210 - #define AUTOTEMP_MAX 250 + #define AUTOTEMP_MIN 210 + #define AUTOTEMP_MAX 250 #define AUTOTEMP_FACTOR 0.1f // Turn on AUTOTEMP on M104/M109 by default using proportions set here //#define AUTOTEMP_PROPORTIONAL #if ENABLED(AUTOTEMP_PROPORTIONAL) - #define AUTOTEMP_MIN_P 0 // (°C) Added to the target temperature - #define AUTOTEMP_MAX_P 5 // (°C) Added to the target temperature - #define AUTOTEMP_FACTOR_P 1 // Apply this F parameter by default (overridden by M104/M109 F) + #define AUTOTEMP_MIN_P 0 // (°C) Added to the target temperature + #define AUTOTEMP_MAX_P 5 // (°C) Added to the target temperature + #define AUTOTEMP_FACTOR_P 1 // Apply this F parameter by default (overridden by M104/M109 F) #endif #endif diff --git a/Marlin/src/inc/Changes.h b/Marlin/src/inc/Changes.h index 2d8fe87863..7b904218bf 100644 --- a/Marlin/src/inc/Changes.h +++ b/Marlin/src/inc/Changes.h @@ -749,6 +749,18 @@ #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." +#elif defined(DEFAULT_Kp_LIST) || defined(DEFAULT_Ki_LIST) || defined(DEFAULT_Kd_LIST) + #error "DEFAULT_Kp_LIST, DEFAULT_Ki_LIST, DEFAULT_Kd_LIST are now (uppercase) DEFAULT_KP_LIST, DEFAULT_KI_LIST, DEFAULT_KD_LIST." +#elif defined(DEFAULT_Kp) || defined(DEFAULT_Ki) || defined(DEFAULT_Kd) + #error "DEFAULT_Kp, DEFAULT_Ki, DEFAULT_Kd are now (uppercase) DEFAULT_KP, DEFAULT_KI, DEFAULT_KD." +#elif defined(DEFAULT_bedKp) || defined(DEFAULT_bedKi) || defined(DEFAULT_bedKd) + #error "DEFAULT_bedKp, DEFAULT_bedKi, DEFAULT_bedKd are now DEFAULT_BED_KP, DEFAULT_BED_KI, DEFAULT_BED_KD." +#elif defined(DEFAULT_chamberKp) || defined(DEFAULT_chamberKi) || defined(DEFAULT_chamberKd) + #error "DEFAULT_chamberKp, DEFAULT_chamberKi, DEFAULT_chamberKd are now DEFAULT_CHAMBER_KP, DEFAULT_CHAMBER_KI, DEFAULT_CHAMBER_KD." +#elif defined(DEFAULT_Kc) + #error "DEFAULT_Kc is now (uppercase) DEFAULT_KC." +#elif defined(DEFAULT_Kf) + #error "DEFAULT_Kf is now (uppercase) DEFAULT_KF." #endif // SDSS renamed to SD_SS_PIN diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 8b3a60e048..00ba63c966 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -2873,10 +2873,10 @@ hal_timer_t Stepper::block_phase_isr() { planner.laser_inline.status.isSyncPower = false; // Clear the flag to process subsequent trap calc's. else if (current_block->laser.status.isEnabled) { #if ENABLED(LASER_POWER_TRAP) - TERN_(DEBUG_LASER_TRAP, SERIAL_ECHO_MSG("InitTrapPwr:",current_block->laser.trap_ramp_active_pwr)); + TERN_(DEBUG_LASER_TRAP, SERIAL_ECHO_MSG("InitTrapPwr:", current_block->laser.trap_ramp_active_pwr)); cutter.apply_power(current_block->laser.status.isPowered ? current_block->laser.trap_ramp_active_pwr : 0); #else - TERN_(DEBUG_CUTTER_POWER, SERIAL_ECHO_MSG("InlinePwr:",current_block->laser.power)); + TERN_(DEBUG_CUTTER_POWER, SERIAL_ECHO_MSG("InlinePwr:", current_block->laser.power)); cutter.apply_power(current_block->laser.status.isPowered ? current_block->laser.power : 0); #endif } diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 964e473361..8d63e226b9 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -720,47 +720,17 @@ void Temperature::factory_reset() { // #if ENABLED(PIDTEMP) #if ENABLED(PID_PARAMS_PER_HOTEND) - constexpr float defKp[] = - #ifdef DEFAULT_Kp_LIST - DEFAULT_Kp_LIST - #else - ARRAY_BY_HOTENDS1(DEFAULT_Kp) - #endif - , defKi[] = - #ifdef DEFAULT_Ki_LIST - DEFAULT_Ki_LIST - #else - ARRAY_BY_HOTENDS1(DEFAULT_Ki) - #endif - , defKd[] = - #ifdef DEFAULT_Kd_LIST - DEFAULT_Kd_LIST - #else - ARRAY_BY_HOTENDS1(DEFAULT_Kd) - #endif - ; - static_assert(WITHIN(COUNT(defKp), 1, HOTENDS), "DEFAULT_Kp_LIST must have between 1 and HOTENDS items."); - static_assert(WITHIN(COUNT(defKi), 1, HOTENDS), "DEFAULT_Ki_LIST must have between 1 and HOTENDS items."); - static_assert(WITHIN(COUNT(defKd), 1, HOTENDS), "DEFAULT_Kd_LIST must have between 1 and HOTENDS items."); + constexpr float defKP[] = DEFAULT_KP_LIST, defKI[] = DEFAULT_KI_LIST, defKD[] = DEFAULT_KD_LIST; + static_assert(WITHIN(COUNT(defKP), 1, HOTENDS), "DEFAULT_KP_LIST must have between 1 and HOTENDS items."); + static_assert(WITHIN(COUNT(defKI), 1, HOTENDS), "DEFAULT_KI_LIST must have between 1 and HOTENDS items."); + static_assert(WITHIN(COUNT(defKD), 1, HOTENDS), "DEFAULT_KD_LIST must have between 1 and HOTENDS items."); #if ENABLED(PID_EXTRUSION_SCALING) - constexpr float defKc[] = - #ifdef DEFAULT_Kc_LIST - DEFAULT_Kc_LIST - #else - ARRAY_BY_HOTENDS1(DEFAULT_Kc) - #endif - ; - static_assert(WITHIN(COUNT(defKc), 1, HOTENDS), "DEFAULT_Kc_LIST must have between 1 and HOTENDS items."); + constexpr float defKC[] = DEFAULT_KC_LIST; + static_assert(WITHIN(COUNT(defKC), 1, HOTENDS), "DEFAULT_KC_LIST must have between 1 and HOTENDS items."); #endif #if ENABLED(PID_FAN_SCALING) - constexpr float defKf[] = - #ifdef DEFAULT_Kf_LIST - DEFAULT_Kf_LIST - #else - ARRAY_BY_HOTENDS1(DEFAULT_Kf) - #endif - ; - static_assert(WITHIN(COUNT(defKf), 1, HOTENDS), "DEFAULT_Kf_LIST must have between 1 and HOTENDS items."); + constexpr float defKF[] = DEFAULT_KF_LIST; + static_assert(WITHIN(COUNT(defKF), 1, HOTENDS), "DEFAULT_KF_LIST must have between 1 and HOTENDS items."); #endif #define PID_DEFAULT(N,E) def##N[E] #else @@ -768,11 +738,11 @@ void Temperature::factory_reset() { #endif HOTEND_LOOP() { temp_hotend[e].pid.set( - PID_DEFAULT(Kp, ALIM(e, defKp)), - PID_DEFAULT(Ki, ALIM(e, defKi)), - PID_DEFAULT(Kd, ALIM(e, defKd)) - OPTARG(PID_EXTRUSION_SCALING, PID_DEFAULT(Kc, ALIM(e, defKc))) - OPTARG(PID_FAN_SCALING, PID_DEFAULT(Kf, ALIM(e, defKf))) + PID_DEFAULT(KP, ALIM(e, defKP)), + PID_DEFAULT(KI, ALIM(e, defKI)), + PID_DEFAULT(KD, ALIM(e, defKD)) + OPTARG(PID_EXTRUSION_SCALING, PID_DEFAULT(KC, ALIM(e, defKC))) + OPTARG(PID_FAN_SCALING, PID_DEFAULT(KF, ALIM(e, defKF))) ); } #endif // PIDTEMP @@ -786,14 +756,14 @@ void Temperature::factory_reset() { // Heated Bed PID // #if ENABLED(PIDTEMPBED) - temp_bed.pid.set(DEFAULT_bedKp, DEFAULT_bedKi, DEFAULT_bedKd); + temp_bed.pid.set(DEFAULT_BED_KP, DEFAULT_BED_KI, DEFAULT_BED_KD); #endif // // Heated Chamber PID // #if ENABLED(PIDTEMPCHAMBER) - temp_chamber.pid.set(DEFAULT_chamberKp, DEFAULT_chamberKi, DEFAULT_chamberKd); + temp_chamber.pid.set(DEFAULT_CHAMBER_KP, DEFAULT_CHAMBER_KI, DEFAULT_CHAMBER_KD); #endif // User-Defined Thermistors @@ -1009,14 +979,14 @@ void Temperature::factory_reset() { TERN_(HOST_PROMPT_SUPPORT, hostui.notify(GET_TEXT_F(MSG_PID_AUTOTUNE_DONE))); #if ANY(PIDTEMPBED, PIDTEMPCHAMBER) - FSTR_P const estring = PER_CBH(F("chamber"), F("bed"), FPSTR(NUL_STR)); - say_default_(); SERIAL_ECHOLN(estring, F("Kp "), tune_pid.p); - say_default_(); SERIAL_ECHOLN(estring, F("Ki "), tune_pid.i); - say_default_(); SERIAL_ECHOLN(estring, F("Kd "), tune_pid.d); + FSTR_P const estring = PER_CBH(F("CHAMBER_"), F("BED_"), FPSTR(NUL_STR)); + say_default_(); SERIAL_ECHOLN(estring, F("KP "), tune_pid.p); + say_default_(); SERIAL_ECHOLN(estring, F("KI "), tune_pid.i); + say_default_(); SERIAL_ECHOLN(estring, F("KD "), tune_pid.d); #else - say_default_(); SERIAL_ECHOLNPGM("Kp ", tune_pid.p); - say_default_(); SERIAL_ECHOLNPGM("Ki ", tune_pid.i); - say_default_(); SERIAL_ECHOLNPGM("Kd ", tune_pid.d); + say_default_(); SERIAL_ECHOLNPGM("KP ", tune_pid.p); + say_default_(); SERIAL_ECHOLNPGM("KI ", tune_pid.i); + say_default_(); SERIAL_ECHOLNPGM("KD ", tune_pid.d); #endif auto _set_hotend_pid = [](const uint8_t tool, const raw_pid_t &in_pid) { diff --git a/buildroot/tests/BTT_GTR_V1_0 b/buildroot/tests/BTT_GTR_V1_0 index 81d079b4f1..1ed65dcc90 100755 --- a/buildroot/tests/BTT_GTR_V1_0 +++ b/buildroot/tests/BTT_GTR_V1_0 @@ -25,7 +25,7 @@ restore_configs opt_set MOTHERBOARD BOARD_BTT_GTR_V1_0 SERIAL_PORT -1 \ EXTRUDERS 5 TEMP_SENSOR_1 1 TEMP_SENSOR_2 1 TEMP_SENSOR_3 1 TEMP_SENSOR_4 1 \ Z_DRIVER_TYPE A4988 Z2_DRIVER_TYPE A4988 Z3_DRIVER_TYPE A4988 Z4_DRIVER_TYPE A4988 \ - DEFAULT_Kp_LIST '{ 22.2, 20.0, 21.0, 19.0, 18.0 }' DEFAULT_Ki_LIST '{ 1.08 }' DEFAULT_Kd_LIST '{ 114.0, 112.0, 110.0, 108.0 }' \ + DEFAULT_KP_LIST '{ 22.2, 20.0, 21.0, 19.0, 18.0 }' DEFAULT_KI_LIST '{ 1.08 }' DEFAULT_KD_LIST '{ 114.0, 112.0, 110.0, 108.0 }' \ Z3_STOP_PIN PI7 Z4_STOP_PIN PF6 opt_enable TOOLCHANGE_FILAMENT_SWAP TOOLCHANGE_MIGRATION_FEATURE TOOLCHANGE_FS_SLOW_FIRST_PRIME TOOLCHANGE_FS_PRIME_FIRST_USED \ REPRAP_DISCOUNT_SMART_CONTROLLER PID_PARAMS_PER_HOTEND Z_MULTI_ENDSTOPS TC_GCODE_USE_GLOBAL_X TC_GCODE_USE_GLOBAL_Y From 084b065f46976757432fba17fed46a6e015956e1 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 30 Nov 2025 17:23:55 -0600 Subject: [PATCH 11/47] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20MMU2=20menu?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/menu/menu_mmu2.cpp | 10 ++-------- 1 file changed, 2 insertions(+), 8 deletions(-) diff --git a/Marlin/src/lcd/menu/menu_mmu2.cpp b/Marlin/src/lcd/menu/menu_mmu2.cpp index fccc1a464c..332f96ffe2 100644 --- a/Marlin/src/lcd/menu/menu_mmu2.cpp +++ b/Marlin/src/lcd/menu/menu_mmu2.cpp @@ -154,10 +154,7 @@ void menu_mmu3_fail_stats_last_print() { sprintf_P(buffer2, PSTR("%hu"), load_fail_num); START_SCREEN(); - STATIC_ITEM( - TERN(printJobOngoing(), MSG_MMU_CURRENT_PRINT_FAILURES, MSG_MMU_LAST_PRINT_FAILURES), - SS_INVERT - ); + STATIC_ITEM_F(printJobOngoing() ? GET_TEXT_F(MSG_MMU_CURRENT_PRINT_FAILURES) : GET_TEXT_F(MSG_MMU_LAST_PRINT_FAILURES), SS_INVERT); #ifndef __AVR__ // TODO: I couldn't make this work on AVR PSTRING_ITEM(MSG_MMU_FAILS, buffer1, SS_FULL); @@ -236,10 +233,7 @@ void menu_mmu3_statistics() { ACTION_ITEM(MSG_MMU_DEV_INCREMENT_LOAD_FAILS, menu_mmu3_dev_increment_load_fail_stat); #endif - SUBMENU( - TERN(printJobOngoing(), MSG_MMU_CURRENT_PRINT_FAILURES, MSG_MMU_LAST_PRINT_FAILURES), - menu_mmu3_fail_stats_last_print - ); + SUBMENU_F(printJobOngoing() ? GET_TEXT_F(MSG_MMU_CURRENT_PRINT_FAILURES) : GET_TEXT_F(MSG_MMU_LAST_PRINT_FAILURES), menu_mmu3_fail_stats_last_print); SUBMENU(MSG_MMU_TOTAL_FAILURES, menu_mmu3_fail_stas_total); SUBMENU(MSG_MMU_MATERIAL_CHANGES, menu_mmu3_toolchange_stat_total); CONFIRM_ITEM(MSG_MMU_RESET_FAIL_STATS, From 544cde20fba4486d210f2a28f0da684b4865b026 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 1 Dec 2025 00:40:21 +0000 Subject: [PATCH 12/47] [cron] Bump distribution date (2025-12-01) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index e04bcf0334..c884bcea7a 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-30" +//#define STRING_DISTRIBUTION_DATE "2025-12-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 d97a80ad36..3aa89f99b0 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-30" + #define STRING_DISTRIBUTION_DATE "2025-12-01" #endif /** From 35319049fe1140e4e14245b1f328535760fd8b06 Mon Sep 17 00:00:00 2001 From: Harald Wagener Date: Mon, 1 Dec 2025 03:05:45 +0100 Subject: [PATCH 13/47] =?UTF-8?q?=E2=9C=A8=20FT=5FMOTION=20>=20FTM=5FPOLYS?= =?UTF-8?q?=20(#28197)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 17 ++--- Marlin/src/gcode/feature/ft_motion/M494.cpp | 62 +++++++++++-------- Marlin/src/gcode/gcode.cpp | 4 +- Marlin/src/inc/Conditionals-4-adv.h | 3 + Marlin/src/lcd/menu/menu_motion.cpp | 58 +++++++++-------- Marlin/src/module/ft_motion.cpp | 18 ++++-- Marlin/src/module/ft_motion.h | 20 ++++-- .../src/module/ft_motion/trajectory_poly6.cpp | 4 +- ini/features.ini | 3 +- 9 files changed, 114 insertions(+), 75 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index f0b685ba19..410b08ab2f 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1201,14 +1201,17 @@ // smoothing acceleration peaks, which may also smooth curved surfaces. #endif - #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 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. + #define FTM_POLYS // Disable POLY5/6 to save ~3k of Flash. Preserves TRAPEZOIDAL. + #if ENABLED(FTM_POLYS) + #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 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. - #define FTM_POLY6_ACCELERATION_OVERSHOOT 1.875f // Max acceleration overshoot factor for POLY6 (1.25 to 1.875) + #define FTM_POLY6_ACCELERATION_OVERSHOOT 1.875f // Max acceleration overshoot factor for POLY6 (1.25 to 1.875) + #endif /** * Advanced configuration diff --git a/Marlin/src/gcode/feature/ft_motion/M494.cpp b/Marlin/src/gcode/feature/ft_motion/M494.cpp index f3a4e61123..a359ab5269 100644 --- a/Marlin/src/gcode/feature/ft_motion/M494.cpp +++ b/Marlin/src/gcode/feature/ft_motion/M494.cpp @@ -38,12 +38,16 @@ static FSTR_P get_trajectory_type_name() { } void say_ftm_settings() { - SERIAL_ECHOLN(F(" Trajectory: "), get_trajectory_type_name(), C('('), (uint8_t)ftMotion.getTrajectoryType(), C(')')); + #if ENABLED(FTM_POLYS) + SERIAL_ECHOLN(F(" Trajectory: "), get_trajectory_type_name(), C('('), (uint8_t)ftMotion.getTrajectoryType(), C(')')); + #endif const ft_config_t &c = ftMotion.cfg; - if (ftMotion.getTrajectoryType() == TrajectoryType::POLY6) - SERIAL_ECHOLNPGM(" Poly6 Overshoot: ", p_float_t(c.poly6_acceleration_overshoot, 3)); + #if ENABLED(FTM_POLYS) + if (ftMotion.getTrajectoryType() == TrajectoryType::POLY6) + SERIAL_ECHOLNPGM(" Poly6 Overshoot: ", p_float_t(c.poly6_acceleration_overshoot, 3)); + #endif #if ENABLED(FTM_SMOOTHING) #define _SMOO_REPORT(A) SERIAL_ECHOLN(F(" "), C(IAXIS_CHAR(_AXIS(A))), F(" smoothing time: "), p_float_t(c.smoothingTime.A, 3), C('s')); @@ -66,10 +70,13 @@ void GcodeSuite::M494_report(const bool forReplay/*=true*/) { " Z", c.smoothingTime.Z, " E", c.smoothingTime.E ) ); - #endif + #endif // FTM_SMOOTHING - if (ftMotion.getTrajectoryType() == TrajectoryType::POLY6) - SERIAL_ECHOPGM(" O", c.poly6_acceleration_overshoot); + #if ENABLED(FTM_POLYS) + + if (ftMotion.getTrajectoryType() == TrajectoryType::POLY6) + SERIAL_ECHOPGM(" O", c.poly6_acceleration_overshoot); + #endif // FTM_POLYS SERIAL_EOL(); } @@ -88,28 +95,31 @@ void GcodeSuite::M494_report(const bool forReplay/*=true*/) { void GcodeSuite::M494() { bool report = !parser.seen_any(); - // Parse trajectory type parameter. - if (parser.seenval('T')) { - const int val = parser.value_int(); - if (WITHIN(val, 0, 2)) { - planner.synchronize(); - ftMotion.setTrajectoryType((TrajectoryType)val); - report = true; - } - else - SERIAL_ECHOLN(F("?Invalid "), F("trajectory type [T] value. Use 0=TRAPEZOIDAL, 1=POLY5, 2=POLY6")); - } + #if ENABLED(FTM_POLYS) - // Parse overshoot parameter. - if (parser.seenval('O')) { - const float val = parser.value_float(); - if (WITHIN(val, 1.25f, 1.875f)) { - ftMotion.cfg.poly6_acceleration_overshoot = val; - report = true; + // Parse trajectory type parameter. + if (parser.seenval('T')) { + const int val = parser.value_int(); + if (WITHIN(val, 0, 2)) { + planner.synchronize(); + ftMotion.setTrajectoryType((TrajectoryType)val); + report = true; + } + else + SERIAL_ECHOLN(F("?Invalid "), F("trajectory type [T] value. Use 0=TRAPEZOIDAL, 1=POLY5, 2=POLY6")); } - else - SERIAL_ECHOLN(F("?Invalid "), F("overshoot [O] value. Range 1.25-1.875")); - } + // Parse overshoot parameter. + if (parser.seenval('O')) { + const float val = parser.value_float(); + if (WITHIN(val, 1.25f, 1.875f)) { + ftMotion.cfg.poly6_acceleration_overshoot = val; + report = true; + } + else + SERIAL_ECHOLN(F("?Invalid "), F("overshoot [O] value. Range 1.25-1.875")); + } + + #endif // FTM_POLYS #if ENABLED(FTM_SMOOTHING) diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index aa629f4a71..6dab1eb3bb 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -926,8 +926,8 @@ void GcodeSuite::process_parsed_command(bool no_ok/*=false*/) { #endif #if ENABLED(FT_MOTION) - case 493: M493(); break; // M493: Fixed-Time Motion control - #if ENABLED(FTM_SMOOTHING) + case 493: M493(); break; // M493: Fixed-Time Motion control + #if ANY(FTM_SMOOTHING, FTM_POLYS) case 494: M494(); break; // M494: Fixed-Time Motion extras #endif #if ENABLED(FTM_RESONANCE_TEST) diff --git a/Marlin/src/inc/Conditionals-4-adv.h b/Marlin/src/inc/Conditionals-4-adv.h index 6bac442308..32cd506760 100644 --- a/Marlin/src/inc/Conditionals-4-adv.h +++ b/Marlin/src/inc/Conditionals-4-adv.h @@ -1541,6 +1541,9 @@ #if !HAS_EXTRUDERS #undef FTM_SHAPER_E #endif + #if DISABLED(FTM_POLYS) + #define FTM_TRAJECTORY_TYPE TRAPEZOIDAL + #endif #endif // Multi-Stepping Limit diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index ef082fe89f..8bc29739ac 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -327,14 +327,17 @@ void menu_move() { } } - FSTR_P get_trajectory_name() { - switch (ftMotion.getTrajectoryType()) { - default: - case TrajectoryType::TRAPEZOIDAL: return GET_TEXT_F(MSG_FTM_TRAPEZOIDAL); - case TrajectoryType::POLY5: return GET_TEXT_F(MSG_FTM_POLY5); - case TrajectoryType::POLY6: return GET_TEXT_F(MSG_FTM_POLY6); + #if ENABLED(FTM_POLYS) + FSTR_P get_trajectory_name() { + switch (ftMotion.getTrajectoryType()) { + default: + case TrajectoryType::TRAPEZOIDAL: return GET_TEXT_F(MSG_FTM_TRAPEZOIDAL); + case TrajectoryType::POLY5: return GET_TEXT_F(MSG_FTM_POLY5); + case TrajectoryType::POLY6: return GET_TEXT_F(MSG_FTM_POLY6); + + } } - } + #endif // FTM_POLYS #if HAS_DYNAMIC_FREQ FSTR_P get_dyn_freq_mode_name() { @@ -371,16 +374,17 @@ void menu_move() { } SHAPED_MAP(MENU_FTM_SHAPER); - - void menu_ftm_trajectory_generator() { - const TrajectoryType current_type = ftMotion.getTrajectoryType(); - START_MENU(); - BACK_ITEM(MSG_FIXED_TIME_MOTION); - if (current_type != TrajectoryType::TRAPEZOIDAL) ACTION_ITEM(MSG_FTM_TRAPEZOIDAL, []{ planner.synchronize(); ftMotion.setTrajectoryType(TrajectoryType::TRAPEZOIDAL); ui.go_back(); }); - if (current_type != TrajectoryType::POLY5) ACTION_ITEM(MSG_FTM_POLY5, []{ planner.synchronize(); ftMotion.setTrajectoryType(TrajectoryType::POLY5); ui.go_back(); }); - if (current_type != TrajectoryType::POLY6) ACTION_ITEM(MSG_FTM_POLY6, []{ planner.synchronize(); ftMotion.setTrajectoryType(TrajectoryType::POLY6); ui.go_back(); }); + #if ENABLED(FTM_POLYS) + void menu_ftm_trajectory_generator() { + const TrajectoryType current_type = ftMotion.getTrajectoryType(); + START_MENU(); + BACK_ITEM(MSG_FIXED_TIME_MOTION); + if (current_type != TrajectoryType::TRAPEZOIDAL) ACTION_ITEM(MSG_FTM_TRAPEZOIDAL, []{ planner.synchronize(); ftMotion.setTrajectoryType(TrajectoryType::TRAPEZOIDAL); ui.go_back(); }); + if (current_type != TrajectoryType::POLY5) ACTION_ITEM(MSG_FTM_POLY5, []{ planner.synchronize(); ftMotion.setTrajectoryType(TrajectoryType::POLY5); ui.go_back(); }); + if (current_type != TrajectoryType::POLY6) ACTION_ITEM(MSG_FTM_POLY6, []{ planner.synchronize(); ftMotion.setTrajectoryType(TrajectoryType::POLY6); ui.go_back(); }); END_MENU(); } + #endif // FTM_POLYS #if ENABLED(FTM_RESONANCE_TEST) @@ -497,7 +501,9 @@ void menu_move() { #else auto _shaper_name = [](const AxisEnum a) { return get_shaper_name(a); }; auto _dmode = []{ return get_dyn_freq_mode_name(); }; - auto _traj_name = []{ return get_trajectory_name(); }; + #if ENABLED(FTM_POLYS) + auto _traj_name = []{ return get_trajectory_name(); }; + #endif #endif START_MENU(); @@ -508,6 +514,12 @@ void menu_move() { // Show only when FT Motion is active (or optionally always show) if (c.active || ENABLED(FT_MOTION_NO_MENU_TOGGLE)) { + #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, &c.poly6_acceleration_overshoot, 1.25f, 1.875f); + #endif + #define SHAPER_MENU_ITEM(A) \ SUBMENU_N_S(_AXIS(A), _shaper_name(_AXIS(A)), MSG_FTM_CMPN_MODE, menu_ftm_shaper_##A); \ if (AXIS_IS_SHAPING(A)) { \ @@ -516,11 +528,6 @@ void menu_move() { if (AXIS_IS_EISHAPING(A)) \ EDIT_ITEM_FAST_N(float42_52, _AXIS(A), MSG_FTM_VTOL_N, &c.vtol.A, 0.0f, 1.0f, ftMotion.update_shaping_params); \ } - SUBMENU_S(_traj_name(), 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); - SHAPED_MAP(SHAPER_MENU_ITEM); #if HAS_DYNAMIC_FREQ @@ -596,10 +603,11 @@ void menu_move() { START_MENU(); BACK_ITEM(MSG_TUNE); - SUBMENU_S(_traj_name(), 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 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, &c.poly6_acceleration_overshoot, 1.25f, 1.875f); + #endif #define _CMPM_MENU_ITEM(A) SUBMENU_N_S(_AXIS(A), _shaper_name(_AXIS(A)), MSG_FTM_CMPN_MODE, menu_ftm_shaper_##A); SHAPED_MAP(_CMPM_MENU_ITEM); diff --git a/Marlin/src/module/ft_motion.cpp b/Marlin/src/module/ft_motion.cpp index 74ef6e79ef..8c596f1fa3 100644 --- a/Marlin/src/module/ft_motion.cpp +++ b/Marlin/src/module/ft_motion.cpp @@ -33,8 +33,10 @@ #include "ft_motion.h" #include "ft_motion/trajectory_trapezoidal.h" -#include "ft_motion/trajectory_poly5.h" -#include "ft_motion/trajectory_poly6.h" +#if ENABLED(FTM_POLYS) + #include "ft_motion/trajectory_poly5.h" + #include "ft_motion/trajectory_poly6.h" +#endif #if ENABLED(FTM_RESONANCE_TEST) #include "ft_motion/resonance_generator.h" #include "../gcode/gcode.h" // for home_all_axes @@ -71,8 +73,10 @@ float FTMotion::tau = 0.0f; // (s) Time since start of b // Trajectory generators TrapezoidalTrajectoryGenerator FTMotion::trapezoidalGenerator; -Poly5TrajectoryGenerator FTMotion::poly5Generator; -Poly6TrajectoryGenerator FTMotion::poly6Generator; +#if ENABLED(FTM_POLYS) + Poly5TrajectoryGenerator FTMotion::poly5Generator; + Poly6TrajectoryGenerator FTMotion::poly6Generator; +#endif TrajectoryGenerator* FTMotion::currentGenerator = &FTMotion::trapezoidalGenerator; TrajectoryType FTMotion::trajectoryType = TrajectoryType::FTM_TRAJECTORY_TYPE; @@ -307,8 +311,10 @@ void FTMotion::setTrajectoryType(const TrajectoryType type) { switch (type) { default: cfg.trajectory_type = trajectoryType = TrajectoryType::FTM_TRAJECTORY_TYPE; case TrajectoryType::TRAPEZOIDAL: currentGenerator = &trapezoidalGenerator; break; - case TrajectoryType::POLY5: currentGenerator = &poly5Generator; break; - case TrajectoryType::POLY6: currentGenerator = &poly6Generator; break; + #if ENABLED(FTM_POLYS) + case TrajectoryType::POLY5: currentGenerator = &poly5Generator; break; + case TrajectoryType::POLY6: currentGenerator = &poly6Generator; break; + #endif } } diff --git a/Marlin/src/module/ft_motion.h b/Marlin/src/module/ft_motion.h index d839869058..d26fa8b882 100644 --- a/Marlin/src/module/ft_motion.h +++ b/Marlin/src/module/ft_motion.h @@ -26,8 +26,10 @@ #include "stepper.h" // For stepper motion and direction #include "ft_motion/trajectory_trapezoidal.h" -#include "ft_motion/trajectory_poly5.h" -#include "ft_motion/trajectory_poly6.h" +#if ENABLED(FTM_POLYS) + #include "ft_motion/trajectory_poly5.h" + #include "ft_motion/trajectory_poly6.h" +#endif #if ENABLED(FTM_RESONANCE_TEST) #include "ft_motion/resonance_generator.h" #endif @@ -83,7 +85,9 @@ typedef struct FTConfig { #endif TrajectoryType trajectory_type = TrajectoryType::FTM_TRAJECTORY_TYPE; // Trajectory generator type - float poly6_acceleration_overshoot; // Overshoot factor for Poly6 (1.25 to 2.0) + #if ENABLED(FTM_POLYS) + float poly6_acceleration_overshoot; // Overshoot factor for Poly6 (1.25 to 2.0) + #endif } ft_config_t; /** @@ -134,7 +138,9 @@ class FTMotion { #undef _SET_SMOOTH #endif - cfg.poly6_acceleration_overshoot = FTM_POLY6_ACCELERATION_OVERSHOOT; + #if ENABLED(FTM_POLYS) + cfg.poly6_acceleration_overshoot = FTM_POLY6_ACCELERATION_OVERSHOOT; + #endif setTrajectoryType(TrajectoryType::FTM_TRAJECTORY_TYPE); @@ -219,8 +225,10 @@ class FTMotion { // Trajectory generators static TrapezoidalTrajectoryGenerator trapezoidalGenerator; - static Poly5TrajectoryGenerator poly5Generator; - static Poly6TrajectoryGenerator poly6Generator; + #if ENABLED(FTM_POLYS) + static Poly5TrajectoryGenerator poly5Generator; + static Poly6TrajectoryGenerator poly6Generator; + #endif static TrajectoryGenerator* currentGenerator; static TrajectoryType trajectoryType; diff --git a/Marlin/src/module/ft_motion/trajectory_poly6.cpp b/Marlin/src/module/ft_motion/trajectory_poly6.cpp index 45dff71084..4693828fe3 100644 --- a/Marlin/src/module/ft_motion/trajectory_poly6.cpp +++ b/Marlin/src/module/ft_motion/trajectory_poly6.cpp @@ -22,7 +22,7 @@ #include "../../inc/MarlinConfig.h" -#if ENABLED(FT_MOTION) +#if ENABLED(FTM_POLYS) #include "trajectory_poly6.h" #include "../ft_motion.h" @@ -140,4 +140,4 @@ void Poly6TrajectoryGenerator::reset() { acc_c6 = dec_c6 = 0.0f; } -#endif // FT_MOTION +#endif // FTM_POLYS diff --git a/ini/features.ini b/ini/features.ini index 1c10302fb0..4afdc3dc4c 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -311,9 +311,10 @@ 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=+ +FTM_POLYS = build_src_filter=+ HAS_LIN_ADVANCE_K = build_src_filter=+ PHOTO_GCODE = build_src_filter=+ CONTROLLER_FAN_EDITABLE = build_src_filter=+ From 7fcc605595f777e00c377372f9a4e7c09d232a2a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 24 Nov 2025 17:06:42 -0600 Subject: [PATCH 14/47] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Reloc?= =?UTF-8?q?ate=20G38=20data?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/MarlinCore.cpp | 5 ----- Marlin/src/MarlinCore.h | 5 ----- Marlin/src/gcode/probe/G38.cpp | 10 ++++++---- Marlin/src/module/endstops.cpp | 6 +++--- Marlin/src/module/endstops.h | 8 ++++++++ 5 files changed, 17 insertions(+), 17 deletions(-) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index cb81efc4bb..b6a47ec744 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -164,11 +164,6 @@ CardReader card; #endif -#if ENABLED(G38_PROBE_TARGET) - uint8_t G38_move; // = 0 - bool G38_did_trigger; // = false -#endif - #if ENABLED(DELTA) #include "module/delta.h" #elif ENABLED(POLARGRAPH) diff --git a/Marlin/src/MarlinCore.h b/Marlin/src/MarlinCore.h index ecab0e3630..6f27b9998e 100644 --- a/Marlin/src/MarlinCore.h +++ b/Marlin/src/MarlinCore.h @@ -33,11 +33,6 @@ void stop(); void idle(const bool no_stepper_sleep=false); inline void idle_no_sleep() { idle(true); } -#if ENABLED(G38_PROBE_TARGET) - extern uint8_t G38_move; // Flag to tell the ISR that G38 is in progress, and the type - extern bool G38_did_trigger; // Flag from the ISR to indicate the endstop changed -#endif - void kill(FSTR_P const lcd_error=nullptr, FSTR_P const lcd_component=nullptr, const bool steppers_off=false); void minkill(const bool steppers_off=false); diff --git a/Marlin/src/gcode/probe/G38.cpp b/Marlin/src/gcode/probe/G38.cpp index d57eb9b59e..34cab07ed6 100644 --- a/Marlin/src/gcode/probe/G38.cpp +++ b/Marlin/src/gcode/probe/G38.cpp @@ -31,12 +31,14 @@ #include "../../module/planner.h" #include "../../module/probe.h" +probe_target_t G38_move{0}; + inline void G38_single_probe(const uint8_t move_value) { endstops.enable(true); - G38_move = move_value; + G38_move.type = move_value; prepare_line_to_destination(); planner.synchronize(); - G38_move = 0; + G38_move.type = 0; endstops.hit_on_purpose(); set_current_from_steppers_for_axis(ALL_AXES_ENUM); sync_plan_position(); @@ -64,12 +66,12 @@ inline bool G38_run_probe() { constexpr uint8_t move_value = 1; #endif - G38_did_trigger = false; + G38_move.triggered = false; // Move until destination reached or target hit G38_single_probe(move_value); - if (G38_did_trigger) { + if (G38_move.triggered) { G38_pass_fail = true; diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 20b3b8b1d2..31b877b642 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -473,7 +473,7 @@ void Endstops::update() { #if ENABLED(G38_PROBE_TARGET) // For G38 moves check the probe's pin for ALL movement - if (G38_move) UPDATE_LIVE_STATE(Z, TERN(USE_Z_MIN_PROBE, MIN_PROBE, MIN)); + if (G38_move.type) UPDATE_LIVE_STATE(Z, TERN(USE_Z_MIN_PROBE, MIN_PROBE, MIN)); #endif #if ENABLED(CALIBRATION_GCODE) @@ -723,8 +723,8 @@ void Endstops::update() { #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; + if (G38_move.type && TEST_ENDSTOP(Z_MIN_PROBE) == TERN1(G38_PROBE_AWAY, (G38_move.type < 4))) { + G38_move.triggered = true; #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)) }; diff --git a/Marlin/src/module/endstops.h b/Marlin/src/module/endstops.h index 4d7a444bc4..17715de1da 100644 --- a/Marlin/src/module/endstops.h +++ b/Marlin/src/module/endstops.h @@ -313,3 +313,11 @@ class TemporaryGlobalEndstopsState { } ~TemporaryGlobalEndstopsState() { endstops.enable_globally(saved); } }; + +#if ENABLED(G38_PROBE_TARGET) + typedef struct ProbeTarget { + uint8_t type; // Flag to tell the ISR the type of G38 in progress; 0 for NONE. + bool triggered; // Flag from the ISR to indicate the endstop changed + } probe_target_t; + extern probe_target_t G38_move; +#endif From 73fa80f12870525ca9ae7ca7f341f4bf57b804e8 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 27 Nov 2025 12:28:34 -0600 Subject: [PATCH 15/47] =?UTF-8?q?=F0=9F=8E=A8=20Pretty=20up=20timers?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/AVR/timers.h | 14 ++++++------ Marlin/src/HAL/DUE/timers.h | 14 ++++++------ Marlin/src/HAL/ESP32/timers.h | 33 +++++++++++++++-------------- Marlin/src/HAL/GD32_MFL/timers.h | 17 ++++++++------- Marlin/src/HAL/HC32/timers.h | 12 +++++------ Marlin/src/HAL/LINUX/timers.h | 22 +++++++++---------- Marlin/src/HAL/LPC1768/timers.h | 22 +++++++++---------- Marlin/src/HAL/NATIVE_SIM/timers.h | 22 +++++++++---------- Marlin/src/HAL/RP2040/timers.h | 16 +++++++------- Marlin/src/HAL/SAMD21/timers.h | 12 +++++------ Marlin/src/HAL/SAMD51/timers.h | 12 +++++------ Marlin/src/HAL/STM32/timers.h | 16 +++++++------- Marlin/src/HAL/STM32F1/timers.h | 22 +++++++++---------- Marlin/src/HAL/TEENSY31_32/timers.h | 20 ++++++++--------- Marlin/src/HAL/TEENSY35_36/timers.h | 20 ++++++++--------- Marlin/src/HAL/TEENSY40_41/timers.h | 16 +++++++------- 16 files changed, 145 insertions(+), 145 deletions(-) diff --git a/Marlin/src/HAL/AVR/timers.h b/Marlin/src/HAL/AVR/timers.h index f316b7c551..892e0e493b 100644 --- a/Marlin/src/HAL/AVR/timers.h +++ b/Marlin/src/HAL/AVR/timers.h @@ -46,15 +46,15 @@ typedef uint16_t hal_timer_t; #define MF_TIMER_TEMP 0 #endif -#define TEMP_TIMER_FREQUENCY (((F_CPU) + 0x2000) / 0x4000) +#define TEMP_TIMER_FREQUENCY (((F_CPU) + 0x2000) / 0x4000) -#define STEPPER_TIMER_RATE HAL_TIMER_RATE -#define STEPPER_TIMER_PRESCALE 8 -#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) +#define STEPPER_TIMER_RATE HAL_TIMER_RATE +#define STEPPER_TIMER_PRESCALE 8 +#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) -#define PULSE_TIMER_RATE STEPPER_TIMER_RATE -#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer +#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE #define ENABLE_STEPPER_DRIVER_INTERRUPT() SBI(TIMSK1, OCIE1A) #define DISABLE_STEPPER_DRIVER_INTERRUPT() CBI(TIMSK1, OCIE1A) diff --git a/Marlin/src/HAL/DUE/timers.h b/Marlin/src/HAL/DUE/timers.h index 8572958732..c63e051ef3 100644 --- a/Marlin/src/HAL/DUE/timers.h +++ b/Marlin/src/HAL/DUE/timers.h @@ -52,19 +52,19 @@ typedef uint32_t hal_timer_t; #define MF_TIMER_TONE 6 // index of timer to use for beeper tones #endif -#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency +#define TEMP_TIMER_FREQUENCY 1000 // (Hz) Temperature ISR frequency -#define STEPPER_TIMER_RATE HAL_TIMER_RATE // frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) -#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs +#define STEPPER_TIMER_RATE HAL_TIMER_RATE // (Hz) Frequency of Stepper Timer ISR (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) +#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) // (MHz) Stepper Timer ticks per µs #define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US) -#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer -#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer #define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) +#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 STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) #define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP) diff --git a/Marlin/src/HAL/ESP32/timers.h b/Marlin/src/HAL/ESP32/timers.h index 868b5fa850..4e5f92d671 100644 --- a/Marlin/src/HAL/ESP32/timers.h +++ b/Marlin/src/HAL/ESP32/timers.h @@ -36,35 +36,40 @@ typedef uint64_t hal_timer_t; #define MF_TIMER_STEP 0 // Timer Index for Stepper #endif #ifndef MF_TIMER_PULSE - #define MF_TIMER_PULSE MF_TIMER_STEP + #define MF_TIMER_PULSE MF_TIMER_STEP // Timer Index for Pulse interval #endif #ifndef MF_TIMER_TEMP #define MF_TIMER_TEMP 1 // Timer Index for Temperature #endif #ifndef MF_TIMER_PWM - #define MF_TIMER_PWM 2 // index of timer to use for PWM outputs + #define MF_TIMER_PWM 2 // Timer Index for PWM outputs #endif #ifndef MF_TIMER_TONE - #define MF_TIMER_TONE 3 // index of timer for beeper tones + #define MF_TIMER_TONE 3 // Timer Index for beeper tones #endif -#define HAL_TIMER_RATE APB_CLK_FREQ // frequency of timer peripherals +#define HAL_TIMER_RATE APB_CLK_FREQ // Frequency of timer peripherals + +#define TEMP_TIMER_PRESCALE 1000 // Prescaler for setting Temp Timer, 72Khz +#define TEMP_TIMER_FREQUENCY 1000 // (Hz) Temperature ISR frequency #if ENABLED(I2S_STEPPER_STREAM) #define STEPPER_TIMER_PRESCALE 1 - #define STEPPER_TIMER_RATE 250'000 // 250khz, 4µs pulses of i2s word clock + #define STEPPER_TIMER_RATE 250'000 // 250khz, 4µs pulses of i2s word clock + #define STEPPER_TIMER_TICKS_PER_US 0.25 // (MHz) Stepper Timer ticks per µs #else #define STEPPER_TIMER_PRESCALE 40 - #define STEPPER_TIMER_RATE ((HAL_TIMER_RATE) / (STEPPER_TIMER_PRESCALE)) // frequency of stepper timer, 2MHz + #define STEPPER_TIMER_RATE ((HAL_TIMER_RATE) / (STEPPER_TIMER_PRESCALE)) // (Hz) Frequency of Stepper Timer ISR, 2MHz + #define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1'000'000UL) // (MHz) Stepper Timer ticks per µs #endif -#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1'000'000) // stepper timer ticks per µs #define STEP_TIMER_MIN_INTERVAL 8 // minimum time in µs between stepper interrupts -#define TONE_TIMER_PRESCALE 1000 // Arbitrary value, no idea what i'm doing here +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer +#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define TEMP_TIMER_PRESCALE 1000 // prescaler for setting Temp timer, 72Khz -#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency +#define TONE_TIMER_PRESCALE 1000 // Arbitrary value, no idea what i'm doing here #define PWM_TIMER_PRESCALE 10 #if ENABLED(FAST_PWM_FAN) @@ -74,13 +79,9 @@ typedef uint64_t hal_timer_t; #endif #define MAX_PWM_PINS 32 // Number of PWM pin-slots -#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer -#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US - -#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) +#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 STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) #define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP) diff --git a/Marlin/src/HAL/GD32_MFL/timers.h b/Marlin/src/HAL/GD32_MFL/timers.h index 9ecb1dcf79..d45e3d1767 100644 --- a/Marlin/src/HAL/GD32_MFL/timers.h +++ b/Marlin/src/HAL/GD32_MFL/timers.h @@ -29,10 +29,6 @@ // Defines // ------------------------ -// Timer configuration constants -#define STEPPER_TIMER_RATE 2000000 -#define TEMP_TIMER_FREQUENCY 1000 - // Timer instance definitions #define MF_TIMER_STEP 3 #define MF_TIMER_TEMP 1 @@ -43,12 +39,17 @@ extern uint32_t GetStepperTimerClkFreq(); +// 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 PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // Stepper timer ticks per µs -#define PULSE_TIMER_RATE STEPPER_TIMER_RATE +#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 PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer #define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE // Timer interrupt priorities #define STEP_TIMER_IRQ_PRIORITY 2 diff --git a/Marlin/src/HAL/HC32/timers.h b/Marlin/src/HAL/HC32/timers.h index e5bb29e834..9b898101dc 100644 --- a/Marlin/src/HAL/HC32/timers.h +++ b/Marlin/src/HAL/HC32/timers.h @@ -65,8 +65,8 @@ extern Timer0 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_RATE (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) // 50MHz / 16 = 3.125MHz -#define STEPPER_TIMER_TICKS_PER_US (STEPPER_TIMER_RATE / 1000000UL) // Integer 3 +#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 MF_TIMER_PULSE MF_TIMER_STEP @@ -110,11 +110,11 @@ inline void HAL_timer_isr_epilogue(const timer_channel_t) {} // // HAL function aliases // -#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_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(MF_TIMER_TEMP) +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP); // diff --git a/Marlin/src/HAL/LINUX/timers.h b/Marlin/src/HAL/LINUX/timers.h index b09fc6156a..cbca970bb2 100644 --- a/Marlin/src/HAL/LINUX/timers.h +++ b/Marlin/src/HAL/LINUX/timers.h @@ -49,21 +49,21 @@ typedef uint32_t hal_timer_t; #endif #define TEMP_TIMER_RATE 1000000 -#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency +#define TEMP_TIMER_FREQUENCY 1000 // (Hz) Temperature ISR frequency -#define STEPPER_TIMER_RATE HAL_TIMER_RATE // frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) -#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs -#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US) +#define STEPPER_TIMER_RATE HAL_TIMER_RATE // (Hz) Frequency of Stepper Timer ISR (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) +#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) // (MHz) Stepper Timer ticks per µs +#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US) -#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer -#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer +#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#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_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(MF_TIMER_TEMP) +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP) #ifndef HAL_STEP_TIMER_ISR diff --git a/Marlin/src/HAL/LPC1768/timers.h b/Marlin/src/HAL/LPC1768/timers.h index eae2cd587e..e29aa273a1 100644 --- a/Marlin/src/HAL/LPC1768/timers.h +++ b/Marlin/src/HAL/LPC1768/timers.h @@ -77,21 +77,19 @@ typedef uint32_t hal_timer_t; #define TEMP_TIMER_RATE 1000000 // 1MHz #define TEMP_TIMER_FREQUENCY 1000 // (Hz) Temperature ISR frequency -#ifndef STEPPER_TIMER_RATE - #define STEPPER_TIMER_RATE HAL_TIMER_RATE // (Hz) Frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) -#endif -#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // Stepper Timer ticks per µs -#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US) +#define STEPPER_TIMER_RATE HAL_TIMER_RATE // (Hz) Frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) +#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) // (MHz) Stepper Timer ticks per µs +#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US) -#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer -#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer +#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#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_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(MF_TIMER_TEMP) +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP) #ifndef HAL_STEP_TIMER_ISR diff --git a/Marlin/src/HAL/NATIVE_SIM/timers.h b/Marlin/src/HAL/NATIVE_SIM/timers.h index 3868f8f1e3..6609774d12 100644 --- a/Marlin/src/HAL/NATIVE_SIM/timers.h +++ b/Marlin/src/HAL/NATIVE_SIM/timers.h @@ -52,22 +52,22 @@ typedef uint64_t hal_timer_t; #endif #define SYSTICK_TIMER_FREQUENCY 1000 -#define TEMP_TIMER_RATE 1'000'000 -#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency +#define TEMP_TIMER_RATE 1'000'000 // (Hz) Temperature Timer count rate +#define TEMP_TIMER_FREQUENCY 1000 // (Hz) Temperature ISR call frequency -#define STEPPER_TIMER_RATE HAL_TIMER_RATE // frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) -#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1'000'000) // stepper timer ticks per µs +#define STEPPER_TIMER_RATE HAL_TIMER_RATE // (Hz) Frequency of Stepper Timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) +#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1'000'000) // (MHz) Stepper Timer ticks per µs #define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US) -#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer -#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer +#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#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_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(MF_TIMER_TEMP) +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP) #ifndef HAL_STEP_TIMER_ISR diff --git a/Marlin/src/HAL/RP2040/timers.h b/Marlin/src/HAL/RP2040/timers.h index 5e0234c10c..06deb152f7 100644 --- a/Marlin/src/HAL/RP2040/timers.h +++ b/Marlin/src/HAL/RP2040/timers.h @@ -58,21 +58,21 @@ typedef uint64_t hal_timer_t; #endif #define TEMP_TIMER_RATE HAL_TIMER_RATE -#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency +#define TEMP_TIMER_FREQUENCY 1000 // (Hz) Temperature ISR frequency #define STEPPER_TIMER_RATE HAL_TIMER_RATE / 10 // 100khz roughly #define STEPPER_TIMER_TICKS_PER_US (0.1) // fixed value as we use a microsecond timesource #define STEPPER_TIMER_PRESCALE (10) -#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer -#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer +#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#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_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(MF_TIMER_TEMP) +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP) #ifndef HAL_STEP_TIMER_ISR diff --git a/Marlin/src/HAL/SAMD21/timers.h b/Marlin/src/HAL/SAMD21/timers.h index ee193e8137..c558b89791 100644 --- a/Marlin/src/HAL/SAMD21/timers.h +++ b/Marlin/src/HAL/SAMD21/timers.h @@ -49,15 +49,15 @@ typedef uint32_t hal_timer_t; #define MF_TIMER_TEMP MF_TIMER_RTC // Timer Index for Temperature #endif -#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency +#define TEMP_TIMER_FREQUENCY 1000 // (Hz) Temperature ISR frequency -#define STEPPER_TIMER_RATE HAL_TIMER_RATE // frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) -#define STEPPER_TIMER_TICKS_PER_US (STEPPER_TIMER_RATE / 1000000) // stepper timer ticks per µs +#define STEPPER_TIMER_RATE HAL_TIMER_RATE // (Hz) Frequency of Stepper Timer ISR (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) +#define STEPPER_TIMER_TICKS_PER_US (STEPPER_TIMER_RATE / 1000000) // (MHz) Stepper Timer ticks per µs #define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US) -#define PULSE_TIMER_RATE STEPPER_TIMER_RATE -#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer +#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE #define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) #define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP) diff --git a/Marlin/src/HAL/SAMD51/timers.h b/Marlin/src/HAL/SAMD51/timers.h index 2b02ad8775..d39ac0254a 100644 --- a/Marlin/src/HAL/SAMD51/timers.h +++ b/Marlin/src/HAL/SAMD51/timers.h @@ -48,15 +48,15 @@ typedef uint32_t hal_timer_t; #define MF_TIMER_TEMP MF_TIMER_RTC // Timer Index for Temperature #endif -#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency +#define TEMP_TIMER_FREQUENCY 1000 // (Hz) Temperature ISR frequency -#define STEPPER_TIMER_RATE HAL_TIMER_RATE // frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) -#define STEPPER_TIMER_TICKS_PER_US (STEPPER_TIMER_RATE / 1000000) // stepper timer ticks per µs +#define STEPPER_TIMER_RATE HAL_TIMER_RATE // (Hz) Frequency of Stepper Timer ISR (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) +#define STEPPER_TIMER_TICKS_PER_US (STEPPER_TIMER_RATE / 1000000) // (MHz) Stepper Timer ticks per µs #define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US) -#define PULSE_TIMER_RATE STEPPER_TIMER_RATE -#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer +#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE #define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) #define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP) diff --git a/Marlin/src/HAL/STM32/timers.h b/Marlin/src/HAL/STM32/timers.h index 70e0bcd4a5..c8c4845d98 100644 --- a/Marlin/src/HAL/STM32/timers.h +++ b/Marlin/src/HAL/STM32/timers.h @@ -54,17 +54,17 @@ #define STEPPER_TIMER_RATE 2000000 // 2 Mhz extern uint32_t GetStepperTimerClkFreq(); #define STEPPER_TIMER_PRESCALE (GetStepperTimerClkFreq() / (STEPPER_TIMER_RATE)) -#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs +#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) // (MHz) Stepper Timer ticks per µs -#define PULSE_TIMER_RATE STEPPER_TIMER_RATE -#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer +#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#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_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(MF_TIMER_TEMP) +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP) extern void Step_Handler(); diff --git a/Marlin/src/HAL/STM32F1/timers.h b/Marlin/src/HAL/STM32F1/timers.h index b87d355922..10ee2e4f9e 100644 --- a/Marlin/src/HAL/STM32F1/timers.h +++ b/Marlin/src/HAL/STM32F1/timers.h @@ -95,27 +95,27 @@ typedef uint16_t hal_timer_t; #define TEMP_TIMER_IRQ_PRIO 3 #define SERVO0_TIMER_IRQ_PRIO 1 -#define TEMP_TIMER_PRESCALE 1000 // prescaler for setting Temp timer, 72Khz -#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency +#define TEMP_TIMER_PRESCALE 1000 // Prescaler for setting Temp Timer, 72Khz +#define TEMP_TIMER_FREQUENCY 1000 // (Hz) Temperature ISR frequency -#define STEPPER_TIMER_PRESCALE 18 // prescaler for setting stepper timer, 4Mhz -#define STEPPER_TIMER_RATE (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) // frequency of stepper timer -#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs +#define STEPPER_TIMER_PRESCALE 18 // Prescaler for setting stepper timer, 4Mhz +#define STEPPER_TIMER_RATE (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) // (Hz) Frequency of Stepper Timer ISR +#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) // (MHz) Stepper Timer ticks per µs -#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer -#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer #define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE timer_dev* HAL_get_timer_dev(int number); #define TIMER_DEV(num) HAL_get_timer_dev(num) #define STEP_TIMER_DEV TIMER_DEV(MF_TIMER_STEP) #define TEMP_TIMER_DEV TIMER_DEV(MF_TIMER_TEMP) -#define ENABLE_STEPPER_DRIVER_INTERRUPT() timer_enable_irq(STEP_TIMER_DEV, STEP_TIMER_CHAN) -#define DISABLE_STEPPER_DRIVER_INTERRUPT() timer_disable_irq(STEP_TIMER_DEV, STEP_TIMER_CHAN) -#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) +#define ENABLE_STEPPER_DRIVER_INTERRUPT() timer_enable_irq(STEP_TIMER_DEV, STEP_TIMER_CHAN) +#define DISABLE_STEPPER_DRIVER_INTERRUPT() timer_disable_irq(STEP_TIMER_DEV, STEP_TIMER_CHAN) +#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) -#define ENABLE_TEMPERATURE_INTERRUPT() timer_enable_irq(TEMP_TIMER_DEV, TEMP_TIMER_CHAN) +#define ENABLE_TEMPERATURE_INTERRUPT() timer_enable_irq(TEMP_TIMER_DEV, TEMP_TIMER_CHAN) #define DISABLE_TEMPERATURE_INTERRUPT() timer_disable_irq(TEMP_TIMER_DEV, TEMP_TIMER_CHAN) #define HAL_timer_get_count(timer_num) timer_get_count(TIMER_DEV(timer_num)) diff --git a/Marlin/src/HAL/TEENSY31_32/timers.h b/Marlin/src/HAL/TEENSY31_32/timers.h index 84281a228f..7de8cccde4 100644 --- a/Marlin/src/HAL/TEENSY31_32/timers.h +++ b/Marlin/src/HAL/TEENSY31_32/timers.h @@ -58,19 +58,19 @@ typedef uint32_t hal_timer_t; #define TEMP_TIMER_FREQUENCY 1000 -#define STEPPER_TIMER_RATE HAL_TIMER_RATE -#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) -#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US) +#define STEPPER_TIMER_RATE HAL_TIMER_RATE +#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) +#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US) -#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer -#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer +#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#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_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(MF_TIMER_TEMP) +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP) #ifndef HAL_STEP_TIMER_ISR diff --git a/Marlin/src/HAL/TEENSY35_36/timers.h b/Marlin/src/HAL/TEENSY35_36/timers.h index c7292f3619..60b35faa38 100644 --- a/Marlin/src/HAL/TEENSY35_36/timers.h +++ b/Marlin/src/HAL/TEENSY35_36/timers.h @@ -58,19 +58,19 @@ typedef uint32_t hal_timer_t; #define TEMP_TIMER_FREQUENCY 1000 -#define STEPPER_TIMER_RATE HAL_TIMER_RATE -#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) -#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US) +#define STEPPER_TIMER_RATE HAL_TIMER_RATE +#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) +#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US) -#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer -#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer +#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#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_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(MF_TIMER_TEMP) +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP) #ifndef HAL_STEP_TIMER_ISR diff --git a/Marlin/src/HAL/TEENSY40_41/timers.h b/Marlin/src/HAL/TEENSY40_41/timers.h index 98a852ee57..49b5c32836 100644 --- a/Marlin/src/HAL/TEENSY40_41/timers.h +++ b/Marlin/src/HAL/TEENSY40_41/timers.h @@ -59,18 +59,18 @@ 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_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) #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 -#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer +#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#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_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(MF_TIMER_TEMP) +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP) #ifndef HAL_STEP_TIMER_ISR From 584abc5835e6b5db2483379ccaba10bc4a136d22 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 27 Nov 2025 12:48:54 -0600 Subject: [PATCH 16/47] =?UTF-8?q?=F0=9F=8E=A8=20"controllerfan"?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/temperature.cpp | 8 ++++---- Marlin/src/module/temperature.h | 2 +- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 8d63e226b9..d56937d513 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -410,7 +410,7 @@ PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED); #endif #if ALL(FAN_SOFT_PWM, USE_CONTROLLER_FAN) - uint8_t Temperature::soft_pwm_controller_speed = FAN_OFF_PWM; + uint8_t Temperature::soft_pwm_controllerfan_speed = FAN_OFF_PWM; #endif // Init fans according to whether they're native PWM or Software PWM @@ -4038,7 +4038,7 @@ void Temperature::isr() { #endif #if ALL(FAN_SOFT_PWM, USE_CONTROLLER_FAN) - static SoftPWM soft_pwm_controller; + static SoftPWM soft_pwm_controllerfan; #endif #define WRITE_FAN(n, v) WRITE(FAN##n##_PIN, (v) ^ ENABLED(FAN_INVERTING)) @@ -4076,7 +4076,7 @@ void Temperature::isr() { #if ENABLED(FAN_SOFT_PWM) #if ENABLED(USE_CONTROLLER_FAN) - WRITE(CONTROLLER_FAN_PIN, soft_pwm_controller.add(pwm_mask, controllerFan.soft_pwm_speed)); + WRITE(CONTROLLER_FAN_PIN, soft_pwm_controllerfan.add(pwm_mask, controllerFan.soft_pwm_speed)); #endif #define _FAN_PWM(N) do{ \ @@ -4132,7 +4132,7 @@ void Temperature::isr() { if (soft_pwm_count_fan[7] <= pwm_count_tmp) WRITE_FAN(7, LOW); #endif #if ENABLED(USE_CONTROLLER_FAN) - if (soft_pwm_controller.count <= pwm_count_tmp) WRITE(CONTROLLER_FAN_PIN, LOW); + if (soft_pwm_controllerfan.count <= pwm_count_tmp) WRITE(CONTROLLER_FAN_PIN, LOW); #endif #endif } diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index 884a72646e..f2ef4d0f6c 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -686,7 +686,7 @@ class Temperature { #endif #if ALL(FAN_SOFT_PWM, USE_CONTROLLER_FAN) - static uint8_t soft_pwm_controller_speed; + static uint8_t soft_pwm_controllerfan_speed; #endif #if ALL(HAS_MARLINUI_MENU, PREVENT_COLD_EXTRUSION) && E_MANUAL > 0 From 0ac1435a8ca015e0edf2f28999bd6d7535b1cb0a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 27 Nov 2025 12:48:28 -0600 Subject: [PATCH 17/47] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Reduc?= =?UTF-8?q?tion=20via=20TERF?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/fancheck.cpp | 42 ++------ Marlin/src/module/endstops.cpp | 173 ++++++------------------------ Marlin/src/module/stepper.cpp | 110 +++++-------------- Marlin/src/module/temperature.cpp | 100 +++-------------- 4 files changed, 82 insertions(+), 343 deletions(-) diff --git a/Marlin/src/feature/fancheck.cpp b/Marlin/src/feature/fancheck.cpp index 4978b8c999..339eb16aa9 100644 --- a/Marlin/src/feature/fancheck.cpp +++ b/Marlin/src/feature/fancheck.cpp @@ -42,30 +42,18 @@ bool FanCheck::enabled; void FanCheck::init() { #define _TACHINIT(N) TERN(E##N##_FAN_TACHO_PULLUP, SET_INPUT_PULLUP, TERN(E##N##_FAN_TACHO_PULLDOWN, SET_INPUT_PULLDOWN, SET_INPUT))(E##N##_FAN_TACHO_PIN) - TERF(HAS_E0_FAN_TACHO, _TACHINIT)(0); - TERF(HAS_E1_FAN_TACHO, _TACHINIT)(1); - TERF(HAS_E2_FAN_TACHO, _TACHINIT)(2); - TERF(HAS_E3_FAN_TACHO, _TACHINIT)(3); - TERF(HAS_E4_FAN_TACHO, _TACHINIT)(4); - TERF(HAS_E5_FAN_TACHO, _TACHINIT)(5); - TERF(HAS_E6_FAN_TACHO, _TACHINIT)(6); - TERF(HAS_E7_FAN_TACHO, _TACHINIT)(7); + #define _EN_TACHINIT(N) TERF(HAS_E##N##_FAN_TACHO, _TACHINIT)(N); + REPEAT(8, _EN_TACHINIT); } void FanCheck::update_tachometers() { bool status; - #define _TACHO_CASE(N) case N: status = READ(E##N##_FAN_TACHO_PIN); break; + #define __TACHO_GET_STATUS(N) case N: status = READ(E##N##_FAN_TACHO_PIN); break; + #define _TACHO_GET_STATUS(N) TERF(HAS_E##N##_FAN_TACHO, __TACHO_GET_STATUS)(N) for (uint8_t f = 0; f < TACHO_COUNT; ++f) { switch (f) { - TERF(HAS_E0_FAN_TACHO, _TACHO_CASE)(0) - TERF(HAS_E1_FAN_TACHO, _TACHO_CASE)(1) - TERF(HAS_E2_FAN_TACHO, _TACHO_CASE)(2) - TERF(HAS_E3_FAN_TACHO, _TACHO_CASE)(3) - TERF(HAS_E4_FAN_TACHO, _TACHO_CASE)(4) - TERF(HAS_E5_FAN_TACHO, _TACHO_CASE)(5) - TERF(HAS_E6_FAN_TACHO, _TACHO_CASE)(6) - TERF(HAS_E7_FAN_TACHO, _TACHO_CASE)(7) + REPEAT(8, _TACHO_GET_STATUS) default: continue; } @@ -83,14 +71,8 @@ void FanCheck::compute_speed(uint16_t elapsedTime) { uint8_t fan_error_msk = 0; for (uint8_t f = 0; f < TACHO_COUNT; ++f) { switch (f) { - TERN_(HAS_E0_FAN_TACHO, case 0:) - TERN_(HAS_E1_FAN_TACHO, case 1:) - TERN_(HAS_E2_FAN_TACHO, case 2:) - TERN_(HAS_E3_FAN_TACHO, case 3:) - TERN_(HAS_E4_FAN_TACHO, case 4:) - TERN_(HAS_E5_FAN_TACHO, case 5:) - TERN_(HAS_E6_FAN_TACHO, case 6:) - TERN_(HAS_E7_FAN_TACHO, case 7:) + #define _EN_COMPUTE_FAN_CASE(N) TERN_(HAS_E##N##_FAN_TACHO, case N:) + REPEAT(8, _EN_COMPUTE_FAN_CASE) // Compute fan speed rps[f] = edge_counter[f] * float(250) / elapsedTime; edge_counter[f] = 0; @@ -147,14 +129,8 @@ void FanCheck::print_fan_states() { for (uint8_t s = 0; s < 2; ++s) { for (uint8_t f = 0; f < TACHO_COUNT; ++f) { switch (f) { - TERN_(HAS_E0_FAN_TACHO, case 0:) - TERN_(HAS_E1_FAN_TACHO, case 1:) - TERN_(HAS_E2_FAN_TACHO, case 2:) - TERN_(HAS_E3_FAN_TACHO, case 3:) - TERN_(HAS_E4_FAN_TACHO, case 4:) - TERN_(HAS_E5_FAN_TACHO, case 5:) - TERN_(HAS_E6_FAN_TACHO, case 6:) - TERN_(HAS_E7_FAN_TACHO, case 7:) + #define _EN_PRINT_FAN_CASE(N) TERN_(HAS_E##N##_FAN_TACHO, case N:) + REPEAT(8, _EN_PRINT_FAN_CASE) SERIAL_ECHOPGM("E", f); if (s == 0) SERIAL_ECHOPGM(":", 60 * rps[f], " RPM "); diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 31b877b642..821bb2df48 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -133,34 +133,9 @@ Endstops::endstop_mask_t Endstops::live_state = 0; void Endstops::init() { #define _INIT_ENDSTOP(T,A,N) TERN(ENDSTOPPULLUP_##A##T, SET_INPUT_PULLUP, TERN(ENDSTOPPULLDOWN_##A##T, SET_INPUT_PULLDOWN, SET_INPUT))(A##N##_##T##_PIN) - TERF(USE_X_MIN, _INIT_ENDSTOP)(MIN,X,); - TERF(USE_X_MAX, _INIT_ENDSTOP)(MAX,X,); - TERF(USE_X2_MIN, _INIT_ENDSTOP)(MIN,X,2); - TERF(USE_X2_MAX, _INIT_ENDSTOP)(MAX,X,2); - TERF(USE_Y_MIN, _INIT_ENDSTOP)(MIN,Y,); - TERF(USE_Y_MAX, _INIT_ENDSTOP)(MAX,Y,); - TERF(USE_Y2_MIN, _INIT_ENDSTOP)(MIN,Y,2); - TERF(USE_Y2_MAX, _INIT_ENDSTOP)(MAX,Y,2); - TERF(USE_Z_MIN, _INIT_ENDSTOP)(MIN,Z,); - TERF(USE_Z_MAX, _INIT_ENDSTOP)(MAX,Z,); - TERF(USE_Z2_MIN, _INIT_ENDSTOP)(MIN,Z,2); - TERF(USE_Z2_MAX, _INIT_ENDSTOP)(MAX,Z,2); - TERF(USE_Z3_MIN, _INIT_ENDSTOP)(MIN,Z,3); - TERF(USE_Z3_MAX, _INIT_ENDSTOP)(MAX,Z,3); - TERF(USE_Z4_MIN, _INIT_ENDSTOP)(MIN,Z,4); - TERF(USE_Z4_MAX, _INIT_ENDSTOP)(MAX,Z,4); - TERF(USE_I_MIN, _INIT_ENDSTOP)(MIN,I,); - TERF(USE_I_MAX, _INIT_ENDSTOP)(MAX,I,); - TERF(USE_J_MIN, _INIT_ENDSTOP)(MIN,J,); - TERF(USE_J_MAX, _INIT_ENDSTOP)(MAX,J,); - TERF(USE_K_MIN, _INIT_ENDSTOP)(MIN,K,); - TERF(USE_K_MAX, _INIT_ENDSTOP)(MAX,K,); - TERF(USE_U_MIN, _INIT_ENDSTOP)(MIN,U,); - TERF(USE_U_MAX, _INIT_ENDSTOP)(MAX,U,); - TERF(USE_V_MIN, _INIT_ENDSTOP)(MIN,V,); - TERF(USE_V_MAX, _INIT_ENDSTOP)(MAX,V,); - TERF(USE_W_MIN, _INIT_ENDSTOP)(MIN,W,); - TERF(USE_W_MAX, _INIT_ENDSTOP)(MAX,W,); + #define _INIT_ES_MINMAX(A,N) do{ TERF(USE_##A##N##_MIN, _INIT_ENDSTOP)(MIN,A,N); TERF(USE_##A##N##_MAX, _INIT_ENDSTOP)(MAX,A,N); }while(0); + #define INIT_AXIS_ENDSTOPS(S) do{ _INIT_ES_MINMAX(S, ); _INIT_ES_MINMAX(S,2); _INIT_ES_MINMAX(S,3); _INIT_ES_MINMAX(S,4); }while(0); + MAIN_AXIS_MAP(INIT_AXIS_ENDSTOPS); #if USE_CALIBRATION #if ENABLED(CALIBRATION_PIN_PULLUP) @@ -399,37 +374,15 @@ void Endstops::event_handler() { #endif void __O2 Endstops::report_states() { + TERN_(BLTOUCH, bltouch._set_SW_mode()); + SERIAL_ECHOLNPGM(STR_M119_REPORT); - #define ES_REPORT(S) print_es_state(READ_ENDSTOP(S##_PIN) == S##_ENDSTOP_HIT_STATE, F(STR_##S)) - TERF(USE_X_MIN, ES_REPORT)(X_MIN); - TERF(USE_X2_MIN, ES_REPORT)(X2_MIN); - TERF(USE_X_MAX, ES_REPORT)(X_MAX); - TERF(USE_X2_MAX, ES_REPORT)(X2_MAX); - TERF(USE_Y_MIN, ES_REPORT)(Y_MIN); - TERF(USE_Y2_MIN, ES_REPORT)(Y2_MIN); - TERF(USE_Y_MAX, ES_REPORT)(Y_MAX); - TERF(USE_Y2_MAX, ES_REPORT)(Y2_MAX); - TERF(USE_Z_MIN, ES_REPORT)(Z_MIN); - TERF(USE_Z2_MIN, ES_REPORT)(Z2_MIN); - TERF(USE_Z3_MIN, ES_REPORT)(Z3_MIN); - TERF(USE_Z4_MIN, ES_REPORT)(Z4_MIN); - TERF(USE_Z_MAX, ES_REPORT)(Z_MAX); - TERF(USE_Z2_MAX, ES_REPORT)(Z2_MAX); - TERF(USE_Z3_MAX, ES_REPORT)(Z3_MAX); - TERF(USE_Z4_MAX, ES_REPORT)(Z4_MAX); - TERF(USE_I_MIN, ES_REPORT)(I_MIN); - TERF(USE_I_MAX, ES_REPORT)(I_MAX); - TERF(USE_J_MIN, ES_REPORT)(J_MIN); - TERF(USE_J_MAX, ES_REPORT)(J_MAX); - TERF(USE_K_MIN, ES_REPORT)(K_MIN); - TERF(USE_K_MAX, ES_REPORT)(K_MAX); - TERF(USE_U_MIN, ES_REPORT)(U_MIN); - TERF(USE_U_MAX, ES_REPORT)(U_MAX); - TERF(USE_V_MIN, ES_REPORT)(V_MIN); - TERF(USE_V_MAX, ES_REPORT)(V_MAX); - TERF(USE_W_MIN, ES_REPORT)(W_MIN); - TERF(USE_W_MAX, ES_REPORT)(W_MAX); + + #define _ES_REPORT(S) print_es_state(READ_ENDSTOP(S##_PIN) == S##_ENDSTOP_HIT_STATE, F(STR_##S)) + #define ES_REPORT(S) TERF(USE_##S, _ES_REPORT)(S); + MAP(ES_REPORT, X_MIN, X2_MIN, X_MAX, X2_MAX, Y_MIN, Y2_MIN, Y_MAX, Y2_MAX, Z_MIN, Z2_MIN, Z3_MIN, Z4_MIN, Z_MAX, Z2_MAX, Z3_MAX, Z4_MAX); + MAP(ES_REPORT, I_MIN, I_MAX, J_MIN, J_MAX, K_MIN, K_MAX, U_MIN, U_MAX, V_MIN, V_MAX, W_MIN, W_MAX) TERF(PROBE_ACTIVATION_SWITCH, print_es_state)(probe_switch_activated(), F(STR_PROBE_EN)); @@ -605,18 +558,8 @@ void Endstops::update() { COPY_LIVE_STATE(Z_MAX, Z4_MAX); #endif - TERF(USE_I_MIN, UPDATE_LIVE_STATE)(I, MIN); - TERF(USE_I_MAX, UPDATE_LIVE_STATE)(I, MAX); - TERF(USE_J_MIN, UPDATE_LIVE_STATE)(J, MIN); - TERF(USE_J_MAX, UPDATE_LIVE_STATE)(J, MAX); - TERF(USE_K_MIN, UPDATE_LIVE_STATE)(K, MIN); - TERF(USE_K_MAX, UPDATE_LIVE_STATE)(K, MAX); - TERF(USE_U_MIN, UPDATE_LIVE_STATE)(U, MIN); - TERF(USE_U_MAX, UPDATE_LIVE_STATE)(U, MAX); - TERF(USE_V_MIN, UPDATE_LIVE_STATE)(V, MIN); - TERF(USE_V_MAX, UPDATE_LIVE_STATE)(V, MAX); - TERF(USE_W_MIN, UPDATE_LIVE_STATE)(W, MIN); - TERF(USE_W_MAX, UPDATE_LIVE_STATE)(W, MAX); + #define _LIVE_UPDATE(A) TERF(USE_##A##_MIN, UPDATE_LIVE_STATE)(A, MIN); TERF(USE_##A##_MAX, UPDATE_LIVE_STATE)(A, MAX); + SECONDARY_AXIS_MAP(_LIVE_UPDATE); #if ENDSTOP_NOISE_THRESHOLD @@ -1039,15 +982,19 @@ void Endstops::update() { } void Endstops::clear_endstop_state() { - TERN_(X_SPI_SENSORLESS, CBI(live_state, X_ENDSTOP)); + + #define _ES_CLEAR(S) CBI(live_state, S##_ENDSTOP); + #define ES_CLEAR(S) TERN_(S##_SPI_SENSORLESS, CBI(live_state, S##_ENDSTOP)); + + ES_CLEAR(X); #if ALL(X_SPI_SENSORLESS, X_DUAL_ENDSTOPS) CBI(live_state, X2_ENDSTOP); #endif - TERN_(Y_SPI_SENSORLESS, CBI(live_state, Y_ENDSTOP)); + ES_CLEAR(Y); #if ALL(Y_SPI_SENSORLESS, Y_DUAL_ENDSTOPS) CBI(live_state, Y2_ENDSTOP); #endif - TERN_(Z_SPI_SENSORLESS, CBI(live_state, Z_ENDSTOP)); + ES_CLEAR(Z); #if ALL(Z_SPI_SENSORLESS, Z_MULTI_ENDSTOPS) CBI(live_state, Z2_ENDSTOP); #if NUM_Z_STEPPERS >= 3 @@ -1057,12 +1004,7 @@ void Endstops::update() { #endif #endif #endif - TERN_(I_SPI_SENSORLESS, CBI(live_state, I_ENDSTOP)); - TERN_(J_SPI_SENSORLESS, CBI(live_state, J_ENDSTOP)); - TERN_(K_SPI_SENSORLESS, CBI(live_state, K_ENDSTOP)); - TERN_(U_SPI_SENSORLESS, CBI(live_state, U_ENDSTOP)); - TERN_(V_SPI_SENSORLESS, CBI(live_state, V_ENDSTOP)); - TERN_(W_SPI_SENSORLESS, CBI(live_state, W_ENDSTOP)); + SECONDARY_AXIS_MAP(ES_CLEAR); } #endif // SPI_ENDSTOPS @@ -1086,73 +1028,22 @@ void Endstops::update() { static uint8_t local_LED_status = 0; uint16_t live_state_local = 0; - #define ES_GET_STATE(S) if (READ_ENDSTOP(S##_PIN)) SBI(live_state_local, S) - TERF(USE_X_MIN, ES_GET_STATE)(X_MIN); - TERF(USE_X_MAX, ES_GET_STATE)(X_MAX); - TERF(USE_Y_MIN, ES_GET_STATE)(Y_MIN); - TERF(USE_Y_MAX, ES_GET_STATE)(Y_MAX); - TERF(USE_Z_MIN, ES_GET_STATE)(Z_MIN); - TERF(USE_Z_MAX, ES_GET_STATE)(Z_MAX); - TERF(USE_Z_MIN_PROBE, ES_GET_STATE)(Z_MIN_PROBE); - TERF(USE_CALIBRATION, ES_GET_STATE)(CALIBRATION); - TERF(USE_X2_MIN, ES_GET_STATE)(X2_MIN); - TERF(USE_X2_MAX, ES_GET_STATE)(X2_MAX); - TERF(USE_Y2_MIN, ES_GET_STATE)(Y2_MIN); - TERF(USE_Y2_MAX, ES_GET_STATE)(Y2_MAX); - TERF(USE_Z2_MIN, ES_GET_STATE)(Z2_MIN); - TERF(USE_Z2_MAX, ES_GET_STATE)(Z2_MAX); - TERF(USE_Z3_MIN, ES_GET_STATE)(Z3_MIN); - TERF(USE_Z3_MAX, ES_GET_STATE)(Z3_MAX); - TERF(USE_Z4_MIN, ES_GET_STATE)(Z4_MIN); - TERF(USE_Z4_MAX, ES_GET_STATE)(Z4_MAX); - TERF(USE_I_MAX, ES_GET_STATE)(I_MAX); - TERF(USE_I_MIN, ES_GET_STATE)(I_MIN); - TERF(USE_J_MAX, ES_GET_STATE)(J_MAX); - TERF(USE_J_MIN, ES_GET_STATE)(J_MIN); - TERF(USE_K_MAX, ES_GET_STATE)(K_MAX); - TERF(USE_K_MIN, ES_GET_STATE)(K_MIN); - TERF(USE_U_MAX, ES_GET_STATE)(U_MAX); - TERF(USE_U_MIN, ES_GET_STATE)(U_MIN); - TERF(USE_V_MAX, ES_GET_STATE)(V_MAX); - TERF(USE_V_MIN, ES_GET_STATE)(V_MIN); - TERF(USE_W_MAX, ES_GET_STATE)(W_MAX); - TERF(USE_W_MIN, ES_GET_STATE)(W_MIN); + #define _ES_GET_STATE(S) if (READ_ENDSTOP(S##_PIN)) SBI(live_state_local, S); + #define ES_GET_STATE(S) TERF(USE_##S, _ES_GET_STATE)(S) + MAP(ES_GET_STATE, X_MIN, X_MAX, Y_MIN, Y_MAX, Z_MIN, Z_MAX); + MAP(ES_GET_STATE, Z_MIN_PROBE, CALIBRATION); + MAP(ES_GET_STATE, X2_MIN, X2_MAX, Y2_MIN, Y2_MAX, Z2_MIN, Z2_MAX, Z3_MIN, Z3_MAX, Z4_MIN, Z4_MAX) + MAP(ES_GET_STATE, I_MIN, I_MAX, J_MIN, J_MAX, K_MIN, K_MAX, U_MIN, U_MAX, V_MIN, V_MAX, W_MIN, W_MAX); const uint16_t endstop_change = live_state_local ^ old_live_state_local; - #define ES_REPORT_CHANGE(S) if (TEST(endstop_change, S)) SERIAL_ECHOPGM(" " STRINGIFY(S) ":", TEST(live_state_local, S)) + #define _ES_REPORT_CHANGE(S) SERIAL_ECHO(F(" " STRINGIFY(S) ":"), TEST(live_state_local, S)); + #define ES_REPORT_CHANGE(S) TERF(USE_##S, _ES_REPORT_CHANGE)(S) if (endstop_change) { - TERF(USE_X_MIN, ES_REPORT_CHANGE)(X_MIN); - TERF(USE_X_MAX, ES_REPORT_CHANGE)(X_MAX); - TERF(USE_Y_MIN, ES_REPORT_CHANGE)(Y_MIN); - TERF(USE_Y_MAX, ES_REPORT_CHANGE)(Y_MAX); - TERF(USE_Z_MIN, ES_REPORT_CHANGE)(Z_MIN); - TERF(USE_Z_MAX, ES_REPORT_CHANGE)(Z_MAX); - TERF(USE_Z_MIN_PROBE, ES_REPORT_CHANGE)(Z_MIN_PROBE); - TERF(USE_CALIBRATION, ES_REPORT_CHANGE)(CALIBRATION); - TERF(USE_X2_MIN, ES_REPORT_CHANGE)(X2_MIN); - TERF(USE_X2_MAX, ES_REPORT_CHANGE)(X2_MAX); - TERF(USE_Y2_MIN, ES_REPORT_CHANGE)(Y2_MIN); - TERF(USE_Y2_MAX, ES_REPORT_CHANGE)(Y2_MAX); - TERF(USE_Z2_MIN, ES_REPORT_CHANGE)(Z2_MIN); - TERF(USE_Z2_MAX, ES_REPORT_CHANGE)(Z2_MAX); - TERF(USE_Z3_MIN, ES_REPORT_CHANGE)(Z3_MIN); - TERF(USE_Z3_MAX, ES_REPORT_CHANGE)(Z3_MAX); - TERF(USE_Z4_MIN, ES_REPORT_CHANGE)(Z4_MIN); - TERF(USE_Z4_MAX, ES_REPORT_CHANGE)(Z4_MAX); - TERF(USE_I_MIN, ES_REPORT_CHANGE)(I_MIN); - TERF(USE_I_MAX, ES_REPORT_CHANGE)(I_MAX); - TERF(USE_J_MIN, ES_REPORT_CHANGE)(J_MIN); - TERF(USE_J_MAX, ES_REPORT_CHANGE)(J_MAX); - TERF(USE_K_MIN, ES_REPORT_CHANGE)(K_MIN); - TERF(USE_K_MAX, ES_REPORT_CHANGE)(K_MAX); - TERF(USE_U_MIN, ES_REPORT_CHANGE)(U_MIN); - TERF(USE_U_MAX, ES_REPORT_CHANGE)(U_MAX); - TERF(USE_V_MIN, ES_REPORT_CHANGE)(V_MIN); - TERF(USE_V_MAX, ES_REPORT_CHANGE)(V_MAX); - TERF(USE_W_MIN, ES_REPORT_CHANGE)(W_MIN); - TERF(USE_W_MAX, ES_REPORT_CHANGE)(W_MAX); - + MAP(ES_REPORT_CHANGE, X_MIN, X_MAX, Y_MIN, Y_MAX, Z_MIN, Z_MAX, + , Z_MIN_PROBE, CALIBRATION, + , X2_MIN, X2_MAX, Y2_MIN, Y2_MAX, Z2_MIN, Z2_MAX, Z3_MIN, Z3_MAX, Z4_MIN, Z4_MAX, + , I_MIN, I_MAX, J_MIN, J_MAX, K_MIN, K_MAX, U_MIN, U_MAX, V_MIN, V_MAX, W_MIN, W_MAX); SERIAL_ECHOLNPGM("\n"); hal.set_pwm_duty(pin_t(LED_PIN), local_LED_status); local_LED_status ^= 255; diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 00ba63c966..cb1926c318 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -2041,15 +2041,8 @@ void Stepper::pulse_phase_isr() { const uint32_t advance_divisor_cached = advance_divisor; // Determine if pulses are needed - TERF(HAS_X_STEP, PULSE_PREP)(X); - TERF(HAS_Y_STEP, PULSE_PREP)(Y); - TERF(HAS_Z_STEP, PULSE_PREP)(Z); - TERF(HAS_I_STEP, PULSE_PREP)(I); - TERF(HAS_J_STEP, PULSE_PREP)(J); - TERF(HAS_K_STEP, PULSE_PREP)(K); - TERF(HAS_U_STEP, PULSE_PREP)(U); - TERF(HAS_V_STEP, PULSE_PREP)(V); - TERF(HAS_W_STEP, PULSE_PREP)(W); + #define _PULSE_PREP(A) TERF(HAS_##A##_STEP, PULSE_PREP)(A); + MAIN_AXIS_MAP(_PULSE_PREP); #if ANY(HAS_E0_STEP, MIXING_EXTRUDER) PULSE_PREP(E); @@ -2099,15 +2092,8 @@ void Stepper::pulse_phase_isr() { #endif // Pulse start - TERF(HAS_X_STEP, PULSE_START)(X); - TERF(HAS_Y_STEP, PULSE_START)(Y); - TERF(HAS_Z_STEP, PULSE_START)(Z); - TERF(HAS_I_STEP, PULSE_START)(I); - TERF(HAS_J_STEP, PULSE_START)(J); - TERF(HAS_K_STEP, PULSE_START)(K); - TERF(HAS_U_STEP, PULSE_START)(U); - TERF(HAS_V_STEP, PULSE_START)(V); - TERF(HAS_W_STEP, PULSE_START)(W); + #define _PULSE_START(A) TERF(HAS_##A##_STEP, PULSE_START)(A); + MAIN_AXIS_MAP(_PULSE_START); #if ENABLED(MIXING_EXTRUDER) if (step_needed.e) { @@ -2127,15 +2113,8 @@ void Stepper::pulse_phase_isr() { #endif // Pulse stop - TERF(HAS_X_STEP, PULSE_STOP)(X); - TERF(HAS_Y_STEP, PULSE_STOP)(Y); - TERF(HAS_Z_STEP, PULSE_STOP)(Z); - TERF(HAS_I_STEP, PULSE_STOP)(I); - TERF(HAS_J_STEP, PULSE_STOP)(J); - TERF(HAS_K_STEP, PULSE_STOP)(K); - TERF(HAS_U_STEP, PULSE_STOP)(U); - TERF(HAS_V_STEP, PULSE_STOP)(V); - TERF(HAS_W_STEP, PULSE_STOP)(W); + #define _PULSE_STOP(A) TERF(HAS_##A##_STEP, PULSE_STOP)(A); + MAIN_AXIS_MAP(_PULSE_STOP); #if ENABLED(MIXING_EXTRUDER) if (step_needed.e) E_STEP_WRITE(mixer.get_stepper(), !STEP_STATE_E); @@ -3231,53 +3210,21 @@ void Stepper::init() { TERN_(HAS_MICROSTEPS, microstep_init()); // Init Dir Pins - TERN_(HAS_X_DIR, X_DIR_INIT()); - TERN_(HAS_X2_DIR, X2_DIR_INIT()); - TERN_(HAS_Y_DIR, Y_DIR_INIT()); - TERN_(HAS_Y2_DIR, Y2_DIR_INIT()); - TERN_(HAS_Z_DIR, Z_DIR_INIT()); - TERN_(HAS_Z2_DIR, Z2_DIR_INIT()); - TERN_(HAS_Z3_DIR, Z3_DIR_INIT()); - TERN_(HAS_Z4_DIR, Z4_DIR_INIT()); - TERN_(HAS_I_DIR, I_DIR_INIT()); - TERN_(HAS_J_DIR, J_DIR_INIT()); - TERN_(HAS_K_DIR, K_DIR_INIT()); - TERN_(HAS_U_DIR, U_DIR_INIT()); - TERN_(HAS_V_DIR, V_DIR_INIT()); - TERN_(HAS_W_DIR, W_DIR_INIT()); - TERN_(HAS_E0_DIR, E0_DIR_INIT()); - TERN_(HAS_E1_DIR, E1_DIR_INIT()); - TERN_(HAS_E2_DIR, E2_DIR_INIT()); - TERN_(HAS_E3_DIR, E3_DIR_INIT()); - TERN_(HAS_E4_DIR, E4_DIR_INIT()); - TERN_(HAS_E5_DIR, E5_DIR_INIT()); - TERN_(HAS_E6_DIR, E6_DIR_INIT()); - TERN_(HAS_E7_DIR, E7_DIR_INIT()); + #define _INIT_DIR(A) TERN_(HAS_##A##_DIR, A##_DIR_INIT()); + #define _EN_INIT_DIR(N) _INIT_DIR(E##N) + MAIN_AXIS_MAP(_INIT_DIR); + MAP(_INIT_DIR, X2, Y2, Z2, Z3, Z4); + REPEAT(8, _EN_INIT_DIR); // Init Enable Pins - Steppers default to disabled. - #define _INIT_CONFIG_ENABLE(A) do{ A##_ENABLE_INIT(); if (A##_ENABLE_INIT_STATE) A##_ENABLE_WRITE(HIGH); }while(0) - TERN_(HAS_X_ENABLE, _INIT_CONFIG_ENABLE(X)); - TERN_(HAS_X2_ENABLE, _INIT_CONFIG_ENABLE(X2)); - TERN_(HAS_Y_ENABLE, _INIT_CONFIG_ENABLE(Y)); - TERN_(HAS_Y2_ENABLE, _INIT_CONFIG_ENABLE(Y2)); - TERN_(HAS_Z_ENABLE, _INIT_CONFIG_ENABLE(Z)); - TERN_(HAS_Z2_ENABLE, _INIT_CONFIG_ENABLE(Z2)); - TERN_(HAS_Z3_ENABLE, _INIT_CONFIG_ENABLE(Z3)); - TERN_(HAS_Z4_ENABLE, _INIT_CONFIG_ENABLE(Z4)); - TERN_(HAS_I_ENABLE, _INIT_CONFIG_ENABLE(I)); - TERN_(HAS_J_ENABLE, _INIT_CONFIG_ENABLE(J)); - TERN_(HAS_K_ENABLE, _INIT_CONFIG_ENABLE(K)); - TERN_(HAS_U_ENABLE, _INIT_CONFIG_ENABLE(U)); - TERN_(HAS_V_ENABLE, _INIT_CONFIG_ENABLE(V)); - TERN_(HAS_W_ENABLE, _INIT_CONFIG_ENABLE(W)); - TERN_(HAS_E0_ENABLE, _INIT_CONFIG_ENABLE(E0)); - TERN_(HAS_E1_ENABLE, _INIT_CONFIG_ENABLE(E1)); - TERN_(HAS_E2_ENABLE, _INIT_CONFIG_ENABLE(E2)); - TERN_(HAS_E3_ENABLE, _INIT_CONFIG_ENABLE(E3)); - TERN_(HAS_E4_ENABLE, _INIT_CONFIG_ENABLE(E4)); - TERN_(HAS_E5_ENABLE, _INIT_CONFIG_ENABLE(E5)); - TERN_(HAS_E6_ENABLE, _INIT_CONFIG_ENABLE(E6)); - TERN_(HAS_E7_ENABLE, _INIT_CONFIG_ENABLE(E7)); + #define __INIT_ENABLE(A) do{ A##_ENABLE_INIT(); if (A##_ENABLE_INIT_STATE) A##_ENABLE_WRITE(HIGH); }while(0) + + #define _INIT_ENABLE(A) TERF(HAS_##A##_ENABLE, __INIT_ENABLE)(A); + MAIN_AXIS_MAP(_INIT_ENABLE); + MAP(_INIT_ENABLE, X2, Y2, Z2, Z3, Z4); + + #define _EN_INIT_ENABLE(N) TERN_(HAS_E##N##_ENABLE, __INIT_ENABLE(E##N)); + REPEAT(8, _EN_INIT_ENABLE); #define _STEP_INIT(AXIS) AXIS ##_STEP_INIT() #define _WRITE_STEP(AXIS, HIGHLOW) AXIS ##_STEP_WRITE(HIGHLOW) @@ -3322,21 +3269,12 @@ void Stepper::init() { #endif AXIS_INIT(Z, Z); #endif - TERN_(HAS_I_STEP, AXIS_INIT(I, I)); - TERN_(HAS_J_STEP, AXIS_INIT(J, J)); - TERN_(HAS_K_STEP, AXIS_INIT(K, K)); - TERN_(HAS_U_STEP, AXIS_INIT(U, U)); - TERN_(HAS_V_STEP, AXIS_INIT(V, V)); - TERN_(HAS_W_STEP, AXIS_INIT(W, W)); - TERN_(HAS_E0_STEP, E_AXIS_INIT(0)); - TERN_(HAS_E1_STEP, E_AXIS_INIT(1)); - TERN_(HAS_E2_STEP, E_AXIS_INIT(2)); - TERN_(HAS_E3_STEP, E_AXIS_INIT(3)); - TERN_(HAS_E4_STEP, E_AXIS_INIT(4)); - TERN_(HAS_E5_STEP, E_AXIS_INIT(5)); - TERN_(HAS_E6_STEP, E_AXIS_INIT(6)); - TERN_(HAS_E7_STEP, E_AXIS_INIT(7)); + #define _AXIS_INIT(A) TERF(HAS_##A##_STEP, AXIS_INIT)(A, A); + SECONDARY_AXIS_MAP(_AXIS_INIT); + + #define _EN_AXIS_INIT(N) TERF(HAS_E##N##_STEP, E_AXIS_INIT)(N); + REPEAT(8, _EN_AXIS_INIT); #if DISABLED(I2S_STEPPER_STREAM) HAL_timer_start(MF_TIMER_STEP, 122); // Init Stepper ISR to 122 Hz for quick starting diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index d56937d513..6bda47b573 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -3090,14 +3090,8 @@ void Temperature::init() { OUT_WRITE(HEATER_0_PIN, ENABLED(HEATER_0_INVERTING)); #endif #endif - - TERF(HAS_HEATER_1, OUT_WRITE)(HEATER_1_PIN, ENABLED(HEATER_1_INVERTING)); - TERF(HAS_HEATER_2, OUT_WRITE)(HEATER_2_PIN, ENABLED(HEATER_2_INVERTING)); - TERF(HAS_HEATER_3, OUT_WRITE)(HEATER_3_PIN, ENABLED(HEATER_3_INVERTING)); - TERF(HAS_HEATER_4, OUT_WRITE)(HEATER_4_PIN, ENABLED(HEATER_4_INVERTING)); - TERF(HAS_HEATER_5, OUT_WRITE)(HEATER_5_PIN, ENABLED(HEATER_5_INVERTING)); - TERF(HAS_HEATER_6, OUT_WRITE)(HEATER_6_PIN, ENABLED(HEATER_6_INVERTING)); - TERF(HAS_HEATER_7, OUT_WRITE)(HEATER_7_PIN, ENABLED(HEATER_7_INVERTING)); + #define _INIT_HEATER(N) TERF(HAS_HEATER_##N, OUT_WRITE)(HEATER_##N##_PIN, ENABLED(HEATER_##N##_INVERTING)); + REPEAT_1(7, _INIT_HEATER); #if HAS_HEATED_BED #if ENABLED(PELTIER_BED) @@ -3119,14 +3113,9 @@ void Temperature::init() { OUT_WRITE(COOLER_PIN, ENABLED(COOLER_INVERTING)); #endif - TERF(HAS_FAN0, INIT_FAN_PIN)(FAN0_PIN); - TERF(HAS_FAN1, INIT_FAN_PIN)(FAN1_PIN); - TERF(HAS_FAN2, INIT_FAN_PIN)(FAN2_PIN); - TERF(HAS_FAN3, INIT_FAN_PIN)(FAN3_PIN); - TERF(HAS_FAN4, INIT_FAN_PIN)(FAN4_PIN); - TERF(HAS_FAN5, INIT_FAN_PIN)(FAN5_PIN); - TERF(HAS_FAN6, INIT_FAN_PIN)(FAN6_PIN); - TERF(HAS_FAN7, INIT_FAN_PIN)(FAN7_PIN); + #define _INIT_FAN(N) TERF(HAS_FAN##N, INIT_FAN_PIN)(FAN##N##_PIN); + REPEAT(FAN_COUNT, _INIT_FAN); + TERF(USE_CONTROLLER_FAN, INIT_FAN_PIN)(CONTROLLER_FAN_PIN); TERN_(HAS_MAXTC_SW_SPI, max_tc_spi.init()); @@ -4043,6 +4032,10 @@ void Temperature::isr() { #define WRITE_FAN(n, v) WRITE(FAN##n##_PIN, (v) ^ ENABLED(FAN_INVERTING)) + #if ENABLED(FAN_SOFT_PWM) + #define _FAN_LOW(N) if (TERN0(HAS_FAN##N, soft_pwm_count_fan[N] <= pwm_count_tmp)) { TERF(HAS_FAN##N, WRITE_FAN)(N, LOW); }; + #endif + #if DISABLED(SLOW_PWM_HEATERS) #if ANY(HAS_HOTEND, HAS_HEATED_BED, HAS_HEATED_CHAMBER, HAS_COOLER, FAN_SOFT_PWM) @@ -4079,20 +4072,13 @@ void Temperature::isr() { WRITE(CONTROLLER_FAN_PIN, soft_pwm_controllerfan.add(pwm_mask, controllerFan.soft_pwm_speed)); #endif - #define _FAN_PWM(N) do{ \ + #define __FAN_PWM(N) do{ \ uint8_t &spcf = soft_pwm_count_fan[N]; \ spcf = (spcf & pwm_mask) + (soft_pwm_amount_fan[N] >> 1); \ WRITE_FAN(N, spcf > pwm_mask ? HIGH : LOW); \ }while(0) - - TERF(HAS_FAN0, _FAN_PWM)(0); - TERF(HAS_FAN1, _FAN_PWM)(1); - TERF(HAS_FAN2, _FAN_PWM)(2); - TERF(HAS_FAN3, _FAN_PWM)(3); - TERF(HAS_FAN4, _FAN_PWM)(4); - TERF(HAS_FAN5, _FAN_PWM)(5); - TERF(HAS_FAN6, _FAN_PWM)(6); - TERF(HAS_FAN7, _FAN_PWM)(7); + #define _FAN_PWM(N) TERF(HAS_FAN##N, __FAN_PWM)(N); + REPEAT(FAN_COUNT, _FAN_PWM); #endif } else { @@ -4107,30 +4093,7 @@ void Temperature::isr() { TERF(HAS_COOLER, _PWM_LOW)(COOLER, soft_pwm_cooler); #if ENABLED(FAN_SOFT_PWM) - #if HAS_FAN0 - if (soft_pwm_count_fan[0] <= pwm_count_tmp) WRITE_FAN(0, LOW); - #endif - #if HAS_FAN1 - if (soft_pwm_count_fan[1] <= pwm_count_tmp) WRITE_FAN(1, LOW); - #endif - #if HAS_FAN2 - if (soft_pwm_count_fan[2] <= pwm_count_tmp) WRITE_FAN(2, LOW); - #endif - #if HAS_FAN3 - if (soft_pwm_count_fan[3] <= pwm_count_tmp) WRITE_FAN(3, LOW); - #endif - #if HAS_FAN4 - if (soft_pwm_count_fan[4] <= pwm_count_tmp) WRITE_FAN(4, LOW); - #endif - #if HAS_FAN5 - if (soft_pwm_count_fan[5] <= pwm_count_tmp) WRITE_FAN(5, LOW); - #endif - #if HAS_FAN6 - if (soft_pwm_count_fan[6] <= pwm_count_tmp) WRITE_FAN(6, LOW); - #endif - #if HAS_FAN7 - if (soft_pwm_count_fan[7] <= pwm_count_tmp) WRITE_FAN(7, LOW); - #endif + REPEAT(FAN_COUNT, _FAN_LOW); #if ENABLED(USE_CONTROLLER_FAN) if (soft_pwm_controllerfan.count <= pwm_count_tmp) WRITE(CONTROLLER_FAN_PIN, LOW); #endif @@ -4185,43 +4148,14 @@ void Temperature::isr() { #if ENABLED(FAN_SOFT_PWM) if (pwm_count_tmp >= 127) { pwm_count_tmp = 0; - #define _PWM_FAN(N) do{ \ + #define __PWM_FAN(N) do{ \ soft_pwm_count_fan[N] = soft_pwm_amount_fan[N] >> 1; \ WRITE_FAN(N, soft_pwm_count_fan[N] > 0 ? HIGH : LOW); \ }while(0) - TERF(HAS_FAN0, _PWM_FAN)(0); - TERF(HAS_FAN1, _PWM_FAN)(1); - TERF(HAS_FAN2, _PWM_FAN)(2); - TERF(HAS_FAN3, _FAN_PWM)(3); - TERF(HAS_FAN4, _FAN_PWM)(4); - TERF(HAS_FAN5, _FAN_PWM)(5); - TERF(HAS_FAN6, _FAN_PWM)(6); - TERF(HAS_FAN7, _FAN_PWM)(7); + #define _PWM_FAN(N) TERF(HAS_FAN##N, __PWM_FAN)(N); + REPEAT(FAN_COUNT, _PWM_FAN); } - #if HAS_FAN0 - if (soft_pwm_count_fan[0] <= pwm_count_tmp) WRITE_FAN(0, LOW); - #endif - #if HAS_FAN1 - if (soft_pwm_count_fan[1] <= pwm_count_tmp) WRITE_FAN(1, LOW); - #endif - #if HAS_FAN2 - if (soft_pwm_count_fan[2] <= pwm_count_tmp) WRITE_FAN(2, LOW); - #endif - #if HAS_FAN3 - if (soft_pwm_count_fan[3] <= pwm_count_tmp) WRITE_FAN(3, LOW); - #endif - #if HAS_FAN4 - if (soft_pwm_count_fan[4] <= pwm_count_tmp) WRITE_FAN(4, LOW); - #endif - #if HAS_FAN5 - if (soft_pwm_count_fan[5] <= pwm_count_tmp) WRITE_FAN(5, LOW); - #endif - #if HAS_FAN6 - if (soft_pwm_count_fan[6] <= pwm_count_tmp) WRITE_FAN(6, LOW); - #endif - #if HAS_FAN7 - if (soft_pwm_count_fan[7] <= pwm_count_tmp) WRITE_FAN(7, LOW); - #endif + REPEAT(FAN_COUNT, _FAN_LOW); #endif // FAN_SOFT_PWM // SOFT_PWM_SCALE to frequency: From e99d801e6be64f686a5af69bf3066fbcf809e8fc Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 24 Nov 2025 15:16:03 -0600 Subject: [PATCH 18/47] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Add?= =?UTF-8?q?=20a=20"Marlin"=20class?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/AVR/HAL.cpp | 3 +- Marlin/src/HAL/AVR/HAL.h | 2 +- Marlin/src/HAL/AVR/MarlinSerial.cpp | 1 - Marlin/src/HAL/DUE/HAL.cpp | 1 - Marlin/src/HAL/DUE/HAL.h | 2 +- Marlin/src/HAL/DUE/MarlinSerial.cpp | 1 - Marlin/src/HAL/ESP32/HAL.h | 2 +- Marlin/src/HAL/HC32/MarlinHAL.h | 2 +- Marlin/src/HAL/LINUX/HAL.h | 2 +- Marlin/src/HAL/LPC1768/HAL.h | 2 +- Marlin/src/HAL/LPC1768/Servo.h | 2 + Marlin/src/HAL/NATIVE_SIM/HAL.h | 2 +- Marlin/src/HAL/RP2040/HAL.h | 2 +- Marlin/src/HAL/SAMD21/HAL.h | 2 +- Marlin/src/HAL/SAMD51/HAL.h | 2 +- Marlin/src/HAL/STM32/HAL.h | 2 +- Marlin/src/HAL/STM32F1/HAL.h | 2 +- Marlin/src/HAL/STM32F1/Servo.cpp | 2 - Marlin/src/HAL/TEENSY31_32/HAL.h | 2 +- Marlin/src/HAL/TEENSY35_36/HAL.h | 2 +- Marlin/src/HAL/TEENSY40_41/HAL.h | 2 +- Marlin/src/MarlinCore.cpp | 107 ++++++++++------- Marlin/src/MarlinCore.h | 111 ++++++++++++------ Marlin/src/core/language.h | 7 ++ Marlin/src/core/utility.cpp | 12 +- Marlin/src/core/utility.h | 2 - Marlin/src/feature/babystep.cpp | 1 - Marlin/src/feature/bedlevel/bdl/bdl.cpp | 5 +- Marlin/src/feature/bedlevel/ubl/ubl.cpp | 3 +- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 15 ++- .../src/feature/bedlevel/ubl/ubl_motion.cpp | 1 - Marlin/src/feature/dac/dac_dac084s085.cpp | 1 - Marlin/src/feature/direct_stepping.cpp | 2 +- Marlin/src/feature/e_parser.cpp | 5 +- Marlin/src/feature/easythreed_ui.cpp | 10 +- Marlin/src/feature/encoder_i2c.cpp | 2 +- Marlin/src/feature/fancheck.cpp | 8 +- Marlin/src/feature/fancheck.h | 7 +- Marlin/src/feature/host_actions.cpp | 6 +- Marlin/src/feature/hotend_idle.cpp | 2 +- Marlin/src/feature/max7219.h | 15 ++- Marlin/src/feature/mmu/mmu.cpp | 1 - Marlin/src/feature/mmu/mmu2.cpp | 9 +- Marlin/src/feature/mmu3/mmu3.cpp | 4 +- Marlin/src/feature/mmu3/mmu3_marlin1.cpp | 10 +- Marlin/src/feature/mmu3/mmu3_reporting.cpp | 2 +- Marlin/src/feature/mmu3/ultralcd.cpp | 2 +- Marlin/src/feature/pause.cpp | 38 +++--- Marlin/src/feature/power.cpp | 4 +- Marlin/src/feature/powerloss.cpp | 4 +- Marlin/src/feature/runout.h | 3 +- Marlin/src/feature/spindle_laser.cpp | 2 +- Marlin/src/feature/tmc_util.cpp | 3 +- Marlin/src/gcode/bedlevel/G26.cpp | 1 - Marlin/src/gcode/bedlevel/G42.cpp | 1 - Marlin/src/gcode/bedlevel/abl/G29.cpp | 4 +- Marlin/src/gcode/calibrate/G76_M871.cpp | 2 +- Marlin/src/gcode/calibrate/M100.cpp | 14 +-- Marlin/src/gcode/config/M43.cpp | 11 +- Marlin/src/gcode/config/M550.cpp | 11 +- Marlin/src/gcode/control/M108_M112_M410.cpp | 6 +- Marlin/src/gcode/control/M226.cpp | 5 +- Marlin/src/gcode/control/M42.cpp | 4 +- Marlin/src/gcode/control/M80_M81.cpp | 4 +- Marlin/src/gcode/control/M999.cpp | 4 +- Marlin/src/gcode/feature/camera/M240.cpp | 6 +- .../src/gcode/feature/filwidth/M404-M407.cpp | 1 - .../src/gcode/feature/power_monitor/M430.cpp | 1 - Marlin/src/gcode/gcode.cpp | 4 +- Marlin/src/gcode/gcode_d.cpp | 2 +- Marlin/src/gcode/geometry/M206_M428.cpp | 1 - Marlin/src/gcode/host/M16.cpp | 4 +- Marlin/src/gcode/host/M876.cpp | 1 - Marlin/src/gcode/lcd/M0_M1.cpp | 3 +- Marlin/src/gcode/lcd/M414.cpp | 1 - Marlin/src/gcode/motion/G2_G3.cpp | 2 +- Marlin/src/gcode/motion/G5.cpp | 1 - Marlin/src/gcode/probe/G38.cpp | 9 +- Marlin/src/gcode/probe/M102.cpp | 3 +- Marlin/src/gcode/queue.cpp | 10 +- Marlin/src/gcode/scara/M360-M364.cpp | 3 +- Marlin/src/gcode/sd/M1001.cpp | 3 +- Marlin/src/gcode/sd/M24_M25.cpp | 4 +- Marlin/src/gcode/sd/M32.cpp | 4 +- Marlin/src/gcode/stats/M75-M78.cpp | 2 +- Marlin/src/inc/MarlinConfig.h | 1 + Marlin/src/lcd/HD44780/marlinui_HD44780.cpp | 8 +- Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp | 6 +- Marlin/src/lcd/dogm/status_screen_DOGM.cpp | 8 +- .../lcd/dogm/status_screen_lite_ST7920.cpp | 8 +- Marlin/src/lcd/e3v2/common/encoder.cpp | 4 +- Marlin/src/lcd/e3v2/creality/dwin.cpp | 14 +-- Marlin/src/lcd/e3v2/jyersui/dwin.cpp | 10 +- .../lcd/e3v2/marlinui/ui_status_480x272.cpp | 2 +- Marlin/src/lcd/e3v2/proui/dwin.cpp | 25 ++-- Marlin/src/lcd/e3v2/proui/dwin_popup.cpp | 2 +- Marlin/src/lcd/e3v2/proui/gcode_preview.cpp | 2 +- .../lcd/extui/anycubic_chiron/chiron_tft.cpp | 2 +- .../anycubic_i3mega/anycubic_i3mega_lcd.cpp | 2 +- .../extui/dgus/fysetc/DGUSScreenHandler.cpp | 2 +- .../extui/dgus/hiprecy/DGUSScreenHandler.cpp | 2 +- .../lcd/extui/dgus/mks/DGUSScreenHandler.cpp | 7 +- .../extui/dgus/origin/DGUSScreenHandler.cpp | 2 +- .../extui/dgus_reloaded/DGUSScreenHandler.cpp | 4 +- .../ftdi_eve_touch_ui/ftdi_eve_lib/compat.h | 2 + .../lcd/extui/ia_creality/ia_creality_rts.cpp | 2 +- Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp | 4 +- Marlin/src/lcd/extui/mks_ui/draw_printing.cpp | 6 +- Marlin/src/lcd/extui/mks_ui/draw_set.cpp | 2 +- Marlin/src/lcd/extui/mks_ui/draw_ui.cpp | 4 +- Marlin/src/lcd/extui/mks_ui/wifi_module.cpp | 9 +- Marlin/src/lcd/extui/nextion/nextion_tft.cpp | 4 +- Marlin/src/lcd/extui/ui_api.cpp | 10 +- Marlin/src/lcd/marlinui.cpp | 17 +-- Marlin/src/lcd/menu/menu_advanced.cpp | 2 +- Marlin/src/lcd/menu/menu_bed_tramming.cpp | 2 +- Marlin/src/lcd/menu/menu_configuration.cpp | 2 +- Marlin/src/lcd/menu/menu_delta_calibrate.cpp | 2 +- Marlin/src/lcd/menu/menu_filament.cpp | 10 +- Marlin/src/lcd/menu/menu_info.cpp | 2 +- Marlin/src/lcd/menu/menu_item.h | 3 +- Marlin/src/lcd/menu/menu_language.cpp | 1 - Marlin/src/lcd/menu/menu_main.cpp | 4 +- Marlin/src/lcd/menu/menu_mmu2.cpp | 16 ++- Marlin/src/lcd/sovol_rts/sovol_rts.cpp | 9 +- Marlin/src/lcd/tft/touch.cpp | 9 +- Marlin/src/lcd/tft/ui_color_ui.cpp | 6 +- .../src/lcd/tft/ui_move_axis_screen_1024.cpp | 2 +- .../src/lcd/tft/ui_move_axis_screen_320.cpp | 2 +- .../src/lcd/tft/ui_move_axis_screen_480.cpp | 2 +- Marlin/src/lcd/utf8.cpp | 1 - Marlin/src/libs/nozzle.cpp | 1 - Marlin/src/module/delta.cpp | 1 - Marlin/src/module/endstops.cpp | 4 +- Marlin/src/module/motion.cpp | 8 +- Marlin/src/module/motion.h | 6 +- Marlin/src/module/planner.cpp | 6 +- Marlin/src/module/planner.h | 2 +- Marlin/src/module/planner_bezier.cpp | 3 +- Marlin/src/module/polargraph.cpp | 1 - Marlin/src/module/printcounter.cpp | 1 - Marlin/src/module/probe.cpp | 18 ++- Marlin/src/module/scara.cpp | 1 - Marlin/src/module/settings.cpp | 9 +- Marlin/src/module/stepper.cpp | 1 - Marlin/src/module/temperature.cpp | 111 +++++++++--------- Marlin/src/module/tool_change.cpp | 6 +- Marlin/src/pins/pinsDebug.h | 6 +- Marlin/src/pins/pinsDebug_list.h | 2 +- Marlin/src/sd/Sd2Card.cpp | 2 - Marlin/src/sd/SdBaseFile.cpp | 1 - Marlin/src/sd/SdVolume.cpp | 2 - Marlin/src/sd/cardreader.cpp | 12 +- docs/Queue.md | 6 +- 154 files changed, 501 insertions(+), 531 deletions(-) diff --git a/Marlin/src/HAL/AVR/HAL.cpp b/Marlin/src/HAL/AVR/HAL.cpp index 97173c63f9..4fbab8941f 100644 --- a/Marlin/src/HAL/AVR/HAL.cpp +++ b/Marlin/src/HAL/AVR/HAL.cpp @@ -119,7 +119,6 @@ void MarlinHAL::reboot() { #if ENABLED(USE_WATCHDOG) #include - #include "../../MarlinCore.h" // Initialize watchdog with 8s timeout, if possible. Otherwise, make it 4s. void MarlinHAL::watchdog_init() { @@ -154,7 +153,7 @@ void MarlinHAL::reboot() { ISR(WDT_vect) { sei(); // With the interrupt driven serial we need to allow interrupts. SERIAL_ERROR_MSG(STR_WATCHDOG_FIRED); - minkill(); // interrupt-safe final kill and infinite loop + marlin.minkill(); // interrupt-safe final kill and infinite loop } #endif diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h index e7a82a3b83..02c5d42beb 100644 --- a/Marlin/src/HAL/AVR/HAL.h +++ b/Marlin/src/HAL/AVR/HAL.h @@ -206,7 +206,7 @@ public: static void delay_ms(const int ms) { delay(ms); } - // Tasks, called from idle() + // Tasks, called from marlin.idle() static void idletask() {} // Reset diff --git a/Marlin/src/HAL/AVR/MarlinSerial.cpp b/Marlin/src/HAL/AVR/MarlinSerial.cpp index d070731418..750776c4be 100644 --- a/Marlin/src/HAL/AVR/MarlinSerial.cpp +++ b/Marlin/src/HAL/AVR/MarlinSerial.cpp @@ -41,7 +41,6 @@ #if !defined(USBCON) && (defined(UBRRH) || defined(UBRR0H) || defined(UBRR1H) || defined(UBRR2H) || defined(UBRR3H)) #include "MarlinSerial.h" -#include "../../MarlinCore.h" #if ENABLED(DIRECT_STEPPING) #include "../../feature/direct_stepping.h" diff --git a/Marlin/src/HAL/DUE/HAL.cpp b/Marlin/src/HAL/DUE/HAL.cpp index 9b3cf1a516..19a174259a 100644 --- a/Marlin/src/HAL/DUE/HAL.cpp +++ b/Marlin/src/HAL/DUE/HAL.cpp @@ -27,7 +27,6 @@ #ifdef ARDUINO_ARCH_SAM #include "../../inc/MarlinConfig.h" -#include "../../MarlinCore.h" #include #include "usb/usb_task.h" diff --git a/Marlin/src/HAL/DUE/HAL.h b/Marlin/src/HAL/DUE/HAL.h index 54a977c2d8..f83668ca9d 100644 --- a/Marlin/src/HAL/DUE/HAL.h +++ b/Marlin/src/HAL/DUE/HAL.h @@ -132,7 +132,7 @@ public: static void delay_ms(const int ms) { delay(ms); } - // Tasks, called from idle() + // Tasks, called from marlin.idle() static void idletask(); // Reset diff --git a/Marlin/src/HAL/DUE/MarlinSerial.cpp b/Marlin/src/HAL/DUE/MarlinSerial.cpp index 90efe55fc2..2e80b4c8d1 100644 --- a/Marlin/src/HAL/DUE/MarlinSerial.cpp +++ b/Marlin/src/HAL/DUE/MarlinSerial.cpp @@ -31,7 +31,6 @@ #include "MarlinSerial.h" #include "InterruptVectors.h" -#include "../../MarlinCore.h" template typename MarlinSerial::ring_buffer_r MarlinSerial::rx_buffer = { 0, 0, { 0 } }; template typename MarlinSerial::ring_buffer_t MarlinSerial::tx_buffer = { 0 }; diff --git a/Marlin/src/HAL/ESP32/HAL.h b/Marlin/src/HAL/ESP32/HAL.h index 36b8ea53fc..cd9e738be3 100644 --- a/Marlin/src/HAL/ESP32/HAL.h +++ b/Marlin/src/HAL/ESP32/HAL.h @@ -194,7 +194,7 @@ public: static void delay_ms(const int ms) { delay(ms); } - // Tasks, called from idle() + // Tasks, called from marlin.idle() static void idletask(); // Reset diff --git a/Marlin/src/HAL/HC32/MarlinHAL.h b/Marlin/src/HAL/HC32/MarlinHAL.h index 86dc3c7e53..ba3ac4c731 100644 --- a/Marlin/src/HAL/HC32/MarlinHAL.h +++ b/Marlin/src/HAL/HC32/MarlinHAL.h @@ -67,7 +67,7 @@ public: static void delay_ms(const int ms); - // Tasks, called from idle() + // Tasks, called from marlin.idle() static void idletask(); // Reset diff --git a/Marlin/src/HAL/LINUX/HAL.h b/Marlin/src/HAL/LINUX/HAL.h index 68e0e1062c..66e4036fdc 100644 --- a/Marlin/src/HAL/LINUX/HAL.h +++ b/Marlin/src/HAL/LINUX/HAL.h @@ -126,7 +126,7 @@ public: static void delay_ms(const int ms) { delay(ms); } - // Tasks, called from idle() + // Tasks, called from marlin.idle() static void idletask() {} // Reset diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h index 9a68cdf748..052d6637c8 100644 --- a/Marlin/src/HAL/LPC1768/HAL.h +++ b/Marlin/src/HAL/LPC1768/HAL.h @@ -160,7 +160,7 @@ public: static bool watchdog_timed_out() IF_DISABLED(USE_WATCHDOG, { return false; }); static void watchdog_clear_timeout_flag() IF_DISABLED(USE_WATCHDOG, {}); - // Tasks, called from idle() + // Tasks, called from marlin.idle() static void idletask(); // Reset diff --git a/Marlin/src/HAL/LPC1768/Servo.h b/Marlin/src/HAL/LPC1768/Servo.h index 221001c948..d7f0a2a555 100644 --- a/Marlin/src/HAL/LPC1768/Servo.h +++ b/Marlin/src/HAL/LPC1768/Servo.h @@ -49,6 +49,8 @@ #include +#include "../../MarlinCore.h" + class libServo: public Servo { public: void move(const int value) { diff --git a/Marlin/src/HAL/NATIVE_SIM/HAL.h b/Marlin/src/HAL/NATIVE_SIM/HAL.h index 661c502f22..b3b66d54d3 100644 --- a/Marlin/src/HAL/NATIVE_SIM/HAL.h +++ b/Marlin/src/HAL/NATIVE_SIM/HAL.h @@ -197,7 +197,7 @@ public: static void delay_ms(const int ms) { delay(ms); } - // Tasks, called from idle() + // Tasks, called from marlin.idle() static void idletask(); // Reset diff --git a/Marlin/src/HAL/RP2040/HAL.h b/Marlin/src/HAL/RP2040/HAL.h index 206847053b..a1305bd135 100644 --- a/Marlin/src/HAL/RP2040/HAL.h +++ b/Marlin/src/HAL/RP2040/HAL.h @@ -144,7 +144,7 @@ public: static void delay_ms(const int ms) { delay(ms); } - // Tasks, called from idle() + // Tasks, called from marlin.idle() static void idletask() { TERN_(HAS_SD_HOST_DRIVE, tuh_task()); } // Reset diff --git a/Marlin/src/HAL/SAMD21/HAL.h b/Marlin/src/HAL/SAMD21/HAL.h index e95f0e6f70..5545630ce3 100644 --- a/Marlin/src/HAL/SAMD21/HAL.h +++ b/Marlin/src/HAL/SAMD21/HAL.h @@ -144,7 +144,7 @@ public: static void delay_ms(const int ms) { delay(ms); } - // Tasks, called from idle() + // Tasks, called from marlin.idle() static void idletask() {} // Reset diff --git a/Marlin/src/HAL/SAMD51/HAL.h b/Marlin/src/HAL/SAMD51/HAL.h index 51fed64e35..65dcce966d 100644 --- a/Marlin/src/HAL/SAMD51/HAL.h +++ b/Marlin/src/HAL/SAMD51/HAL.h @@ -121,7 +121,7 @@ public: static void delay_ms(const int ms) { delay(ms); } - // Tasks, called from idle() + // Tasks, called from marlin.idle() static void idletask() {} // Reset diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h index a8ef51bcfc..8f9b56704c 100644 --- a/Marlin/src/HAL/STM32/HAL.h +++ b/Marlin/src/HAL/STM32/HAL.h @@ -157,7 +157,7 @@ public: static void delay_ms(const int ms) { delay(ms); } - // Tasks, called from idle() + // Tasks, called from marlin.idle() static void idletask(); // Reset diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index 68773bdf27..2c7321403f 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -187,7 +187,7 @@ public: static void delay_ms(const int ms) { delay(ms); } - // Tasks, called from idle() + // Tasks, called from marlin.idle() static void idletask(); // Reset diff --git a/Marlin/src/HAL/STM32F1/Servo.cpp b/Marlin/src/HAL/STM32F1/Servo.cpp index 7aa8fe3d00..00caec287b 100644 --- a/Marlin/src/HAL/STM32F1/Servo.cpp +++ b/Marlin/src/HAL/STM32F1/Servo.cpp @@ -29,8 +29,6 @@ uint8_t ServoCount = 0; #include "Servo.h" -//#include "Servo.h" - #include #include #include diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.h b/Marlin/src/HAL/TEENSY31_32/HAL.h index 03610c65f8..b98ee9eb39 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL.h +++ b/Marlin/src/HAL/TEENSY31_32/HAL.h @@ -142,7 +142,7 @@ public: static void delay_ms(const int ms) { delay(ms); } - // Tasks, called from idle() + // Tasks, called from marlin.idle() static void idletask() {} // Reset diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.h b/Marlin/src/HAL/TEENSY35_36/HAL.h index 0f229000d4..85d02cec8c 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL.h +++ b/Marlin/src/HAL/TEENSY35_36/HAL.h @@ -147,7 +147,7 @@ public: static void delay_ms(const int ms) { delay(ms); } - // Tasks, called from idle() + // Tasks, called from marlin.idle() static void idletask() {} // Reset diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.h b/Marlin/src/HAL/TEENSY40_41/HAL.h index f884db6684..fc75539e9b 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.h +++ b/Marlin/src/HAL/TEENSY40_41/HAL.h @@ -160,7 +160,7 @@ public: static void delay_ms(const int ms) { delay(ms); } - // Tasks, called from idle() + // Tasks, called from marlin.idle() static void idletask() {} // Reset diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index b6a47ec744..c5ceb15943 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -160,10 +160,6 @@ #include "feature/spindle_laser.h" #endif -#if HAS_MEDIA - CardReader card; -#endif - #if ENABLED(DELTA) #include "module/delta.h" #elif ENABLED(POLARGRAPH) @@ -264,33 +260,51 @@ #include "feature/rs485.h" #endif +/** + * Spin in place here while keeping temperature processing alive + */ +void safe_delay(millis_t ms) { + while (ms > 50) { + ms -= 50; + delay(50); + thermalManager.task(); + } + delay(ms); + thermalManager.task(); // This keeps us safe if too many small safe_delay() calls are made +} + +// Singleton for Marlin global data and methods +Marlin marlin; + +// Marlin static data +#if ENABLED(CONFIGURABLE_MACHINE_NAME) + MString<64> Marlin::machine_name; +#endif + +// Global state of the firmware +MarlinState Marlin::state = MarlinState::MF_INITIALIZING; + +// For M109 and M190, this flag may be cleared (by M108) to exit the wait loop +bool Marlin::wait_for_heatup = false; + #if !HAS_MEDIA CardReader card; // Stub instance with "no media" methods #endif PGMSTR(M112_KILL_STR, "M112 Shutdown"); -#if ENABLED(CONFIGURABLE_MACHINE_NAME) - MString<64> machine_name; -#endif - -MarlinState marlin_state = MarlinState::MF_INITIALIZING; - -// For M109 and M190, this flag may be cleared (by M108) to exit the wait loop -bool wait_for_heatup = false; - // For M0/M1, this flag may be cleared (by M108) to exit the wait-for-user loop #if HAS_RESUME_CONTINUE - bool wait_for_user; // = false + bool Marlin::wait_for_user; // = false - void wait_for_user_response(millis_t ms/*=0*/, const bool no_sleep/*=false*/) { + void Marlin::wait_for_user_response(millis_t ms/*=0*/, const bool no_sleep/*=false*/) { UNUSED(no_sleep); KEEPALIVE_STATE(PAUSED_FOR_USER); - wait_for_user = true; + wait_start(); if (ms) ms += millis(); // expire time while (wait_for_user && !(ms && ELAPSED(millis(), ms))) idle(TERN_(ADVANCED_PAUSE_FEATURE, no_sleep)); - wait_for_user = false; + user_resume(); while (ui.button_pressed()) safe_delay(50); } @@ -320,7 +334,7 @@ bool wait_for_heatup = false; #pragma GCC diagnostic ignored "-Wnarrowing" #pragma GCC diagnostic ignored "-Wsign-compare" -bool pin_is_protected(const pin_t pin) { +bool Marlin::pin_is_protected(const pin_t pin) { #define pgm_read_pin(P) (sizeof(pin_t) == 2 ? (pin_t)pgm_read_word(P) : (pin_t)pgm_read_byte(P)) for (uint8_t i = 0; i < COUNT(sensitive_dio); ++i) if (pin == pgm_read_pin(&sensitive_dio[i])) return true; @@ -331,28 +345,28 @@ bool pin_is_protected(const pin_t pin) { #pragma GCC diagnostic pop -bool printer_busy() { +bool Marlin::printer_busy() { return planner.has_blocks_queued() || printingIsActive(); } /** * A Print Job exists when the timer is running or SD is printing */ -bool printJobOngoing() { return print_job_timer.isRunning() || card.isStillPrinting(); } +bool Marlin::printJobOngoing() { return print_job_timer.isRunning() || card.isStillPrinting(); } /** * Printing is active when a job is underway but not paused */ -bool printingIsActive() { return !did_pause_print && printJobOngoing(); } +bool Marlin::printingIsActive() { return !did_pause_print && printJobOngoing(); } /** * Printing is paused according to SD or host indicators */ -bool printingIsPaused() { +bool Marlin::printingIsPaused() { return did_pause_print || print_job_timer.isPaused() || card.isPaused(); } -void startOrResumeJob() { +void Marlin::startOrResumeJob() { if (!printingIsPaused()) { TERN_(GCODE_REPEAT_MARKERS, repeat.reset()); TERN_(CANCEL_OBJECTS, cancelable.reset()); @@ -378,7 +392,7 @@ void startOrResumeJob() { TERN(HAS_CUTTER, cutter.kill(), thermalManager.zero_fan_speeds()); // Full cutter shutdown including ISR control - wait_for_heatup = false; + marlin.heatup_done(); TERN_(POWER_LOSS_RECOVERY, recovery.purge()); @@ -390,8 +404,8 @@ void startOrResumeJob() { } inline void finishSDPrinting() { - if (queue.enqueue_one(F("M1001"))) { // Keep trying until it gets queued - marlin_state = MarlinState::MF_RUNNING; // Signal to stop trying + if (queue.enqueue_one(F("M1001"))) { // Keep trying until it gets queued + marlin.setState(MarlinState::MF_RUNNING); // Signal to stop trying TERN_(PASSWORD_AFTER_SD_PRINT_END, password.lock_machine()); TERN_(DGUS_LCD_UI_MKS, screen.sdPrintingFinished()); } @@ -412,7 +426,7 @@ void startOrResumeJob() { * - Check if an idle but hot extruder needs filament extruded (EXTRUDER_RUNOUT_PREVENT) * - Pulse FET_SAFETY_PIN if it exists */ -inline void manage_inactivity(const bool no_stepper_sleep=false) { +void Marlin::manage_inactivity(const bool no_stepper_sleep/*=false*/) { queue.get_available_commands(); @@ -708,7 +722,7 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) { #if ENABLED(DUAL_X_CARRIAGE) // handle delayed move timeout - if (delayed_move_time && ELAPSED(ms, delayed_move_time) && IsRunning()) { + if (delayed_move_time && ELAPSED(ms, delayed_move_time) && isRunning()) { // travel moves have been received so enact them delayed_move_time = 0xFFFFFFFFUL; // force moves to be done destination = current_position; @@ -737,7 +751,8 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) { WRITE(FET_SAFETY_PIN, FET_SAFETY_INVERTED); } #endif -} // manage_inactivity() + +} // Marlin::manage_inactivity() #if ALL(EP_BABYSTEPPING, EMERGENCY_PARSER) #include "feature/babystep.h" @@ -765,14 +780,14 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) { * - Update the Průša MMU2 * - Handle Joystick jogging */ -void idle(const bool no_stepper_sleep/*=false*/) { +void Marlin::idle(const bool no_stepper_sleep/*=false*/) { #ifdef MAX7219_DEBUG_PROFILE CodeProfiler idle_profiler; #endif #if ENABLED(MARLIN_DEV_MODE) static uint16_t idle_depth = 0; - if (++idle_depth > 5) SERIAL_ECHOLNPGM("idle() call depth: ", idle_depth); + if (++idle_depth > 5) SERIAL_ECHOLNPGM("Marlin::idle() call depth: ", idle_depth); #endif // Bed Distance Sensor task @@ -788,7 +803,7 @@ void idle(const bool no_stepper_sleep/*=false*/) { TERN_(MAX7219_DEBUG, max7219.idle_tasks()); // Return if setup() isn't completed - if (marlin_state == MarlinState::MF_INITIALIZING) goto IDLE_DONE; + if (state == MarlinState::MF_INITIALIZING) goto IDLE_DONE; // TODO: Still causing errors TERN_(TOOL_SENSOR, (void)check_tool_sensor_stats(active_extruder, true)); @@ -888,13 +903,14 @@ void idle(const bool no_stepper_sleep/*=false*/) { TERN_(MARLIN_DEV_MODE, idle_depth--); return; -} // idle() + +} // Marlin::idle() /** * Kill all activity and lock the machine. * After this the machine will need to be reset. */ -void kill(FSTR_P const lcd_error/*=nullptr*/, FSTR_P const lcd_component/*=nullptr*/, const bool steppers_off/*=false*/) { +void Marlin::kill(FSTR_P const lcd_error/*=nullptr*/, FSTR_P const lcd_component/*=nullptr*/, const bool steppers_off/*=false*/) { thermalManager.disable_all_heaters(); TERN_(HAS_CUTTER, cutter.kill()); // Full cutter shutdown including ISR control @@ -920,7 +936,7 @@ void kill(FSTR_P const lcd_error/*=nullptr*/, FSTR_P const lcd_component/*=nullp minkill(steppers_off); } -void minkill(const bool steppers_off/*=false*/) { +void Marlin::minkill(const bool steppers_off/*=false*/) { // Wait a short time (allows messages to get out before shutting down. for (int i = 1000; i--;) DELAY_US(600); @@ -960,13 +976,14 @@ void minkill(const bool steppers_off/*=false*/) { for (;;) hal.watchdog_refresh(); // Wait for RESET button or power-cycle #endif -} + +} // Marlin::minkill /** * Turn off heaters and stop the print in progress * After a stop the machine may be resumed with M999 */ -void stop() { +void Marlin::stop() { thermalManager.disable_all_heaters(); // 'unpause' taken care of in here print_job_timer.stop(); @@ -975,13 +992,13 @@ void stop() { thermalManager.set_fans_paused(false); // Un-pause fans for safety #endif - if (!IsStopped()) { + if (!isStopped()) { SERIAL_ERROR_MSG(STR_ERR_STOPPED); LCD_MESSAGE(MSG_STOPPED); - safe_delay(350); // allow enough time for messages to get out before stopping - marlin_state = MarlinState::MF_STOPPED; + safe_delay(350); // Allow enough time for messages to get out before stopping + state = MarlinState::MF_STOPPED; } -} // stop() +} // Marlin::stop() inline void tmc_standby_setup() { #if PIN_EXISTS(X_STDBY) @@ -1692,7 +1709,7 @@ void setup() { SETUP_RUN(ftMotion.init()); #endif - marlin_state = MarlinState::MF_RUNNING; + marlin.setState(MarlinState::MF_RUNNING); #ifdef STARTUP_TUNE // Play a short startup tune before continuing. @@ -1708,7 +1725,7 @@ void setup() { /** * The main Marlin program loop * - * - Call idle() to handle all tasks between G-code commands + * - Call marlin.idle() to handle all tasks between G-code commands * Note that no G-codes from the queue can be executed during idle() * but many G-codes can be called directly anytime like macros. * - Check whether SD card auto-start is needed now. @@ -1720,11 +1737,11 @@ void setup() { */ void loop() { do { - idle(); + marlin.idle(); #if HAS_MEDIA if (card.flag.abort_sd_printing) abortSDPrinting(); - if (marlin_state == MarlinState::MF_SD_COMPLETE) finishSDPrinting(); + if (marlin.is(MarlinState::MF_SD_COMPLETE)) finishSDPrinting(); #endif queue.advance(); diff --git a/Marlin/src/MarlinCore.h b/Marlin/src/MarlinCore.h index 6f27b9998e..cfc5eeca80 100644 --- a/Marlin/src/MarlinCore.h +++ b/Marlin/src/MarlinCore.h @@ -27,19 +27,6 @@ #include #include -void stop(); - -// Pass true to keep steppers from timing out -void idle(const bool no_stepper_sleep=false); -inline void idle_no_sleep() { idle(true); } - -void kill(FSTR_P const lcd_error=nullptr, FSTR_P const lcd_component=nullptr, const bool steppers_off=false); -void minkill(const bool steppers_off=false); - -#if ENABLED(CONFIGURABLE_MACHINE_NAME) - extern MString<64> machine_name; -#endif - // Global State of the firmware enum class MarlinState : uint8_t { MF_INITIALIZING = 0, @@ -51,35 +38,81 @@ enum class MarlinState : uint8_t { MF_WAITING, }; -extern MarlinState marlin_state; -inline bool IsRunning() { return marlin_state >= MarlinState::MF_RUNNING; } -inline bool IsStopped() { return marlin_state == MarlinState::MF_STOPPED; } +typedef bool (*testFunc_t)(); -bool printingIsActive(); -bool printJobOngoing(); -bool printingIsPaused(); -void startOrResumeJob(); +// Delay ensuring that temperatures are updated and the watchdog is kept alive +void safe_delay(millis_t ms); -bool printer_busy(); +// Singleton for Marlin global data and methods -extern bool wait_for_heatup; - -#if HAS_RESUME_CONTINUE - extern bool wait_for_user; - void wait_for_user_response(millis_t ms=0, const bool no_sleep=false); -#endif - -bool pin_is_protected(const pin_t pin); - -#if HAS_SUICIDE - inline void suicide() { OUT_WRITE(SUICIDE_PIN, SUICIDE_PIN_STATE); } -#endif - -#if HAS_KILL - #ifndef KILL_PIN_STATE - #define KILL_PIN_STATE LOW +class Marlin { +public: + #if ENABLED(CONFIGURABLE_MACHINE_NAME) + static MString<64> machine_name; #endif - inline bool kill_state() { return READ(KILL_PIN) == KILL_PIN_STATE; } -#endif + + static MarlinState state; + static void setState(const MarlinState s) { state = s; } + static bool is(const MarlinState s) { return state == s; } + static bool isStopped() { return is(MarlinState::MF_STOPPED); } + static bool isRunning() { return state >= MarlinState::MF_RUNNING; } + + static bool printingIsActive(); + static bool printJobOngoing(); + static bool printingIsPaused(); + static void startOrResumeJob(); + + static bool printer_busy(); + + static void stop(); + + // Maintain all important activities + static void manage_inactivity(const bool no_stepper_sleep=false); + + // Pass true to keep steppers from timing out + static void idle(const bool no_stepper_sleep=false); + static void idle_no_sleep() { idle(true); } + + static void kill(FSTR_P const lcd_error=nullptr, FSTR_P const lcd_component=nullptr, const bool steppers_off=false); + static void minkill(const bool steppers_off=false); + + #if HAS_RESUME_CONTINUE + // Global waiting for user response + static bool wait_for_user; + static void wait_start() { wait_for_user = true; } + static void user_resume() { wait_for_user = false; } + static void wait_for_user_response(millis_t ms=0, const bool no_sleep=false); + #endif + + // Global waiting for heatup state + static bool wait_for_heatup; + static bool is_heating() { return wait_for_heatup; } + static void heatup_start() { wait_for_heatup = true; } + static void heatup_done() { wait_for_heatup = false; } + static void end_waiting() { TERN_(HAS_RESUME_CONTINUE, wait_for_user =) wait_for_heatup = false; } + + // Shared function for M42 / M43 + static bool pin_is_protected(const pin_t pin); + + #if HAS_SUICIDE + static void suicide() { OUT_WRITE(SUICIDE_PIN, SUICIDE_PIN_STATE); } + #endif + + static bool kill_state() { + return ( + #if HAS_KILL + #ifndef KILL_PIN_STATE + #define KILL_PIN_STATE LOW + #endif + READ(KILL_PIN) == KILL_PIN_STATE + #else + false + #endif + ); + } + +}; + +extern Marlin marlin; extern const char M112_KILL_STR[]; diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h index e0a31db9ab..837f3885b9 100644 --- a/Marlin/src/core/language.h +++ b/Marlin/src/core/language.h @@ -210,6 +210,8 @@ #define STR_KILL_BUTTON "KILL button/pin" // temperature.cpp strings +#define STR_WAIT_FOR_HOTEND "Wait for hotend heating..." +#define STR_WAIT_FOR_BED "Wait for bed heating..." #define STR_PID_AUTOTUNE "PID Autotune" #define STR_PID_AUTOTUNE_START " start" #define STR_PID_BAD_HEATER_ID " failed! Bad heater id" @@ -230,6 +232,8 @@ #define STR_PID_DEBUG_INPUT ": Input " #define STR_PID_DEBUG_OUTPUT " Output " #define STR_INVALID_EXTRUDER_NUM " - Invalid extruder number !" + +// MPCTEMP strings #define STR_MPC_AUTOTUNE_START "MPC Autotune start for " STR_E #define STR_MPC_AUTOTUNE_INTERRUPTED "MPC Autotune interrupted!" #define STR_MPC_AUTOTUNE_FINISHED "MPC Autotune finished! Put the constants below into Configuration.h" @@ -238,6 +242,7 @@ #define STR_MPC_MEASURING_AMBIENT "Measuring ambient heatloss at " #define STR_MPC_TEMPERATURE_ERROR "Temperature error" +// Temperature Sensors #define STR_HEATER_BED "bed" #define STR_HEATER_CHAMBER "chamber" #define STR_COOLER "cooler" @@ -247,6 +252,7 @@ #define STR_REDUNDANT "redundant " #define STR_LASER_TEMP "laser temperature" +// Misc. Errors, Thermal Runaway #define STR_STOPPED_HEATER ", system stopped! Heater_ID: " #define STR_DETECTED_TEMP_B " (temp: " #define STR_DETECTED_TEMP_E ")" @@ -269,6 +275,7 @@ #define STR_DEBUG_COMMUNICATION "COMMUNICATION" #define STR_DEBUG_DETAIL "DETAIL" +// Password Security #define STR_PRINTER_LOCKED "Printer locked! (Unlock with M511 or LCD)" #define STR_WRONG_PASSWORD "Incorrect Password" #define STR_PASSWORD_TOO_LONG "Password too long" diff --git a/Marlin/src/core/utility.cpp b/Marlin/src/core/utility.cpp index c8b903ecc2..f6b8b304c0 100644 --- a/Marlin/src/core/utility.cpp +++ b/Marlin/src/core/utility.cpp @@ -22,26 +22,16 @@ #include "utility.h" -#include "../MarlinCore.h" #include "../module/temperature.h" #if ENABLED(MARLIN_DEV_MODE) MarlinError marlin_error_number; // Error Number - Marlin can beep X times periodically, display, and emit... #endif -void safe_delay(millis_t ms) { - while (ms > 50) { - ms -= 50; - delay(50); - thermalManager.task(); - } - delay(ms); - thermalManager.task(); // This keeps us safe if too many small safe_delay() calls are made -} - // A delay to provide brittle hosts time to receive bytes #if ENABLED(SERIAL_OVERRUN_PROTECTION) + #include "../MarlinCore.h" // for safe_delay #include "../gcode/gcode.h" // for set_autoreport_paused void serial_delay(const millis_t ms) { diff --git a/Marlin/src/core/utility.h b/Marlin/src/core/utility.h index 77e8bac016..b8b4de7f28 100644 --- a/Marlin/src/core/utility.h +++ b/Marlin/src/core/utility.h @@ -25,8 +25,6 @@ #include "../core/types.h" #include "../core/millis_t.h" -void safe_delay(millis_t ms); // Delay ensuring that temperatures are updated and the watchdog is kept alive. - #if ENABLED(SERIAL_OVERRUN_PROTECTION) void serial_delay(const millis_t ms); #else diff --git a/Marlin/src/feature/babystep.cpp b/Marlin/src/feature/babystep.cpp index 6a4929e60f..d61784517b 100644 --- a/Marlin/src/feature/babystep.cpp +++ b/Marlin/src/feature/babystep.cpp @@ -25,7 +25,6 @@ #if ENABLED(BABYSTEPPING) #include "babystep.h" -#include "../MarlinCore.h" #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/bedlevel/bdl/bdl.cpp b/Marlin/src/feature/bedlevel/bdl/bdl.cpp index ea4bcc0607..45c7792d5c 100644 --- a/Marlin/src/feature/bedlevel/bdl/bdl.cpp +++ b/Marlin/src/feature/bedlevel/bdl/bdl.cpp @@ -24,7 +24,6 @@ #if ENABLED(BD_SENSOR) -#include "../../../MarlinCore.h" #include "../../../gcode/gcode.h" #include "../../../module/settings.h" #include "../../../module/motion.h" @@ -110,7 +109,7 @@ float BDS_Leveling::read() { } void BDS_Leveling::process() { - if (config_state == BDS_IDLE && printingIsActive()) return; + if (config_state == BDS_IDLE && marlin.printingIsActive()) return; static millis_t next_check_ms = 0; // starting at T=0 static float zpos = 0.0f; const millis_t ms = millis(); @@ -156,7 +155,7 @@ void BDS_Leveling::process() { } else if (config_state == BDS_HOMING_Z) { SERIAL_ECHOLNPGM("Read:", tmp); - kill(F("BDsensor connect Err!")); + marlin.kill(F("BDsensor connect Err!")); } DEBUG_ECHOLNPGM("BD:", tmp & 0x3FF, " Z:", cur_z, "|", current_position.z); diff --git a/Marlin/src/feature/bedlevel/ubl/ubl.cpp b/Marlin/src/feature/bedlevel/ubl/ubl.cpp index e1f2ed4c16..2357437633 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl.cpp @@ -28,7 +28,6 @@ unified_bed_leveling bedlevel; -#include "../../../MarlinCore.h" #include "../../../gcode/gcode.h" #include "../../../module/settings.h" @@ -221,7 +220,7 @@ void unified_bed_leveling::display_map(const uint8_t map_type) { if (human) SERIAL_CHAR(is_current ? ']' : ' '); SERIAL_FLUSHTX(); - idle_no_sleep(); + marlin.idle_no_sleep(); } if (!lcd) SERIAL_EOL(); diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index e14d7b2a38..6341933bfb 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -26,7 +26,6 @@ #include "../bedlevel.h" -#include "../../../MarlinCore.h" #include "../../../HAL/shared/eeprom_api.h" #include "../../../libs/hex_print.h" #include "../../../module/settings.h" @@ -375,7 +374,7 @@ void unified_bed_leveling::G29() { bool invalidate_all = count >= GRID_MAX_POINTS; if (!invalidate_all) { while (count--) { - if ((count & 0x0F) == 0x0F) idle(); + if ((count & 0x0F) == 0x0F) marlin.idle(); const mesh_index_pair closest = find_closest_mesh_point_of_type(REAL, param.XY_pos); // No more REAL mesh points to invalidate? Assume the user meant // to invalidate the ENTIRE mesh, which can't be done with @@ -856,7 +855,7 @@ void set_message_with_feedback(FSTR_P const fstr) { ui.quick_feedback(false); // Preserve button state for click-and-hold const millis_t nxt = millis() + 1500UL; while (ui.button_pressed()) { // Loop while the encoder is pressed. Uses hardware flag! - idle(); // idle, of course + marlin.idle(); // idle, of course if (ELAPSED(millis(), nxt)) { // After 1.5 seconds ui.quick_feedback(); if (func) (*func)(); @@ -872,7 +871,7 @@ void set_message_with_feedback(FSTR_P const fstr) { void unified_bed_leveling::move_z_with_encoder(const float multiplier) { ui.wait_for_release(); while (!ui.button_pressed()) { - idle(); + marlin.idle(); gcode.reset_stepper_timeout(); // Keep steppers powered if (encoder_diff) { do_blocking_move_to_z(current_position.z + float(encoder_diff) * multiplier); @@ -1088,7 +1087,7 @@ void set_message_with_feedback(FSTR_P const fstr) { SET_SOFT_ENDSTOP_LOOSE(true); do { - idle_no_sleep(); + marlin.idle_no_sleep(); new_z = ui.ubl_mesh_value(); TERN_(UBL_MESH_EDIT_MOVES_Z, do_blocking_move_to_z(h_offset + new_z)); // Move the nozzle as the point is edited SERIAL_FLUSH(); // Prevent host M105 buffer overrun. @@ -1728,7 +1727,7 @@ void unified_bed_leveling::smart_fill_mesh() { const float ez = -lsf_results.D - lsf_results.A * ppos.x - lsf_results.B * ppos.y; z_values[ix][iy] = ez; TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ix, iy, z_values[ix][iy])); - idle(); // housekeeping + marlin.idle(); // housekeeping } } } @@ -1785,7 +1784,7 @@ void unified_bed_leveling::smart_fill_mesh() { SERIAL_EOL(); #if HAS_KILL - SERIAL_ECHOLNPGM("Kill pin on :", KILL_PIN, " state:", kill_state()); + SERIAL_ECHOLNPGM("Kill pin on :", KILL_PIN, " state:", marlin.kill_state()); #endif SERIAL_EOL(); @@ -1823,7 +1822,7 @@ void unified_bed_leveling::smart_fill_mesh() { SERIAL_ECHO_MSG("EEPROM Dump:"); persistentStore.access_start(); for (uint16_t i = 0; i < persistentStore.capacity(); i += 16) { - if (!(i & 0x3)) idle(); + if (!(i & 0x3)) marlin.idle(); print_hex_word(i); SERIAL_ECHOPGM(": "); for (uint16_t j = 0; j < 16; j++) { diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp index be9fb7b947..b6b9ec4368 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp @@ -32,7 +32,6 @@ #include "../../../module/delta.h" #endif -#include "../../../MarlinCore.h" #include //#define DEBUG_UBL_MOTION diff --git a/Marlin/src/feature/dac/dac_dac084s085.cpp b/Marlin/src/feature/dac/dac_dac084s085.cpp index 772bb68de4..1338e5979d 100644 --- a/Marlin/src/feature/dac/dac_dac084s085.cpp +++ b/Marlin/src/feature/dac/dac_dac084s085.cpp @@ -10,7 +10,6 @@ #include "dac_dac084s085.h" -#include "../../MarlinCore.h" #include "../../HAL/shared/Delay.h" dac084s085::dac084s085() { } diff --git a/Marlin/src/feature/direct_stepping.cpp b/Marlin/src/feature/direct_stepping.cpp index 13cf71e076..08cda561b1 100644 --- a/Marlin/src/feature/direct_stepping.cpp +++ b/Marlin/src/feature/direct_stepping.cpp @@ -175,7 +175,7 @@ namespace DirectStepping { template void SerialPageManager::write_responses() { if (fatal_error) { - kill(GET_TEXT_F(MSG_BAD_PAGE)); + marlin.kill(GET_TEXT_F(MSG_BAD_PAGE)); return; } diff --git a/Marlin/src/feature/e_parser.cpp b/Marlin/src/feature/e_parser.cpp index 9e974f2e83..bda1232154 100644 --- a/Marlin/src/feature/e_parser.cpp +++ b/Marlin/src/feature/e_parser.cpp @@ -49,9 +49,6 @@ bool EmergencyParser::killed_by_M112, // = false // Global instance EmergencyParser emergency_parser; -// External references -extern bool wait_for_user, wait_for_heatup; - #if ENABLED(EP_BABYSTEPPING) #include "babystep.h" #endif @@ -208,7 +205,7 @@ void EmergencyParser::update(EmergencyParser::State &state, const uint8_t c) { default: if (ISEOL(c)) { if (enabled) switch (state) { - case EP_M108: wait_for_user = wait_for_heatup = false; break; + case EP_M108: marlin.end_waiting(); break; case EP_M112: killed_by_M112 = true; break; case EP_M410: quickstop_by_M410 = true; break; #if ENABLED(FTM_RESONANCE_TEST) diff --git a/Marlin/src/feature/easythreed_ui.cpp b/Marlin/src/feature/easythreed_ui.cpp index bfa51096f5..7180c4dbcd 100644 --- a/Marlin/src/feature/easythreed_ui.cpp +++ b/Marlin/src/feature/easythreed_ui.cpp @@ -91,7 +91,7 @@ void EasythreedUI::blinkLED() { // Load/Unload buttons are a 3 position switch with a common center ground. // void EasythreedUI::loadButton() { - if (printingIsActive()) return; + if (marlin.printingIsActive()) return; enum FilamentStatus : uint8_t { FS_IDLE, FS_PRESS, FS_CHECK, FS_PROCEED }; static uint8_t filament_status = FS_IDLE; @@ -185,7 +185,7 @@ void EasythreedUI::printButton() { if (PENDING(ms, key_time, 1200 - BTN_DEBOUNCE_MS)) { // Register a press < 1.2 seconds switch (print_key_flag) { case PF_START: { // The "Print" button starts an SD card print - if (printingIsActive()) break; // Already printing? (find another line that checks for 'is planner doing anything else right now?') + if (marlin.printingIsActive()) break; // Already printing? (find another line that checks for 'is planner doing anything else right now?') blink_interval_ms = LED_BLINK_2; // Blink the indicator LED at 1 second intervals print_key_flag = PF_PAUSE; // The "Print" button now pauses the print card.mount(); // Force SD card to mount - now! @@ -201,13 +201,13 @@ void EasythreedUI::printButton() { card.openAndPrintFile(card.filename); // Start printing it } break; case PF_PAUSE: { // Pause printing (not currently firing) - if (!printingIsActive()) break; + if (!marlin.printingIsActive()) break; blink_interval_ms = LED_ON; // Set indicator to steady ON queue.inject(F("M25")); // Queue Pause print_key_flag = PF_RESUME; // The "Print" button now resumes the print } break; case PF_RESUME: { // Resume printing - if (printingIsActive()) break; + if (marlin.printingIsActive()) break; blink_interval_ms = LED_BLINK_2; // Blink the indicator LED at 1 second intervals queue.inject(F("M24")); // Queue resume print_key_flag = PF_PAUSE; // The "Print" button now pauses the print @@ -215,7 +215,7 @@ void EasythreedUI::printButton() { } } else { // Register a longer press - if (print_key_flag == PF_START && !printingIsActive()) { // While not printing, this moves Z up 10mm + if (print_key_flag == PF_START && !marlin.printingIsActive()) { // While not printing, this moves Z up 10mm blink_interval_ms = LED_ON; queue.inject(F("G91\nG0 Z10 F600\nG90")); // Raise Z soon after returning to main loop } diff --git a/Marlin/src/feature/encoder_i2c.cpp b/Marlin/src/feature/encoder_i2c.cpp index 5a47600792..7c83053b89 100644 --- a/Marlin/src/feature/encoder_i2c.cpp +++ b/Marlin/src/feature/encoder_i2c.cpp @@ -149,7 +149,7 @@ void I2CPositionEncoder::update() { #ifdef I2CPE_ERR_THRESH_ABORT if (ABS(error) > I2CPE_ERR_THRESH_ABORT * planner.settings.axis_steps_per_mm[encoderAxis]) { - //kill(F("Significant Error")); + //marlin.kill(F("Significant Error")); SERIAL_ECHOLNPGM("Axis error over threshold, aborting!", error); safe_delay(5000); } diff --git a/Marlin/src/feature/fancheck.cpp b/Marlin/src/feature/fancheck.cpp index 339eb16aa9..d0582ed97a 100644 --- a/Marlin/src/feature/fancheck.cpp +++ b/Marlin/src/feature/fancheck.cpp @@ -93,7 +93,7 @@ void FanCheck::compute_speed(uint16_t elapsedTime) { // Drop the error when all fans are ok if (!fan_error_msk && error == TachoError::REPORTED) error = TachoError::FIXED; - if (error == TachoError::FIXED && !printJobOngoing() && !printingIsPaused()) { + if (error == TachoError::FIXED && !marlin.printJobOngoing() && !marlin.printingIsPaused()) { error = TachoError::NONE; // if the issue has been fixed while the printer is idle, reenable immediately ui.reset_alert_level(); } @@ -106,17 +106,17 @@ void FanCheck::compute_speed(uint16_t elapsedTime) { } void FanCheck::report_speed_error(uint8_t fan) { - if (printJobOngoing()) { + if (marlin.printJobOngoing()) { if (error == TachoError::NONE) { if (thermalManager.degTargetHotend(fan) != 0) { - kill(GET_TEXT_F(MSG_FAN_SPEED_FAULT)); + marlin.kill(GET_TEXT_F(MSG_FAN_SPEED_FAULT)); error = TachoError::REPORTED; } else error = TachoError::DETECTED; // Plans error for next processed command } } - else if (!printingIsPaused()) { + else if (!marlin.printingIsPaused()) { thermalManager.setTargetHotend(0, fan); // Always disable heating if (error == TachoError::NONE) error = TachoError::REPORTED; } diff --git a/Marlin/src/feature/fancheck.h b/Marlin/src/feature/fancheck.h index 3c295b3020..fed6a798e1 100644 --- a/Marlin/src/feature/fancheck.h +++ b/Marlin/src/feature/fancheck.h @@ -25,7 +25,6 @@ #if HAS_FANCHECK -#include "../MarlinCore.h" #include "../lcd/marlinui.h" #if ENABLED(AUTO_REPORT_FANS) @@ -74,7 +73,11 @@ class FanCheck { static void check_deferred_error() { if (error == TachoError::DETECTED) { error = TachoError::REPORTED; - TERN(PARK_HEAD_ON_PAUSE, queue.inject(F("M125")), kill(GET_TEXT_F(MSG_FAN_SPEED_FAULT))); + #if ENABLED(PARK_HEAD_ON_PAUSE) + queue.inject(F("M125")); + #else + marlin.kill(GET_TEXT_F(MSG_FAN_SPEED_FAULT)); + #endif } } diff --git a/Marlin/src/feature/host_actions.cpp b/Marlin/src/feature/host_actions.cpp index 538aa92e91..94bc4db011 100644 --- a/Marlin/src/feature/host_actions.cpp +++ b/Marlin/src/feature/host_actions.cpp @@ -87,10 +87,6 @@ void HostUI::action(FSTR_P const fstr, const bool eol) { PGMSTR(CONTINUE_STR, "Continue"); PGMSTR(DISMISS_STR, "Dismiss"); - #if HAS_RESUME_CONTINUE - extern bool wait_for_user; - #endif - void HostUI::notify(const char * const cstr) { PORT_REDIRECT(SerialMask::All); action(F("notification "), false); @@ -205,7 +201,7 @@ void HostUI::action(FSTR_P const fstr, const bool eol) { } break; case PROMPT_USER_CONTINUE: - TERN_(HAS_RESUME_CONTINUE, wait_for_user = false); + TERN_(HAS_RESUME_CONTINUE, marlin.user_resume()); break; case PROMPT_PAUSE_RESUME: #if ALL(ADVANCED_PAUSE_FEATURE, HAS_MEDIA) diff --git a/Marlin/src/feature/hotend_idle.cpp b/Marlin/src/feature/hotend_idle.cpp index eb16781fdd..a779efeaff 100644 --- a/Marlin/src/feature/hotend_idle.cpp +++ b/Marlin/src/feature/hotend_idle.cpp @@ -43,7 +43,7 @@ millis_t HotendIdleProtection::next_protect_ms = 0; hotend_idle_settings_t HotendIdleProtection::cfg; // Initialized by settings.load void HotendIdleProtection::check_hotends(const millis_t &ms) { - const bool busy = (TERN0(HAS_RESUME_CONTINUE, wait_for_user) || planner.has_blocks_queued()); + const bool busy = (TERN0(HAS_RESUME_CONTINUE, marlin.wait_for_user) || planner.has_blocks_queued()); bool do_prot = false; if (!busy && cfg.timeout != 0) { HOTEND_LOOP() { diff --git a/Marlin/src/feature/max7219.h b/Marlin/src/feature/max7219.h index 799524dc5f..9c39541a7c 100644 --- a/Marlin/src/feature/max7219.h +++ b/Marlin/src/feature/max7219.h @@ -74,14 +74,13 @@ #ifdef MAX7219_DEBUG_PROFILE // This class sums up the amount of time for which its instances exist. - // By default there is one instantiated for the duration of the idle() - // function. But an instance can be created in any code block to measure - // the time spent from the point of instantiation until the CPU leaves - // block. Be careful about having multiple instances of CodeProfiler as - // it does not guard against double counting. In general mixing ISR and - // non-ISR use will require critical sections but note that mode setting - // is atomic so the total or average times can safely be read if you set - // mode to FREEZE first. + // By default there is one instantiated for the duration of marlin.idle() + // but an instance can be created in any code block to measure time spent + // from instantiation until the CPU leaves the block. + // Be careful about having multiple instances of CodeProfiler as it does + // not guard against double counting. In general mixing ISR and non-ISR + // use will require critical sections but note that mode setting is atomic + // so the total or average times can safely be read if you set mode to FREEZE first. class CodeProfiler { public: enum Mode : uint8_t { ACCUMULATE_AVERAGE, ACCUMULATE_TOTAL, FREEZE }; diff --git a/Marlin/src/feature/mmu/mmu.cpp b/Marlin/src/feature/mmu/mmu.cpp index 58c49ed224..b1e66cc425 100644 --- a/Marlin/src/feature/mmu/mmu.cpp +++ b/Marlin/src/feature/mmu/mmu.cpp @@ -24,7 +24,6 @@ #if HAS_PRUSA_MMU1 -#include "../../MarlinCore.h" #include "../../module/planner.h" #include "../../module/stepper.h" diff --git a/Marlin/src/feature/mmu/mmu2.cpp b/Marlin/src/feature/mmu/mmu2.cpp index b976150ed9..76e2b8505f 100644 --- a/Marlin/src/feature/mmu/mmu2.cpp +++ b/Marlin/src/feature/mmu/mmu2.cpp @@ -40,7 +40,6 @@ MMU2 mmu2; #include "../../module/temperature.h" #include "../../module/planner.h" #include "../../module/stepper.h" -#include "../../MarlinCore.h" #if ENABLED(HOST_PROMPT_SUPPORT) #include "../host_actions.h" @@ -446,7 +445,7 @@ bool MMU2::rx_ok() { void MMU2::check_version(const uint16_t buildnr) { if (buildnr < MMU_REQUIRED_FW_BUILDNR) { SERIAL_ERROR_MSG("Invalid MMU2 firmware. Version >= " STRINGIFY(MMU_REQUIRED_FW_BUILDNR) " required."); - kill(GET_TEXT_F(MSG_KILL_MMU2_FIRMWARE)); + marlin.kill(GET_TEXT_F(MSG_KILL_MMU2_FIRMWARE)); } } @@ -786,10 +785,10 @@ void MMU2::command(const uint8_t mmu_cmd) { * Wait for response from MMU */ bool MMU2::get_response() { - while (cmd != MMU_CMD_NONE) idle(); + while (cmd != MMU_CMD_NONE) marlin.idle(); while (!ready) { - idle(); + marlin.idle(); if (state != 3) break; } @@ -985,7 +984,7 @@ bool MMU2::eject_filament(const uint8_t index, const bool recover) { mmu2_attn_buzz(); TERN_(HOST_PROMPT_SUPPORT, hostui.continue_prompt(GET_TEXT_F(MSG_MMU2_EJECT_RECOVER))); TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_MMU2_EJECT_RECOVER))); - TERN_(HAS_RESUME_CONTINUE, wait_for_user_response()); + TERN_(HAS_RESUME_CONTINUE, marlin.wait_for_user_response()); mmu2_attn_buzz(); command(MMU_CMD_R0); diff --git a/Marlin/src/feature/mmu3/mmu3.cpp b/Marlin/src/feature/mmu3/mmu3.cpp index f2c7be3f6a..9727c07829 100644 --- a/Marlin/src/feature/mmu3/mmu3.cpp +++ b/Marlin/src/feature/mmu3/mmu3.cpp @@ -274,7 +274,7 @@ namespace MMU3 { */ void MMU3::checkFINDARunout() { if (!findaDetectsFilament() - //&& printJobOngoing() + //&& marlin.printJobOngoing() && parser.codenum != 600 && TERN1(HAS_LEVELING, planner.leveling_active) && xy_are_trusted() @@ -857,7 +857,7 @@ namespace MMU3 { for (;;) { // in our new implementation, we know the exact state of the MMU at any moment, we do not have to wait for a timeout // So in this case we should decide if the operation is: - // - still running -> wait normally in idle() + // - still running -> wait normally in marlin.idle() // - failed -> then do the safety moves on the printer like before // - finished ok -> proceed with reading other commands safe_delay_keep_alive(0); // calls logicStep() and remembers its return status diff --git a/Marlin/src/feature/mmu3/mmu3_marlin1.cpp b/Marlin/src/feature/mmu3/mmu3_marlin1.cpp index 2c4effe106..f12d83772a 100644 --- a/Marlin/src/feature/mmu3/mmu3_marlin1.cpp +++ b/Marlin/src/feature/mmu3/mmu3_marlin1.cpp @@ -122,15 +122,15 @@ namespace MMU3 { #endif } - bool marlin_printingIsActive() { return printingIsActive(); } + bool marlin_printingIsActive() { return marlin.printingIsActive(); } void marlin_manage_heater() { thermalManager.task(); } - void marlin_manage_inactivity(const bool b) { idle(b); } + void marlin_manage_inactivity(const bool b) { marlin.idle(b); } - void marlin_idle(bool b) { + void marlin_idle(const bool b) { thermalManager.task(); - idle(b); + marlin.idle(b); } void marlin_refresh_print_state_in_ram() { @@ -157,7 +157,7 @@ namespace MMU3 { void thermal_setTargetHotend(int16_t t) { thermalManager.setTargetHotend(t, 0); } void safe_delay_keep_alive(uint16_t t) { - idle(true); + marlin.idle(true); safe_delay(t); } diff --git a/Marlin/src/feature/mmu3/mmu3_reporting.cpp b/Marlin/src/feature/mmu3/mmu3_reporting.cpp index 426aa4d825..b0527937ea 100644 --- a/Marlin/src/feature/mmu3/mmu3_reporting.cpp +++ b/Marlin/src/feature/mmu3/mmu3_reporting.cpp @@ -213,7 +213,7 @@ namespace MMU3 { void EndReport(CommandInProgress /*cip*/, ProgressCode /*ec*/) { // clear the status msg line - let the printed filename get visible again - if (!printJobOngoing()) ui.reset_status(); + if (!marlin.printJobOngoing()) ui.reset_status(); //custom_message_type = CustomMsg::Status; } diff --git a/Marlin/src/feature/mmu3/ultralcd.cpp b/Marlin/src/feature/mmu3/ultralcd.cpp index 96e019740f..3b8f52beb3 100644 --- a/Marlin/src/feature/mmu3/ultralcd.cpp +++ b/Marlin/src/feature/mmu3/ultralcd.cpp @@ -187,7 +187,7 @@ } // Wait for 5 seconds before displaying the next text. for (uint8_t i = 0; i < 100; ++i) { - idle(true); + marlin.idle(true); safe_delay(50); if (ui.use_click()) { if (fmsg_next == nullptr) { diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index e48a0f8ec4..715ec087e1 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -160,10 +160,10 @@ static bool ensure_safe_temperature(const bool wait=true, const PauseMode mode=P if (wait) return thermalManager.wait_for_hotend(active_extruder); // Allow interruption by Emergency Parser M108 - wait_for_heatup = TERN1(PREVENT_COLD_EXTRUSION, !thermalManager.allow_cold_extrude); - while (wait_for_heatup && ABS(thermalManager.wholeDegHotend(active_extruder) - thermalManager.degTargetHotend(active_extruder)) > (TEMP_WINDOW)) - idle(); - wait_for_heatup = false; + marlin.wait_for_heatup = TERN1(PREVENT_COLD_EXTRUSION, !thermalManager.allow_cold_extrude); + while (marlin.is_heating() && ABS(thermalManager.wholeDegHotend(active_extruder) - thermalManager.degTargetHotend(active_extruder)) > (TEMP_WINDOW)) + marlin.idle(); + marlin.heatup_done(); #if ENABLED(PREVENT_COLD_EXTRUSION) // A user can cancel wait-for-heating with M108 @@ -206,7 +206,7 @@ bool load_filament(const float slow_load_length/*=0*/, const float fast_load_len first_impatient_beep(max_beep_count); KEEPALIVE_STATE(PAUSED_FOR_USER); - wait_for_user = true; // LCD click or M108 will clear this + marlin.wait_start(); // LCD click or M108 will clear this TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_FILAMENTLOAD))); @@ -215,19 +215,19 @@ bool load_filament(const float slow_load_length/*=0*/, const float fast_load_len hostui.prompt_do(PROMPT_USER_CONTINUE, F("Load Filament T"), tool, FPSTR(CONTINUE_STR)); #endif - while (wait_for_user) { + while (marlin.wait_for_user) { impatient_beep(max_beep_count); #if ALL(HAS_FILAMENT_SENSOR, FILAMENT_CHANGE_RESUME_ON_INSERT) #if MULTI_FILAMENT_SENSOR - #define _CASE_INSERTED(N) case N-1: if (!FILAMENT_IS_OUT(N)) wait_for_user = false; break; + #define _CASE_INSERTED(N) case N-1: if (!FILAMENT_IS_OUT(N)) marlin.user_resume(); break; switch (active_extruder) { REPEAT_1(NUM_RUNOUT_SENSORS, _CASE_INSERTED) } #else - if (!FILAMENT_IS_OUT()) wait_for_user = false; + if (!FILAMENT_IS_OUT()) marlin.user_resume(); #endif #endif - idle_no_sleep(); + marlin.idle_no_sleep(); } } @@ -270,10 +270,10 @@ bool load_filament(const float slow_load_length/*=0*/, const float fast_load_len TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_FILAMENT_CHANGE_PURGE))); TERN_(HOST_PROMPT_SUPPORT, hostui.continue_prompt(GET_TEXT_F(MSG_FILAMENT_CHANGE_PURGE))); - wait_for_user = true; // A click or M108 breaks the purge_length loop - for (float purge_count = purge_length; purge_count > 0 && wait_for_user; --purge_count) + marlin.wait_start(); // A click or M108 breaks the purge_length loop + for (float purge_count = purge_length; purge_count > 0 && marlin.wait_for_user; --purge_count) unscaled_e_move(1, ADVANCED_PAUSE_PURGE_FEEDRATE); - wait_for_user = false; + marlin.user_resume(); #else @@ -297,14 +297,14 @@ bool load_filament(const float slow_load_length/*=0*/, const float fast_load_len if (show_lcd) { // Show "Purge More" / "Resume" menu and wait for reply KEEPALIVE_STATE(PAUSED_FOR_USER); - wait_for_user = false; + marlin.user_resume(); #if ANY(HAS_MARLINUI_MENU, EXTENSIBLE_UI) ui.pause_show_message(PAUSE_MESSAGE_OPTION); // MarlinUI and MKS UI also set PAUSE_RESPONSE_WAIT_FOR #else pause_menu_response = PAUSE_RESPONSE_WAIT_FOR; TERN_(SOVOL_SV06_RTS, rts.gotoPage(ID_PurgeMore_L, ID_PurgeMore_D)); #endif - while (pause_menu_response == PAUSE_RESPONSE_WAIT_FOR) idle_no_sleep(); + while (pause_menu_response == PAUSE_RESPONSE_WAIT_FOR) marlin.idle_no_sleep(); } #endif @@ -553,8 +553,8 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep KEEPALIVE_STATE(PAUSED_FOR_USER); TERN_(HOST_PROMPT_SUPPORT, hostui.continue_prompt(GET_TEXT_F(MSG_NOZZLE_PARKED))); TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_NOZZLE_PARKED))); - wait_for_user = true; // LCD click or M108 will clear this - while (wait_for_user) { + marlin.wait_start(); // LCD click or M108 will clear this + while (marlin.wait_for_user) { impatient_beep(max_beep_count); // If the nozzle has timed out... @@ -579,7 +579,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_HEATER_TIMEOUT)); #endif - TERN_(HAS_RESUME_CONTINUE, wait_for_user_response(0, true)); // Wait for LCD click or M108 + TERN_(HAS_RESUME_CONTINUE, marlin.wait_for_user_response(0, true)); // Wait for LCD click or M108 TERN_(HOST_PROMPT_SUPPORT, hostui.prompt_do(PROMPT_INFO, GET_TEXT_F(MSG_REHEATING))); @@ -606,12 +606,12 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep LCD_MESSAGE(MSG_REHEATDONE); #endif - IF_DISABLED(PAUSE_REHEAT_FAST_RESUME, wait_for_user = true); + IF_DISABLED(PAUSE_REHEAT_FAST_RESUME, marlin.wait_start()); nozzle_timed_out = false; first_impatient_beep(max_beep_count); } - idle_no_sleep(); + marlin.idle_no_sleep(); } TERN_(DUAL_X_CARRIAGE, set_duplication_enabled(saved_ext_dup_mode, saved_ext)); } diff --git a/Marlin/src/feature/power.cpp b/Marlin/src/feature/power.cpp index a28d95d967..2068558fe9 100644 --- a/Marlin/src/feature/power.cpp +++ b/Marlin/src/feature/power.cpp @@ -119,7 +119,7 @@ void Power::power_on() { * Processes any PSU_POWEROFF_GCODE and makes a PS_OFF_SOUND if enabled. */ void Power::power_off() { - TERN_(HAS_SUICIDE, suicide()); + TERN_(HAS_SUICIDE, marlin.suicide()); if (!psu_on) return; @@ -208,7 +208,7 @@ void Power::power_off() { // If any of the stepper drivers are enabled... if (stepper.axis_enabled.bits) return true; - if (printJobOngoing() || printingIsPaused()) return true; + if (marlin.printJobOngoing() || marlin.printingIsPaused()) return true; #if ENABLED(AUTO_POWER_FANS) FANS_LOOP(i) if (thermalManager.fan_speed[i]) return true; diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp index 6925ed7a34..0dd19808bc 100644 --- a/Marlin/src/feature/powerloss.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -321,7 +321,7 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=POW void PrintJobRecovery::_outage(TERN_(DEBUG_POWER_LOSS_RECOVERY, const bool simulated/*=false*/)) { #if ENABLED(BACKUP_POWER_SUPPLY) static bool lock = false; - if (lock) return; // No re-entrance from idle() during retract_and_lift() + if (lock) return; // No re-entrance from marlin.idle() during retract_and_lift() lock = true; #endif @@ -355,7 +355,7 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=POW sync_plan_position(); } else - kill(GET_TEXT_F(MSG_OUTAGE_RECOVERY)); + marlin.kill(GET_TEXT_F(MSG_OUTAGE_RECOVERY)); } #endif // POWER_LOSS_PIN || DEBUG_POWER_LOSS_RECOVERY diff --git a/Marlin/src/feature/runout.h b/Marlin/src/feature/runout.h index 1cd90b0bb2..7881af4e38 100644 --- a/Marlin/src/feature/runout.h +++ b/Marlin/src/feature/runout.h @@ -31,7 +31,6 @@ #include "../module/stepper.h" // for block_t #include "../gcode/queue.h" #include "pause.h" // for did_pause_print -#include "../MarlinCore.h" // for printingIsActive() #include "../inc/MarlinConfig.h" @@ -64,7 +63,7 @@ typedef Flags< > runout_flags_t; void event_filament_runout(const uint8_t extruder); -inline bool should_monitor_runout() { return did_pause_print || printingIsActive(); } +inline bool should_monitor_runout() { return did_pause_print || marlin.printingIsActive(); } template class TFilamentMonitor; diff --git a/Marlin/src/feature/spindle_laser.cpp b/Marlin/src/feature/spindle_laser.cpp index 5f0ea7dd7b..dd8d859bde 100644 --- a/Marlin/src/feature/spindle_laser.cpp +++ b/Marlin/src/feature/spindle_laser.cpp @@ -112,7 +112,7 @@ void SpindleLaser::init() { const millis_t duration = (float(SPEED_POWER_MAX) * (60000.f / 2550.f) / float(acceleration_spindle_deg_per_s2)) * abs_diff; millis_t next_ocr_change = millis() + duration; while (current_ocr != ocr) { - while (PENDING(millis(), next_ocr_change)) idle(); + while (PENDING(millis(), next_ocr_change)) marlin.idle(); current_ocr += diff > 0 ? 1 : -1; hal.set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), current_ocr ^ SPINDLE_LASER_PWM_OFF); next_ocr_change += duration; diff --git a/Marlin/src/feature/tmc_util.cpp b/Marlin/src/feature/tmc_util.cpp index b1fc69f88a..a91d435355 100644 --- a/Marlin/src/feature/tmc_util.cpp +++ b/Marlin/src/feature/tmc_util.cpp @@ -31,7 +31,6 @@ */ #include "tmc_util.h" -#include "../MarlinCore.h" #include "../module/stepper/indirection.h" #include "../module/printcounter.h" @@ -283,7 +282,7 @@ if (data.is_s2g) SERIAL_ECHOLNPGM("coil short circuit"); TERN_(TMC_DEBUG, tmc_report_all()); TERN_(SOVOL_SV06_RTS, rts.gotoPage(ID_DriverError_L, ID_DriverError_D)); - kill(F("Driver error")); + marlin.kill(F("Driver error")); } #endif diff --git a/Marlin/src/gcode/bedlevel/G26.cpp b/Marlin/src/gcode/bedlevel/G26.cpp index ba4647e6f5..899498faae 100644 --- a/Marlin/src/gcode/bedlevel/G26.cpp +++ b/Marlin/src/gcode/bedlevel/G26.cpp @@ -105,7 +105,6 @@ #include "../gcode.h" #include "../../feature/bedlevel/bedlevel.h" -#include "../../MarlinCore.h" #include "../../module/planner.h" #include "../../module/motion.h" #include "../../module/tool_change.h" diff --git a/Marlin/src/gcode/bedlevel/G42.cpp b/Marlin/src/gcode/bedlevel/G42.cpp index 44f5ceada8..4b9b028419 100644 --- a/Marlin/src/gcode/bedlevel/G42.cpp +++ b/Marlin/src/gcode/bedlevel/G42.cpp @@ -25,7 +25,6 @@ #if HAS_MESH #include "../gcode.h" -#include "../../MarlinCore.h" // for IsRunning() #include "../../module/motion.h" #include "../../feature/bedlevel/bedlevel.h" diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index c306274aec..058d4ea4ab 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -759,7 +759,7 @@ G29_TYPE GcodeSuite::G29() { for (;;) { pos = planner.get_axis_position_mm(axis); if (inInc > 0 ? (pos >= cmp) : (pos <= cmp)) break; - idle_no_sleep(); + marlin.idle_no_sleep(); } //if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM_P(axis == Y_AXIS ? PSTR("Y=") : PSTR("X=", pos); @@ -803,7 +803,7 @@ G29_TYPE GcodeSuite::G29() { #endif abl.reenable = false; // Don't re-enable after modifying the mesh - idle_no_sleep(); + marlin.idle_no_sleep(); } // inner } // outer diff --git a/Marlin/src/gcode/calibrate/G76_M871.cpp b/Marlin/src/gcode/calibrate/G76_M871.cpp index a909ef4c84..35f7ac3174 100644 --- a/Marlin/src/gcode/calibrate/G76_M871.cpp +++ b/Marlin/src/gcode/calibrate/G76_M871.cpp @@ -96,7 +96,7 @@ void GcodeSuite::G76() { auto report_temps = [](millis_t &ntr, millis_t timeout=0) { - idle_no_sleep(); + marlin.idle_no_sleep(); const millis_t ms = millis(); if (ELAPSED(ms, ntr)) { ntr = ms + 1000; diff --git a/Marlin/src/gcode/calibrate/M100.cpp b/Marlin/src/gcode/calibrate/M100.cpp index ddfed4afe1..822ce969ec 100644 --- a/Marlin/src/gcode/calibrate/M100.cpp +++ b/Marlin/src/gcode/calibrate/M100.cpp @@ -28,8 +28,6 @@ #include "../queue.h" #include "../../libs/hex_print.h" -#include "../../MarlinCore.h" // for idle() - /** * M100: Free Memory Watcher * @@ -178,7 +176,7 @@ inline int32_t count_test_bytes(const char * const start_free_memory) { SERIAL_EOL(); start_free_memory += 16; serial_delay(25); - idle(); + marlin.idle(); } } @@ -209,12 +207,12 @@ inline int check_for_free_memory_corruption(FSTR_P const title) { if (end_free_memory < start_free_memory) { SERIAL_ECHOPGM(" end_free_memory < Heap "); //SET_INPUT_PULLUP(63); // if the developer has a switch wired up to their controller board - //safe_delay(5); // this code can be enabled to pause the display as soon as the - //while ( READ(63)) // malfunction is detected. It is currently defaulting to a switch - // idle(); // being on pin-63 which is unassigend and available on most controller - //safe_delay(20); // boards. + //safe_delay(5); // this code can be enabled to pause the display as soon as the + //while ( READ(63)) // malfunction is detected. It is currently defaulting to a switch + // marlin.idle(); // being on pin-63 which is unassigend and available on most controller + //safe_delay(20); // boards. //while ( !READ(63)) - // idle(); + // marlin.idle(); serial_delay(20); #if ENABLED(M100_FREE_MEMORY_DUMPER) M100_dump_routine(F(" Memory corruption detected with end_free_memory -1) { - if (pin_is_protected(pin)) + if (marlin.pin_is_protected(pin)) protected_pin_err(); else { int target = LOW; @@ -51,7 +50,7 @@ void GcodeSuite::M226() { case 0: target = LOW; break; case -1: target = !extDigitalRead(pin); break; } - while (int(extDigitalRead(pin)) != target) idle(); + while (int(extDigitalRead(pin)) != target) marlin.idle(); } } // pin_state -1 0 1 && pin > -1 } // parser.seen('P') diff --git a/Marlin/src/gcode/control/M42.cpp b/Marlin/src/gcode/control/M42.cpp index 4ac7834f90..717b0695a4 100644 --- a/Marlin/src/gcode/control/M42.cpp +++ b/Marlin/src/gcode/control/M42.cpp @@ -37,8 +37,6 @@ #define OUTPUT_OPEN_DRAIN OUTPUT_OPEN_DRAIN #endif -bool pin_is_protected(const pin_t pin); - void protected_pin_err() { SERIAL_ERROR_MSG(STR_ERR_PROTECTED_PIN); } @@ -63,7 +61,7 @@ void GcodeSuite::M42() { const pin_t pin = GET_PIN_MAP_PIN(pin_index); - if (!parser.boolval('I') && pin_is_protected(pin)) return protected_pin_err(); + if (!parser.boolval('I') && marlin.pin_is_protected(pin)) return protected_pin_err(); bool avoidWrite = false; if (parser.seenval('T')) { diff --git a/Marlin/src/gcode/control/M80_M81.cpp b/Marlin/src/gcode/control/M80_M81.cpp index a37b0af680..a7653a4037 100644 --- a/Marlin/src/gcode/control/M80_M81.cpp +++ b/Marlin/src/gcode/control/M80_M81.cpp @@ -93,7 +93,7 @@ void GcodeSuite::M81() { safe_delay(1000); // Wait 1 second before switching off #if ENABLED(CONFIGURABLE_MACHINE_NAME) - ui.set_status(&MString<30>(&machine_name, ' ', F(STR_OFF), '.')); + ui.set_status(&MString<30>(&marlin.machine_name, ' ', F(STR_OFF), '.')); #else LCD_MESSAGE_F(MACHINE_NAME " " STR_OFF "."); #endif @@ -125,6 +125,6 @@ void GcodeSuite::M81() { #if ENABLED(PSU_CONTROL) powerManager.power_off_soon(); #elif HAS_SUICIDE - suicide(); + marlin.suicide(); #endif } diff --git a/Marlin/src/gcode/control/M999.cpp b/Marlin/src/gcode/control/M999.cpp index b4278fccad..e1408a576a 100644 --- a/Marlin/src/gcode/control/M999.cpp +++ b/Marlin/src/gcode/control/M999.cpp @@ -23,7 +23,7 @@ #include "../gcode.h" #include "../../lcd/marlinui.h" // for ui.reset_alert_level -#include "../../MarlinCore.h" // for marlin_state +#include "../../MarlinCore.h" // for setState #include "../queue.h" // for flush_and_request_resend /** @@ -36,7 +36,7 @@ * existing command buffer. */ void GcodeSuite::M999() { - marlin_state = MarlinState::MF_RUNNING; + marlin.setState(MarlinState::MF_RUNNING); ui.reset_alert_level(); if (parser.boolval('S')) return; diff --git a/Marlin/src/gcode/feature/camera/M240.cpp b/Marlin/src/gcode/feature/camera/M240.cpp index 23ec4ea1e7..8bf0f5d539 100644 --- a/Marlin/src/gcode/feature/camera/M240.cpp +++ b/Marlin/src/gcode/feature/camera/M240.cpp @@ -31,10 +31,6 @@ millis_t chdk_timeout; // = 0 #endif -#if defined(PHOTO_POSITION) && PHOTO_DELAY_MS > 0 - #include "../../../MarlinCore.h" // for idle() -#endif - #ifdef PHOTO_RETRACT_MM #define _PHOTO_RETRACT_MM (PHOTO_RETRACT_MM + 0) @@ -185,7 +181,7 @@ void GcodeSuite::M240() { #ifdef PHOTO_POSITION #if PHOTO_DELAY_MS > 0 const millis_t timeout = millis() + parser.intval('P', PHOTO_DELAY_MS); - while (PENDING(millis(), timeout)) idle(); + while (PENDING(millis(), timeout)) marlin.idle(); #endif do_blocking_move_to(old_pos, fr_mm_s); #ifdef PHOTO_RETRACT_MM diff --git a/Marlin/src/gcode/feature/filwidth/M404-M407.cpp b/Marlin/src/gcode/feature/filwidth/M404-M407.cpp index ff174ecf13..5b906760ed 100644 --- a/Marlin/src/gcode/feature/filwidth/M404-M407.cpp +++ b/Marlin/src/gcode/feature/filwidth/M404-M407.cpp @@ -26,7 +26,6 @@ #include "../../../feature/filwidth.h" #include "../../../module/planner.h" -#include "../../../MarlinCore.h" #include "../../gcode.h" /** diff --git a/Marlin/src/gcode/feature/power_monitor/M430.cpp b/Marlin/src/gcode/feature/power_monitor/M430.cpp index 6bbb475a7d..178494790d 100644 --- a/Marlin/src/gcode/feature/power_monitor/M430.cpp +++ b/Marlin/src/gcode/feature/power_monitor/M430.cpp @@ -25,7 +25,6 @@ #if HAS_POWER_MONITOR #include "../../../feature/power_monitor.h" -#include "../../../MarlinCore.h" #include "../../gcode.h" /** diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 6dab1eb3bb..c5b05583e2 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -252,7 +252,7 @@ void GcodeSuite::get_destination_from_command() { */ void GcodeSuite::dwell(const millis_t time) { const millis_t start_ms = millis(); - while (PENDING(millis(), start_ms, time)) idle(); + while (PENDING(millis(), start_ms, time)) marlin.idle(); } /** @@ -286,7 +286,7 @@ void GcodeSuite::dwell(const millis_t time) { #ifdef ACTION_ON_CANCEL hostui.cancel(); #endif - kill(GET_TEXT_F(MSG_LCD_PROBING_FAILED)); + marlin.kill(GET_TEXT_F(MSG_LCD_PROBING_FAILED)); #endif } diff --git a/Marlin/src/gcode/gcode_d.cpp b/Marlin/src/gcode/gcode_d.cpp index bc0d640b73..1e472e0f6e 100644 --- a/Marlin/src/gcode/gcode_d.cpp +++ b/Marlin/src/gcode/gcode_d.cpp @@ -58,7 +58,7 @@ void GcodeSuite::D(const int16_t dcode) { break; case 10: - kill(F("D10"), F("KILL TEST"), parser.seen_test('P')); + marlin.kill(F("D10"), F("KILL TEST"), parser.seen_test('P')); break; case 1: { diff --git a/Marlin/src/gcode/geometry/M206_M428.cpp b/Marlin/src/gcode/geometry/M206_M428.cpp index 3cecbbca43..17bd2b1ff6 100644 --- a/Marlin/src/gcode/geometry/M206_M428.cpp +++ b/Marlin/src/gcode/geometry/M206_M428.cpp @@ -28,7 +28,6 @@ #include "../../module/motion.h" #include "../../lcd/marlinui.h" #include "../../libs/buzzer.h" -#include "../../MarlinCore.h" /** * M206: Set Additional Homing Offset (X Y Z). SCARA aliases T=X, P=Y diff --git a/Marlin/src/gcode/host/M16.cpp b/Marlin/src/gcode/host/M16.cpp index fc41ba3322..3b4020b594 100644 --- a/Marlin/src/gcode/host/M16.cpp +++ b/Marlin/src/gcode/host/M16.cpp @@ -33,8 +33,8 @@ */ void GcodeSuite::M16() { - if (TERN(CONFIGURABLE_MACHINE_NAME, strcmp(parser.string_arg, machine_name), strcmp_P(parser.string_arg, PSTR(MACHINE_NAME)))) - kill(GET_TEXT_F(MSG_KILL_EXPECTED_PRINTER)); + if (TERN(CONFIGURABLE_MACHINE_NAME, strcmp(parser.string_arg, marlin.machine_name), strcmp_P(parser.string_arg, PSTR(MACHINE_NAME)))) + marlin.kill(GET_TEXT_F(MSG_KILL_EXPECTED_PRINTER)); } diff --git a/Marlin/src/gcode/host/M876.cpp b/Marlin/src/gcode/host/M876.cpp index c2a519d0ac..d2f7bf5ecc 100644 --- a/Marlin/src/gcode/host/M876.cpp +++ b/Marlin/src/gcode/host/M876.cpp @@ -26,7 +26,6 @@ #include "../../feature/host_actions.h" #include "../gcode.h" -#include "../../MarlinCore.h" /** * M876: Handle Prompt Response diff --git a/Marlin/src/gcode/lcd/M0_M1.cpp b/Marlin/src/gcode/lcd/M0_M1.cpp index c600bd5da6..81c16ebdfe 100644 --- a/Marlin/src/gcode/lcd/M0_M1.cpp +++ b/Marlin/src/gcode/lcd/M0_M1.cpp @@ -29,7 +29,6 @@ #include "../gcode.h" #include "../../module/planner.h" // for synchronize() -#include "../../MarlinCore.h" // for wait_for_user_response() #if HAS_MARLINUI_MENU #include "../../lcd/marlinui.h" @@ -93,7 +92,7 @@ void GcodeSuite::M0_M1() { hostui.continue_prompt(parser.codenum ? F("M1 Stop") : F("M0 Stop")); #endif - TERN_(HAS_RESUME_CONTINUE, wait_for_user_response(ms)); + TERN_(HAS_RESUME_CONTINUE, marlin.wait_for_user_response(ms)); TERN_(HAS_MARLINUI_MENU, ui.reset_status()); } diff --git a/Marlin/src/gcode/lcd/M414.cpp b/Marlin/src/gcode/lcd/M414.cpp index 4b961ad8ca..ec0fe7913f 100644 --- a/Marlin/src/gcode/lcd/M414.cpp +++ b/Marlin/src/gcode/lcd/M414.cpp @@ -25,7 +25,6 @@ #if HAS_MULTI_LANGUAGE #include "../gcode.h" -#include "../../MarlinCore.h" #include "../../lcd/marlinui.h" /** diff --git a/Marlin/src/gcode/motion/G2_G3.cpp b/Marlin/src/gcode/motion/G2_G3.cpp index e8051d2c2a..9c5dd27f0f 100644 --- a/Marlin/src/gcode/motion/G2_G3.cpp +++ b/Marlin/src/gcode/motion/G2_G3.cpp @@ -321,7 +321,7 @@ void plan_arc( const millis_t ms = millis(); if (ELAPSED(ms, next_idle_ms)) { next_idle_ms = ms + 200UL; - idle(); + marlin.idle(); } #if N_ARC_CORRECTION > 1 diff --git a/Marlin/src/gcode/motion/G5.cpp b/Marlin/src/gcode/motion/G5.cpp index fe1e664f13..64aafffba2 100644 --- a/Marlin/src/gcode/motion/G5.cpp +++ b/Marlin/src/gcode/motion/G5.cpp @@ -39,7 +39,6 @@ */ #include "../gcode.h" -#include "../../MarlinCore.h" // for IsRunning() /** * G5: Cubic B-spline diff --git a/Marlin/src/gcode/probe/G38.cpp b/Marlin/src/gcode/probe/G38.cpp index 34cab07ed6..cd10b7295d 100644 --- a/Marlin/src/gcode/probe/G38.cpp +++ b/Marlin/src/gcode/probe/G38.cpp @@ -44,7 +44,14 @@ inline void G38_single_probe(const uint8_t move_value) { sync_plan_position(); } -inline bool G38_run_probe() { +/** + * Handle G38.N where N is the sub-code for the type of probe: + * 2 - Probe toward workpiece, stop on contact, signal error if failure + * 3 - Probe toward workpiece, stop on contact + * 4 - Probe away from workpiece, stop on contact break, signal error if failure + * 5 - Probe away from workpiece, stop on contact break + */ +FORCE_INLINE bool G38_run_probe() { bool G38_pass_fail = false; diff --git a/Marlin/src/gcode/probe/M102.cpp b/Marlin/src/gcode/probe/M102.cpp index f24a723ed7..509d1c4da2 100644 --- a/Marlin/src/gcode/probe/M102.cpp +++ b/Marlin/src/gcode/probe/M102.cpp @@ -30,7 +30,6 @@ #include "../gcode.h" #include "../../feature/bedlevel/bdl/bdl.h" -#include "../../MarlinCore.h" // for printingIsActive /** * M102: Configure the Bed Distance Sensor @@ -53,7 +52,7 @@ void GcodeSuite::M102() { const int8_t command = parser.value_int(); if (command == BDS_READ_MM) SERIAL_ECHOLNPGM("Bed Distance:", bdl.read(), "mm"); - else if ((command < BDS_IDLE) && printingIsActive()) + else if ((command < BDS_IDLE) && marlin.printingIsActive()) return; else bdl.config_state = command; diff --git a/Marlin/src/gcode/queue.cpp b/Marlin/src/gcode/queue.cpp index 632e3173ea..d733a0e3be 100644 --- a/Marlin/src/gcode/queue.cpp +++ b/Marlin/src/gcode/queue.cpp @@ -191,8 +191,8 @@ bool GCodeQueue::process_injected_command() { * Enqueue and return only when commands are actually enqueued. * Never call this from a G-code handler! */ -void GCodeQueue::enqueue_one_now(const char * const cmd) { while (!enqueue_one(cmd)) idle(); } -void GCodeQueue::enqueue_one_now(FSTR_P const fcmd) { while (!enqueue_one(fcmd)) idle(); } +void GCodeQueue::enqueue_one_now(const char * const cmd) { while (!enqueue_one(cmd)) marlin.idle(); } +void GCodeQueue::enqueue_one_now(FSTR_P const fcmd) { while (!enqueue_one(fcmd)) marlin.idle(); } /** * Attempt to enqueue a single G-code command @@ -520,7 +520,7 @@ void GCodeQueue::get_serial_commands() { // Movement commands give an alert when the machine is stopped // - if (IsStopped()) { + if (marlin.isStopped()) { char* gpos = strchr(command, 'G'); if (gpos) { switch (strtol(gpos + 1, nullptr, 10)) { @@ -538,8 +538,8 @@ void GCodeQueue::get_serial_commands() { #if DISABLED(EMERGENCY_PARSER) // Process critical commands early if (command[0] == 'M') switch (command[3]) { - case '8': if (command[2] == '0' && command[1] == '1') { wait_for_heatup = false; TERN_(HAS_MARLINUI_MENU, wait_for_user = false); } break; - case '2': if (command[2] == '1' && command[1] == '1') kill(FPSTR(M112_KILL_STR), nullptr, true); break; + case '8': if (command[2] == '0' && command[1] == '1') { marlin.end_waiting(); } break; + case '2': if (command[2] == '1' && command[1] == '1') marlin.kill(FPSTR(M112_KILL_STR), nullptr, true); break; case '0': if (command[1] == '4' && command[2] == '1') quickstop_stepper(); break; } #endif diff --git a/Marlin/src/gcode/scara/M360-M364.cpp b/Marlin/src/gcode/scara/M360-M364.cpp index f32fa09de0..ad142a09ba 100644 --- a/Marlin/src/gcode/scara/M360-M364.cpp +++ b/Marlin/src/gcode/scara/M360-M364.cpp @@ -27,10 +27,9 @@ #include "../gcode.h" #include "../../module/scara.h" #include "../../module/motion.h" -#include "../../MarlinCore.h" // for IsRunning() inline bool SCARA_move_to_cal(const uint8_t delta_a, const uint8_t delta_b) { - if (IsRunning()) { + if (marlin.isRunning()) { forward_kinematics(delta_a, delta_b); do_blocking_move_to_xy(cartes); return true; diff --git a/Marlin/src/gcode/sd/M1001.cpp b/Marlin/src/gcode/sd/M1001.cpp index a8213f3fa1..e78e6b3c21 100644 --- a/Marlin/src/gcode/sd/M1001.cpp +++ b/Marlin/src/gcode/sd/M1001.cpp @@ -43,7 +43,6 @@ #endif #if HAS_LEDS_OFF_FLAG - #include "../../MarlinCore.h" // for wait_for_user_response() #include "../../feature/leds/printer_event_leds.h" #endif @@ -100,7 +99,7 @@ void GcodeSuite::M1001() { printerEventLEDs.onPrintCompleted(); TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_PRINT_DONE))); TERN_(HOST_PROMPT_SUPPORT, hostui.continue_prompt(GET_TEXT_F(MSG_PRINT_DONE))); - TERN_(HAS_RESUME_CONTINUE, wait_for_user_response(SEC_TO_MS(TERN(HAS_MARLINUI_MENU, PE_LEDS_COMPLETED_TIME, 30)))); + TERN_(HAS_RESUME_CONTINUE, marlin.wait_for_user_response(SEC_TO_MS(TERN(HAS_MARLINUI_MENU, PE_LEDS_COMPLETED_TIME, 30)))); printerEventLEDs.onResumeAfterWait(); } #endif diff --git a/Marlin/src/gcode/sd/M24_M25.cpp b/Marlin/src/gcode/sd/M24_M25.cpp index 9c230947a6..6eb1375db4 100644 --- a/Marlin/src/gcode/sd/M24_M25.cpp +++ b/Marlin/src/gcode/sd/M24_M25.cpp @@ -45,8 +45,6 @@ #include "../../lcd/extui/dgus/DGUSDisplayDef.h" #endif -#include "../../MarlinCore.h" // for startOrResumeJob - /** * M24: Start or Resume Media Print * @@ -76,7 +74,7 @@ void GcodeSuite::M24() { if (card.isFileOpen()) { card.startOrResumeFilePrinting(); // SD card will now be read for commands - startOrResumeJob(); // Start (or resume) the print job timer + marlin.startOrResumeJob(); // Start (or resume) the print job timer TERN_(POWER_LOSS_RECOVERY, recovery.prepare()); } diff --git a/Marlin/src/gcode/sd/M32.cpp b/Marlin/src/gcode/sd/M32.cpp index 552a75cdf4..904dea1ebc 100644 --- a/Marlin/src/gcode/sd/M32.cpp +++ b/Marlin/src/gcode/sd/M32.cpp @@ -28,8 +28,6 @@ #include "../../sd/cardreader.h" #include "../../module/planner.h" // for synchronize() -#include "../../MarlinCore.h" // for startOrResumeJob - /** * M32: Select file and start SD Print * @@ -52,7 +50,7 @@ void GcodeSuite::M32() { card.startOrResumeFilePrinting(); // Procedure calls count as normal print time. - if (!call_procedure) startOrResumeJob(); + if (!call_procedure) marlin.startOrResumeJob(); } } diff --git a/Marlin/src/gcode/stats/M75-M78.cpp b/Marlin/src/gcode/stats/M75-M78.cpp index 4e1b1aff9d..b5daa8809c 100644 --- a/Marlin/src/gcode/stats/M75-M78.cpp +++ b/Marlin/src/gcode/stats/M75-M78.cpp @@ -40,7 +40,7 @@ * included in the command, print it in the header. */ void GcodeSuite::M75() { - startOrResumeJob(); // ... ExtUI::onPrintTimerStarted() + marlin.startOrResumeJob(); // ... ExtUI::onPrintTimerStarted() #if ENABLED(DWIN_LCD_PROUI) // TODO: Remove if M75 is never used if (!card.isStillPrinting()) dwinPrintHeader(parser.has_string() ? parser.string_arg : GET_TEXT(MSG_HOST_START_PRINT)); diff --git a/Marlin/src/inc/MarlinConfig.h b/Marlin/src/inc/MarlinConfig.h index 70f34944c9..85c9644af8 100644 --- a/Marlin/src/inc/MarlinConfig.h +++ b/Marlin/src/inc/MarlinConfig.h @@ -52,6 +52,7 @@ #include "../core/mstring.h" #include "../core/serial.h" #include "../core/endianness.h" + #include "../MarlinCore.h" #endif diff --git a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp index fd45c41ba1..81063d5e2e 100644 --- a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp +++ b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp @@ -850,7 +850,7 @@ void MarlinUI::draw_status_message(const bool blink) { #if ENABLED(SHOW_REMAINING_TIME) void MarlinUI::drawRemain() { - if (printJobOngoing()) { + if (marlin.printJobOngoing()) { char buffer[8]; const duration_t remaint = get_remaining_time(); #if LCD_INFO_SCREEN_STYLE == 0 @@ -873,7 +873,7 @@ void MarlinUI::draw_status_message(const bool blink) { #if ENABLED(SHOW_INTERACTION_TIME) void MarlinUI::drawInter() { const duration_t interactt = interaction_time; - if (printingIsActive() && interactt.value) { + if (marlin.printingIsActive() && interactt.value) { char buffer[8]; #if LCD_INFO_SCREEN_STYLE == 0 const uint8_t timepos = TPOFFSET - interactt.toDigital(buffer); @@ -894,7 +894,7 @@ void MarlinUI::draw_status_message(const bool blink) { #if ENABLED(SHOW_ELAPSED_TIME) void MarlinUI::drawElapsed() { - if (printJobOngoing()) { + if (marlin.printJobOngoing()) { char buffer[8]; const duration_t elapsedt = print_job_timer.duration(); #if LCD_INFO_SCREEN_STYLE == 0 @@ -1072,7 +1072,7 @@ void MarlinUI::draw_status_screen() { #else // !HAS_DUAL_MIXING - const bool show_e_total = TERN1(HAS_X_AXIS, TERN0(LCD_SHOW_E_TOTAL, printingIsActive())); + const bool show_e_total = TERN1(HAS_X_AXIS, TERN0(LCD_SHOW_E_TOTAL, marlin.printingIsActive())); if (show_e_total) { #if ENABLED(LCD_SHOW_E_TOTAL) diff --git a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp index d772447551..cdb18a74b7 100644 --- a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp +++ b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp @@ -607,7 +607,7 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const #endif #if ENABLED(SHOW_REMAINING_TIME) void MarlinUI::drawRemain() { - if (printJobOngoing()) { + if (marlin.printJobOngoing()) { const duration_t remaint = ui.get_remaining_time(); char buffer[10]; const uint8_t timepos = TPOFFSET - remaint.toDigital(buffer); @@ -620,7 +620,7 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const #if ENABLED(SHOW_INTERACTION_TIME) void MarlinUI::drawInter() { const duration_t interactt = ui.interaction_time; - if (printingIsActive() && interactt.value) { + if (marlin.printingIsActive() && interactt.value) { char buffer[10]; const uint8_t timepos = TPOFFSET - interactt.toDigital(buffer); lcd_moveto(timepos, 1); @@ -631,7 +631,7 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const #endif #if ENABLED(SHOW_ELAPSED_TIME) void MarlinUI::drawElapsed() { - if (printJobOngoing()) { + if (marlin.printJobOngoing()) { const duration_t elapsedt = print_job_timer.duration(); char buffer[10]; const uint8_t timepos = TPOFFSET - elapsedt.toDigital(buffer); diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index 34d64df465..7fd3052772 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -506,19 +506,19 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const #endif #if ENABLED(SHOW_REMAINING_TIME) void MarlinUI::drawRemain() { - if (printJobOngoing() && get_remaining_time() != 0) + if (marlin.printJobOngoing() && get_remaining_time() != 0) prepare_time_string(get_remaining_time(), 'R'); } #endif #if ENABLED(SHOW_INTERACTION_TIME) void MarlinUI::drawInter() { - if (printingIsActive() && interaction_time) + if (marlin.printingIsActive() && interaction_time) prepare_time_string(interaction_time, 'C'); } #endif #if ENABLED(SHOW_ELAPSED_TIME) void MarlinUI::drawElapsed() { - if (printJobOngoing()) + if (marlin.printJobOngoing()) prepare_time_string(print_job_timer.duration(), 'E'); } #endif @@ -549,7 +549,7 @@ void MarlinUI::draw_status_screen() { static char wstring[5], mstring[4]; #endif - const bool show_e_total = TERN1(HAS_X_AXIS, TERN0(LCD_SHOW_E_TOTAL, printingIsActive())); + const bool show_e_total = TERN1(HAS_X_AXIS, TERN0(LCD_SHOW_E_TOTAL, marlin.printingIsActive())); #if HAS_PRINT_PROGRESS static u8g_uint_t progress_bar_solid_width = 0; diff --git a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp index 703c18515a..af0330402c 100644 --- a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp +++ b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp @@ -611,7 +611,7 @@ void ST7920_Lite_Status_Screen::draw_position(const xyze_pos_t &pos, const bool // If position is unknown, flash the labels. const unsigned char alt_label = position_trusted ? 0 : (ui.get_blink() ? ' ' : 0); - if (TERN0(LCD_SHOW_E_TOTAL, printingIsActive())) { + if (TERN0(LCD_SHOW_E_TOTAL, marlin.printingIsActive())) { #if ENABLED(LCD_SHOW_E_TOTAL) char tmp[15]; const uint8_t escale = e_move_accumulator >= 100000.0f ? 10 : 1; // After 100m switch to cm @@ -694,7 +694,7 @@ bool ST7920_Lite_Status_Screen::indicators_changed() { void MarlinUI::drawRemain() { lightUI.drawRemain(); } void ST7920_Lite_Status_Screen::drawRemain() { const duration_t remaint = TERN0(SET_REMAINING_TIME, ui.get_remaining_time()); - if (printJobOngoing() && remaint.value) { + if (marlin.printJobOngoing() && remaint.value) { draw_progress_string(PPOS, prepare_time_string(remaint, 'R')); } } @@ -703,7 +703,7 @@ bool ST7920_Lite_Status_Screen::indicators_changed() { void MarlinUI::drawInter() { lightUI.drawInter(); } void ST7920_Lite_Status_Screen::drawInter() { const duration_t interactt = ui.interaction_time; - if (printingIsActive() && interactt.value) { + if (marlin.printingIsActive() && interactt.value) { draw_progress_string(PPOS, prepare_time_string(interactt, 'C')); } } @@ -711,7 +711,7 @@ bool ST7920_Lite_Status_Screen::indicators_changed() { #if ENABLED(SHOW_ELAPSED_TIME) void MarlinUI::drawElapsed() { lightUI.drawElapsed(); } void ST7920_Lite_Status_Screen::drawElapsed() { - if (printJobOngoing()) { + if (marlin.printJobOngoing()) { const duration_t elapsedt = print_job_timer.duration(); draw_progress_string(PPOS, prepare_time_string(elapsedt, 'E')); } diff --git a/Marlin/src/lcd/e3v2/common/encoder.cpp b/Marlin/src/lcd/e3v2/common/encoder.cpp index 2ae16f8bb1..2f050e92fd 100644 --- a/Marlin/src/lcd/e3v2/common/encoder.cpp +++ b/Marlin/src/lcd/e3v2/common/encoder.cpp @@ -68,8 +68,8 @@ EncoderState encoderReceiveAnalyze() { ui.refresh_brightness(); return ENCODER_DIFF_NO; } - const bool was_waiting = wait_for_user; - wait_for_user = false; + const bool was_waiting = marlin.wait_for_user; + marlin.user_resume(); return was_waiting ? ENCODER_DIFF_NO : ENCODER_DIFF_ENTER; } else return ENCODER_DIFF_NO; diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index affb4695f9..875dfd5fd1 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -312,7 +312,7 @@ void iconResume() { } void iconResumeOrPause() { - if (printingIsPaused() || hmiFlag.pause_flag || hmiFlag.pause_action) + if (marlin.printingIsPaused() || hmiFlag.pause_flag || hmiFlag.pause_action) iconResume(); else iconPause(); @@ -1982,11 +1982,11 @@ void hmiSDCardUpdate() { if (checkkey == ID_SelectFile) { redrawSDList(); } - else if (checkkey == ID_PrintProcess || checkkey == ID_Tune || printingIsActive()) { + else if (checkkey == ID_PrintProcess || checkkey == ID_Tune || marlin.printingIsActive()) { // TODO: Move card removed abort handling // to CardReader::manage_media. card.abortFilePrintSoon(); - wait_for_heatup = wait_for_user = false; + marlin.end_waiting(); dwin_abort_flag = true; // Reset feedrate, return to Home } } @@ -2389,7 +2389,7 @@ void hmiPauseOrStop() { else if (select_print.now == PRINT_STOP) { if (hmiFlag.select_flag) { checkkey = ID_BackMain; - wait_for_heatup = wait_for_user = false; // Stop waiting for heating/user + marlin.end_waiting(); // Stop waiting for heating/user card.abortFilePrintSoon(); // Let the main loop handle SD abort dwin_abort_flag = true; // Reset feedrate, return to Home #ifdef ACTION_ON_CANCEL @@ -4141,15 +4141,15 @@ void eachMomentUpdate() { dwinDrawRectangle(1, COLOR_BG_BLACK, 0, 250, DWIN_WIDTH - 1, STATUS_Y); dwinIconShow(ICON, hmiIsChinese() ? ICON_Confirm_C : ICON_Confirm_E, 86, 283); } - else if (hmiFlag.pause_flag != printingIsPaused()) { + else if (hmiFlag.pause_flag != marlin.printingIsPaused()) { // print status update - hmiFlag.pause_flag = printingIsPaused(); + hmiFlag.pause_flag = marlin.printingIsPaused(); iconResumeOrPause(); } } // pause after homing - if (hmiFlag.pause_action && printingIsPaused() && !planner.has_blocks_queued()) { + if (hmiFlag.pause_action && marlin.printingIsPaused() && !planner.has_blocks_queued()) { hmiFlag.pause_action = false; #if ENABLED(PAUSE_HEAT) TERN_(HAS_HOTEND, resume_hotend_temp = thermalManager.degTargetHotend(0)); diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp index 557a8f0c7c..1ddd54904d 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -4595,7 +4595,7 @@ void JyersDWIN::printScreenControl() { case PRINT_PAUSE_RESUME: if (paused) { if (sdprint) { - wait_for_user = false; + marlin.user_resume(); #if ENABLED(PARK_HEAD_ON_PAUSE) card.startOrResumeFilePrinting(); TERN_(POWER_LOSS_RECOVERY, recovery.prepare()); @@ -4780,15 +4780,15 @@ void JyersDWIN::confirmControl() { break; case Popup_FilInsert: popupHandler(Popup_FilChange); - wait_for_user = false; + marlin.user_resume(); break; case Popup_HeaterTime: popupHandler(Popup_Heating); - wait_for_user = false; + marlin.user_resume(); break; default: redrawMenu(true, true, false); - wait_for_user = false; + marlin.user_resume(); break; } } @@ -4935,7 +4935,7 @@ void JyersDWIN::stateUpdate() { if (process == Proc_Print) printScreenIcons(); if (process == Proc_Wait && !paused) redrawMenu(true, true); } - if (wait_for_user && !(process == Proc_Confirm) && !print_job_timer.isPaused()) + if (marlin.wait_for_user && !(process == Proc_Confirm) && !print_job_timer.isPaused()) confirmHandler(Popup_UserInput); #if ENABLED(ADVANCED_PAUSE_FEATURE) if (process == Proc_Popup && popup == Popup_PurgeMore) { diff --git a/Marlin/src/lcd/e3v2/marlinui/ui_status_480x272.cpp b/Marlin/src/lcd/e3v2/marlinui/ui_status_480x272.cpp index 798a3b2e44..dbeb02dc67 100644 --- a/Marlin/src/lcd/e3v2/marlinui/ui_status_480x272.cpp +++ b/Marlin/src/lcd/e3v2/marlinui/ui_status_480x272.cpp @@ -308,7 +308,7 @@ void MarlinUI::draw_status_screen() { // Axis values const xyz_pos_t lpos = current_position.asLogical(); - const bool show_e_total = TERN1(HAS_X_AXIS, TERN0(LCD_SHOW_E_TOTAL, printingIsActive())); + const bool show_e_total = TERN1(HAS_X_AXIS, TERN0(LCD_SHOW_E_TOTAL, marlin.printingIsActive())); constexpr int16_t cpy = TERN(DWIN_MARLINUI_PORTRAIT, 195, 117); if (show_e_total) { diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index a82e055acf..baf95d942f 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -39,7 +39,6 @@ #include "../../utf8.h" #include "../../marlinui.h" #include "../../extui/ui_api.h" -#include "../../../MarlinCore.h" #include "../../../module/temperature.h" #include "../../../module/printcounter.h" #include "../../../module/motion.h" @@ -294,7 +293,7 @@ MenuItem *fanSpeedItem = nullptr; MenuItem *mMeshMoveZItem = nullptr; MenuItem *editZValueItem = nullptr; -bool isPrinting() { return printingIsActive() || printingIsPaused(); } +bool isPrinting() { return marlin.printingIsActive() || marlin.printingIsPaused(); } bool sdPrinting() { return isPrinting() && card.isStillPrinting(); } bool hostPrinting() { return isPrinting() && !card.isStillPrinting(); } @@ -668,7 +667,7 @@ void drawPrintDone() { } void gotoPrintDone() { - wait_for_user = true; + marlin.wait_start(); if (checkkey != ID_PrintDone) { checkkey = ID_PrintDone; drawPrintDone(); @@ -1214,7 +1213,7 @@ void hmiPrinting() { switch (select_print.now) { case PRINT_SETUP: drawTuneMenu(); break; case PRINT_PAUSE_RESUME: - if (printingIsPaused()) { // If printer is already in pause + if (marlin.printingIsPaused()) { // If printer is already in pause ExtUI::resumePrint(); break; } @@ -1275,7 +1274,7 @@ void hmiWaitForUser() { hmiReturnScreen(); return; } - if (!wait_for_user) { + if (!marlin.wait_for_user) { switch (checkkey) { case ID_PrintDone: select_page.reset(); gotoMainMenu(); break; default: ui.reset_status(true); hmiReturnScreen(); break; @@ -1366,8 +1365,8 @@ void eachMomentUpdate() { dwinPrintFinished(); } - if ((hmiFlag.pause_flag != printingIsPaused()) && !hmiFlag.home_flag) { - hmiFlag.pause_flag = printingIsPaused(); + if ((hmiFlag.pause_flag != marlin.printingIsPaused()) && !hmiFlag.home_flag) { + hmiFlag.pause_flag = marlin.printingIsPaused(); if (hmiFlag.pause_flag) dwinPrintPause(); else if (hmiFlag.abort_flag) @@ -1517,14 +1516,14 @@ void hmiSaveProcessID(const uint8_t id) { TERN_(HAS_BED_PROBE, case ID_Leveling:) TERN_(HAS_ESDIAG, case ID_ESDiagProcess:) TERN_(PROUI_ITEM_PLOT, case ID_PlotProcess:) - wait_for_user = true; + marlin.wait_start(); default: break; } } void hmiReturnScreen() { checkkey = last_checkkey; - wait_for_user = false; + marlin.user_resume(); drawMainArea(); } @@ -1823,7 +1822,7 @@ void dwinPrintFinished() { TERN_(POWER_LOSS_RECOVERY, if (card.isPrinting()) recovery.cancel()); hmiFlag.abort_flag = false; hmiFlag.pause_flag = false; - wait_for_heatup = false; + marlin.heatup_done(); planner.finish_and_disable(); thermalManager.cooldown(); gotoPrintDone(); @@ -1960,9 +1959,9 @@ void MarlinUI::update() { void MarlinUI::_set_brightness() { dwinLCDBrightness(backlight ? brightness : 0); if (!backlight) - wait_for_user = true; + marlin.wait_start(); else if (checkkey != ID_PrintDone) - wait_for_user = false; + marlin.user_resume(); } #endif @@ -2133,7 +2132,7 @@ void gotoConfirmToPrint() { // Reset Printer void rebootPrinter() { - wait_for_heatup = wait_for_user = false; // Stop waiting for heating/user + marlin.end_waiting(); // Stop waiting for heating/user thermalManager.disable_all_heaters(); planner.finish_and_disable(); dwinRebootScreen(); diff --git a/Marlin/src/lcd/e3v2/proui/dwin_popup.cpp b/Marlin/src/lcd/e3v2/proui/dwin_popup.cpp index d499151e3f..f0ed1a6c07 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin_popup.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin_popup.cpp @@ -79,7 +79,7 @@ void gotoPopup(const popupDrawFunc_t fnDraw, const popupClickFunc_t fnClick/*=nu } void hmiPopup() { - if (!wait_for_user) { + if (!marlin.wait_for_user) { if (popupClick) popupClick(); return; } diff --git a/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp b/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp index 9ad098f149..ddd73d72b5 100644 --- a/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp +++ b/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp @@ -191,7 +191,7 @@ bool Preview::hasPreview() { void Preview::drawFromSD() { if (!hasPreview()) { hmiFlag.select_flag = 1; - wait_for_user = false; + marlin.user_resume(); return; } diff --git a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp index b4e1978283..6de7683843 100644 --- a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp +++ b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp @@ -612,7 +612,7 @@ void ChironTFT::panelAction(uint8_t req) { break; case 12: // A12 Kill printer - kill(); // from marlincore.h + marlin.kill(); // from MarlinCore.h break; case 13: // A13 Select file diff --git a/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp index 8930cc37c2..bc212bf42c 100644 --- a/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp +++ b/Marlin/src/lcd/extui/anycubic_i3mega/anycubic_i3mega_lcd.cpp @@ -627,7 +627,7 @@ void AnycubicTFT::getCommandFromTFT() { break; case 12: // A12 kill - kill(F(STR_ERR_KILLED)); + marlin.kill(F(STR_ERR_KILLED)); break; case 13: // A13 SELECTION FILE diff --git a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp index f4c7db544b..2cf8193c74 100644 --- a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp @@ -213,7 +213,7 @@ void DGUSScreenHandler::handleManualMove(DGUS_VP_Variable &var, void *val_ptr) { snprintf_P(buf, 32, PSTR("G0 F%d"), backup_speed); queue.enqueue_one_now(buf); } - //while (!enqueue_and_echo_command(buf)) idle(); + //while (!enqueue_and_echo_command(buf)) marlin.idle(); if (!old_relative_mode) queue.enqueue_now(F("G90")); } diff --git a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp index a62d3a2ffc..f718ee16af 100644 --- a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp @@ -215,7 +215,7 @@ void DGUSScreenHandler::handleManualMove(DGUS_VP_Variable &var, void *val_ptr) { snprintf_P(buf, 32, PSTR("G0 F%d"), backup_speed); queue.enqueue_one_now(buf); } - //while (!enqueue_and_echo_command(buf)) idle(); + //while (!enqueue_and_echo_command(buf)) marlin.idle(); if (!old_relative_mode) queue.enqueue_now(F("G90")); } diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp index 2965d75da3..d39c3079be 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp @@ -28,7 +28,6 @@ #include "../../../../inc/MarlinConfig.h" -#include "../../../../MarlinCore.h" #include "../../../../module/settings.h" #include "../../../../module/temperature.h" #include "../../../../module/motion.h" @@ -287,7 +286,7 @@ void DGUSScreenHandler::screenChangeHook(DGUS_VP_Variable &var, void *val_ptr) { // can change any page to use this function and it will check whether a print // job is active. If so DGUS will go to the printing page to continue the job. // - //if (printJobOngoing() || printingIsPaused()) { + //if (marlin.printJobOngoing() || marlin.printingIsPaused()) { // if (target == MKSLCD_PAUSE_SETTING_MOVE || target == MKSLCD_PAUSE_SETTING_EX // || target == MKSLCD_SCREEN_PRINT || target == MKSLCD_SCREEN_PAUSE // ) { @@ -321,7 +320,7 @@ void DGUSScreenHandlerMKS::screenBackChange(DGUS_VP_Variable &var, void *val_ptr void DGUSScreenHandlerMKS::zOffsetConfirm(DGUS_VP_Variable &var, void *val_ptr) { settings.save(); - if (printJobOngoing()) + if (marlin.printJobOngoing()) gotoScreen(MKSLCD_SCREEN_PRINT); else if (print_job_timer.isPaused) gotoScreen(MKSLCD_SCREEN_PAUSE); @@ -1192,7 +1191,7 @@ bool DGUSScreenHandlerMKS::loop() { } #if ENABLED(DGUS_MKS_RUNOUT_SENSOR) - if (booted && printingIsActive()) runoutIdle(); + if (booted && marlin.printingIsActive()) runoutIdle(); #endif #endif // SHOW_BOOTSCREEN diff --git a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp index ac73c8cf65..f577047e3a 100644 --- a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp @@ -215,7 +215,7 @@ void DGUSScreenHandler::handleManualMove(DGUS_VP_Variable &var, void *val_ptr) { snprintf_P(buf, 32, PSTR("G0 F%d"), backup_speed); queue.enqueue_one_now(buf); } - //while (!enqueue_and_echo_command(buf)) idle(); + //while (!enqueue_and_echo_command(buf)) marlin.idle(); if (!old_relative_mode) queue.enqueue_now(F("G90")); } diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.cpp index bb31a1d71a..ae9b00feb1 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSScreenHandler.cpp @@ -117,7 +117,7 @@ void DGUSScreenHandler::loop() { } if (current_screenID == DGUS_ScreenID::WAIT - && ((wait_continue && !wait_for_user) || (!wait_continue && isPrinterIdle())) + && ((wait_continue && !marlin.wait_for_user) || (!wait_continue && isPrinterIdle())) ) { moveToScreen(wait_return_screenID, true); return; @@ -453,7 +453,7 @@ void DGUSScreenHandler::moveToScreen(const DGUS_ScreenID screenID, bool abort_wa if (!abort_wait) return; - if (wait_continue && wait_for_user) + if (wait_continue && marlin.wait_for_user) ExtUI::setUserConfirmed(); } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h index a9f77a518b..08f8ca0d8f 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h @@ -27,6 +27,8 @@ #define FTDI_EXTENDED #endif + #define safe_delay safe_delay + #else // !__MARLIN_FIRMWARE__ #include diff --git a/Marlin/src/lcd/extui/ia_creality/ia_creality_rts.cpp b/Marlin/src/lcd/extui/ia_creality/ia_creality_rts.cpp index ca372e12f2..ca0a22d391 100644 --- a/Marlin/src/lcd/extui/ia_creality/ia_creality_rts.cpp +++ b/Marlin/src/lcd/extui/ia_creality/ia_creality_rts.cpp @@ -100,7 +100,7 @@ void RTS::onStartup() { delay_ms(400); // Delay to allow screen to configure #if ENABLED(CONFIGURABLE_MACHINE_NAME) - const MString<32> ready(machine_name, " Ready"); + const MString<32> ready(marlin.machine_name, " Ready"); onStatusChanged(ready); #else onStatusChanged(F(MACHINE_NAME " Ready")); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp b/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp index 1989724370..5be5e96e13 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp @@ -112,7 +112,7 @@ static void btn_ok_event_cb(lv_obj_t *btn, lv_event_t event) { #endif } else if (DIALOG_IS(TYPE_STOP)) { - wait_for_heatup = false; + marlin.heatup_done(); stop_print_time(); lv_clear_dialog(); lv_draw_ready_print(); @@ -129,7 +129,7 @@ static void btn_ok_event_cb(lv_obj_t *btn, lv_event_t event) { } #if ENABLED(ADVANCED_PAUSE_FEATURE) else if (DIALOG_IS(PAUSE_MESSAGE_WAITING, PAUSE_MESSAGE_INSERT, PAUSE_MESSAGE_HEAT)) - wait_for_user = false; + marlin.user_resume(); else if (DIALOG_IS(PAUSE_MESSAGE_OPTION)) pause_menu_response = PAUSE_RESPONSE_EXTRUDE_MORE; else if (DIALOG_IS(PAUSE_MESSAGE_RESUME)) { diff --git a/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp b/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp index ee913d6465..0027ee6194 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp @@ -27,7 +27,7 @@ #include "draw_ui.h" #include -#include "../../../MarlinCore.h" // for marlin_state +#include "../../../MarlinCore.h" // for is, setState #include "../../../module/temperature.h" #include "../../../module/motion.h" #include "../../../sd/cardreader.h" @@ -294,7 +294,7 @@ void setProBarRate() { lv_label_set_text(bar1ValueText, public_buf_l); lv_obj_align(bar1ValueText, bar1, LV_ALIGN_CENTER, 0, 0); - if (marlin_state == MarlinState::MF_SD_COMPLETE) { + if (marlin.is(MarlinState::MF_SD_COMPLETE)) { if (once_flag == 0) { stop_print_time(); @@ -309,7 +309,7 @@ void setProBarRate() { if (gCfgItems.finish_power_off) { gcode.process_subcommands_now(F("M1001")); queue.inject(F("M81")); - marlin_state = MarlinState::MF_RUNNING; + marlin.setState(MarlinState::MF_RUNNING); } #endif } diff --git a/Marlin/src/lcd/extui/mks_ui/draw_set.cpp b/Marlin/src/lcd/extui/mks_ui/draw_set.cpp index f991b615f6..4e6775bb6a 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_set.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_set.cpp @@ -57,7 +57,7 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { if (event != LV_EVENT_RELEASED) return; if (obj->mks_obj_id == ID_S_CONTINUE) return; if (obj->mks_obj_id == ID_S_MOTOR_OFF) { - TERN(HAS_SUICIDE, suicide(), queue.enqueue_now(F("M84"))); + TERN(HAS_SUICIDE, marlin.suicide(), queue.enqueue_now(F("M84"))); return; } lv_clear_set(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp index 2779db5b02..8f91279e8c 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp @@ -34,7 +34,7 @@ #include -#include "../../../MarlinCore.h" // for marlin_state +#include "../../../MarlinCore.h" // for marlin.is() #include "../../../sd/cardreader.h" #include "../../../module/motion.h" #include "../../../module/planner.h" @@ -757,7 +757,7 @@ void GUI_RefreshPage() { disp_print_time(); disp_fan_Zpos(); } - if (printing_rate_update_flag || marlin_state == MarlinState::MF_SD_COMPLETE) { + if (printing_rate_update_flag || marlin.is(MarlinState::MF_SD_COMPLETE)) { printing_rate_update_flag = false; if (!gcode_preview_over) setProBarRate(); } diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp index 31f08d2852..8a83ff62c0 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp @@ -2081,7 +2081,7 @@ void get_wifi_commands() { while (*command == ' ') command++; // skip any leading spaces // Movement commands alert when stopped - if (IsStopped()) { + if (marlin.isStopped()) { char* gpos = strchr(command, 'G'); if (gpos) { switch (strtol(gpos + 1, nullptr, 10)) { @@ -2097,11 +2097,8 @@ void get_wifi_commands() { #if DISABLED(EMERGENCY_PARSER) // Process critical commands early - if (strcmp_P(command, PSTR("M108")) == 0) { - wait_for_heatup = false; - TERN_(HAS_MARLINUI_MENU, wait_for_user = false); - } - if (strcmp_P(command, PSTR("M112")) == 0) kill(FPSTR(M112_KILL_STR), nullptr, true); + if (strcmp_P(command, PSTR("M108")) == 0) marlin.end_waiting(); + if (strcmp_P(command, PSTR("M112")) == 0) marlin.kill(FPSTR(M112_KILL_STR), nullptr, true); if (strcmp_P(command, PSTR("M410")) == 0) quickstop_stepper(); #endif diff --git a/Marlin/src/lcd/extui/nextion/nextion_tft.cpp b/Marlin/src/lcd/extui/nextion/nextion_tft.cpp index 53af67f3d9..93b2ce5144 100644 --- a/Marlin/src/lcd/extui/nextion/nextion_tft.cpp +++ b/Marlin/src/lcd/extui/nextion/nextion_tft.cpp @@ -67,7 +67,7 @@ void NextionTFT::startup() { SEND_TXT("tmppage.compiled", __DATE__ " / " __TIME__); SEND_VALasTXT("tmppage.extruder", EXTRUDERS); #if ENABLED(CONFIGURABLE_MACHINE_NAME) - SEND_VALasTXT("tmppage.printer", &machine_name); + SEND_VALasTXT("tmppage.printer", &marlin.machine_name); #else SEND_TXT("tmppage.printer", MACHINE_NAME); #endif @@ -230,7 +230,7 @@ void NextionTFT::panelInfo(uint8_t req) { SEND_TXT("tmppage.compiled", __DATE__ " / " __TIME__); SEND_VALasTXT("tmppage.extruder", EXTRUDERS); #if ENABLED(CONFIGURABLE_MACHINE_NAME) - SEND_VALasTXT("tmppage.printer", &machine_name); + SEND_VALasTXT("tmppage.printer", &marlin.machine_name); #else SEND_TXT("tmppage.printer", MACHINE_NAME); #endif diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index 0e8a84bf5b..2f96d08c10 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -1021,9 +1021,9 @@ namespace ExtUI { void coolDown() { thermalManager.cooldown(); } bool awaitingUserConfirm() { - return TERN0(HAS_RESUME_CONTINUE, wait_for_user) || TERN0(HOST_KEEPALIVE_FEATURE, getHostKeepaliveIsPaused()); + return TERN0(HAS_RESUME_CONTINUE, marlin.wait_for_user) || TERN0(HOST_KEEPALIVE_FEATURE, getHostKeepaliveIsPaused()); } - void setUserConfirmed() { TERN_(HAS_RESUME_CONTINUE, wait_for_user = false); } + void setUserConfirmed() { TERN_(HAS_RESUME_CONTINUE, marlin.user_resume()); } #if ENABLED(ADVANCED_PAUSE_FEATURE) void setPauseMenuResponse(PauseMenuResponse response) { pause_menu_response = response; } @@ -1068,7 +1068,7 @@ namespace ExtUI { bool isPrintingFromMediaPaused() { return card.isPaused(); } bool isPrinting() { - return commandsInQueue() || isPrintingFromMedia() || printJobOngoing() || printingIsPaused(); + return commandsInQueue() || isPrintingFromMedia() || marlin.printJobOngoing() || marlin.printingIsPaused(); } bool isPrintingPaused() { @@ -1076,7 +1076,7 @@ namespace ExtUI { } bool isOngoingPrintJob() { - return isPrintingFromMedia() || printJobOngoing(); + return isPrintingFromMedia() || marlin.printJobOngoing(); } bool isMediaMounted() { return card.isMounted(); } @@ -1112,7 +1112,7 @@ namespace ExtUI { void onSurviveInKilled() { thermalManager.disable_all_heaters(); flags.printer_killed = 0; - marlin_state = MarlinState::MF_RUNNING; + marlin.setState(MarlinState::MF_RUNNING); //SERIAL_ECHOLNPGM("survived at: ", millis()); } diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 8a6d18dc2d..b9f7749c97 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -22,7 +22,6 @@ #include "../inc/MarlinConfig.h" -#include "../MarlinCore.h" // for printingIsPaused, machine_name #include "../gcode/parser.h" // for axis_is_rotational, using_inch_units #if HAS_LED_POWEROFF_TIMEOUT || ALL(HAS_WIRED_LCD, PRINTER_EVENT_LEDS) || (HAS_BACKLIGHT_TIMEOUT && defined(NEOPIXEL_BKGD_INDEX_FIRST)) @@ -994,8 +993,8 @@ void MarlinUI::init() { // Ignore the click when clearing wait_for_user or waking the screen. auto do_click = [&]{ wait_for_unclick = true; - lcd_clicked = !wait_for_user && !display_is_asleep(); - wait_for_user = false; + lcd_clicked = !marlin.wait_for_user && !display_is_asleep(); + marlin.user_resume(); quick_feedback(); }; @@ -1562,7 +1561,7 @@ uint8_t expand_u8str_P(char * const outstr, PGM_P const ptpl, const int8_t ind, */ void MarlinUI::reset_status(const bool no_welcome) { FSTR_P msg; - if (printingIsPaused()) + if (marlin.printingIsPaused()) msg = GET_TEXT_F(MSG_PRINT_PAUSED); #if HAS_MEDIA else if (card.isStillPrinting()) @@ -1584,7 +1583,7 @@ uint8_t expand_u8str_P(char * const outstr, PGM_P const ptpl, const int8_t ind, else if (!no_welcome) { #if ENABLED(CONFIGURABLE_MACHINE_NAME) char new_status[MAX_MESSAGE_SIZE + 1]; - expand_u8str_P(new_status, GET_TEXT(WELCOME_MSG), 0, &machine_name); + expand_u8str_P(new_status, GET_TEXT(WELCOME_MSG), 0, &marlin.machine_name); _set_status_and_level(new_status, -1); return; #else @@ -1761,13 +1760,9 @@ uint8_t expand_u8str_P(char * const outstr, PGM_P const ptpl, const int8_t ind, #if HAS_DISPLAY - #if HAS_MEDIA - extern bool wait_for_user, wait_for_heatup; - #endif - void MarlinUI::abort_print() { #if HAS_MEDIA - wait_for_heatup = wait_for_user = false; + marlin.end_waiting(); if (card.isStillPrinting()) card.abortFilePrintSoon(); else if (card.isMounted()) @@ -1834,7 +1829,7 @@ uint8_t expand_u8str_P(char * const outstr, PGM_P const ptpl, const int8_t ind, void MarlinUI::resume_print() { reset_status(); - TERN_(PARK_HEAD_ON_PAUSE, wait_for_heatup = wait_for_user = false); + TERN_(PARK_HEAD_ON_PAUSE, marlin.end_waiting()); TERN_(HAS_MEDIA, if (card.isPaused()) queue.inject_P(M24_STR)); #ifdef ACTION_ON_RESUME hostui.resume(); diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index fa3f748b8e..0ef1ed1b3f 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -684,7 +684,7 @@ void menu_backlash(); void menu_advanced_settings() { #if ANY(POLARGRAPH, SHAPING_MENU, HAS_BED_PROBE, EDITABLE_STEPS_PER_UNIT) - const bool is_busy = printer_busy(); + const bool is_busy = marlin.printer_busy(); #endif #if ENABLED(SD_FIRMWARE_UPDATE) diff --git a/Marlin/src/lcd/menu/menu_bed_tramming.cpp b/Marlin/src/lcd/menu/menu_bed_tramming.cpp index 6302faf5b2..01de15f800 100644 --- a/Marlin/src/lcd/menu/menu_bed_tramming.cpp +++ b/Marlin/src/lcd/menu/menu_bed_tramming.cpp @@ -270,7 +270,7 @@ static void _lcd_goto_next_corner() { endstops.hit_on_purpose(); TERN_(BED_TRAMMING_AUDIO_FEEDBACK, BUZZ(200, 600)); } - idle(); + marlin.idle(); } TERN_(BLTOUCH, if (!bltouch.high_speed_mode) bltouch.stow()); ui.goto_screen(_lcd_draw_probing); diff --git a/Marlin/src/lcd/menu/menu_configuration.cpp b/Marlin/src/lcd/menu/menu_configuration.cpp index d2849ccd1b..cf1a5996f0 100644 --- a/Marlin/src/lcd/menu/menu_configuration.cpp +++ b/Marlin/src/lcd/menu/menu_configuration.cpp @@ -575,7 +575,7 @@ void menu_advanced_settings(); #endif // CUSTOM_MENU_CONFIG void menu_configuration() { - const bool busy = printer_busy(); + const bool busy = marlin.printer_busy(); START_MENU(); BACK_ITEM(MSG_MAIN_MENU); diff --git a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp index 5fae531e4a..a0e60bae26 100644 --- a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp +++ b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp @@ -67,7 +67,7 @@ void _man_probe_pt(const xy_pos_t &xy) { ui.defer_status_screen(); TERN_(HOST_PROMPT_SUPPORT, hostui.continue_prompt(GET_TEXT_F(MSG_DELTA_CALIBRATION_IN_PROGRESS))); TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_DELTA_CALIBRATION_IN_PROGRESS))); - TERN_(HAS_RESUME_CONTINUE, wait_for_user_response()); + TERN_(HAS_RESUME_CONTINUE, marlin.wait_for_user_response()); ui.goto_previous_screen_no_defer(); return current_position.z; } diff --git a/Marlin/src/lcd/menu/menu_filament.cpp b/Marlin/src/lcd/menu/menu_filament.cpp index 8d6e1b8adb..d2d6342185 100644 --- a/Marlin/src/lcd/menu/menu_filament.cpp +++ b/Marlin/src/lcd/menu/menu_filament.cpp @@ -35,7 +35,7 @@ #if HAS_FILAMENT_SENSOR #include "../../feature/runout.h" #endif -#if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) +#if E_STEPPERS > 1 || ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) #include "../../MarlinCore.h" #endif @@ -110,14 +110,10 @@ void _menu_temp_filament_op(const PauseMode mode, const int8_t extruder) { /** * "Change Filament" submenu */ -#if E_STEPPERS > 1 || ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) - bool printingIsPaused(); -#endif - void menu_change_filament() { #if E_STEPPERS > 1 || ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) // Say "filament change" when no print is active - editable.int8 = printingIsPaused() ? PAUSE_MODE_PAUSE_PRINT : PAUSE_MODE_CHANGE_FILAMENT; + editable.int8 = marlin.printingIsPaused() ? PAUSE_MODE_PAUSE_PRINT : PAUSE_MODE_CHANGE_FILAMENT; #if E_STEPPERS > 1 && ENABLED(FILAMENT_UNLOAD_ALL_EXTRUDERS) bool too_cold = false; @@ -126,7 +122,7 @@ void menu_change_filament() { #endif #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) - const bool is_busy = printer_busy(); + const bool is_busy = marlin.printer_busy(); #endif START_MENU(); diff --git a/Marlin/src/lcd/menu/menu_info.cpp b/Marlin/src/lcd/menu/menu_info.cpp index 31d83bd873..fb1f0fe76c 100644 --- a/Marlin/src/lcd/menu/menu_info.cpp +++ b/Marlin/src/lcd/menu/menu_info.cpp @@ -251,7 +251,7 @@ void menu_info_board() { STATIC_ITEM_F(F(SHORT_BUILD_VERSION)); // x.x.x-Branch STATIC_ITEM_F(F(STRING_DISTRIBUTION_DATE)); // YYYY-MM-DD HH:MM #if ENABLED(CONFIGURABLE_MACHINE_NAME) - STATIC_ITEM_C(&machine_name, SS_DEFAULT|SS_INVERT); // My3DPrinter + STATIC_ITEM_C(&marlin.machine_name, SS_DEFAULT|SS_INVERT); // My3DPrinter #else STATIC_ITEM_F(F(MACHINE_NAME), SS_DEFAULT|SS_INVERT); // My3DPrinter #endif diff --git a/Marlin/src/lcd/menu/menu_item.h b/Marlin/src/lcd/menu/menu_item.h index c3544f3c67..ec680665bf 100644 --- a/Marlin/src/lcd/menu/menu_item.h +++ b/Marlin/src/lcd/menu/menu_item.h @@ -413,8 +413,7 @@ class MenuItem_bool : public MenuEditItemBase { #define STATIC_ITEM_C(CSTR, V...) STATIC_ITEM_N_F_C(0, F("$"), CSTR, ##V) -// PSTRING_ITEM is like STATIC_ITEM -// but also takes a PSTR and style. +// PSTRING_ITEM is like STATIC_ITEM but also takes a PSTR and style. #define PSTRING_ITEM_F_P(FLABEL, PVAL, STYL) do{ \ constexpr int m = 20; \ diff --git a/Marlin/src/lcd/menu/menu_language.cpp b/Marlin/src/lcd/menu/menu_language.cpp index c92b860950..d406bec694 100644 --- a/Marlin/src/lcd/menu/menu_language.cpp +++ b/Marlin/src/lcd/menu/menu_language.cpp @@ -29,7 +29,6 @@ #if HAS_MENU_MULTI_LANGUAGE #include "menu_item.h" -#include "../../MarlinCore.h" #include "../../module/settings.h" static void set_lcd_language(const uint8_t inlang) { diff --git a/Marlin/src/lcd/menu/menu_main.cpp b/Marlin/src/lcd/menu/menu_main.cpp index 13fe4e89e2..f89aa5f741 100644 --- a/Marlin/src/lcd/menu/menu_main.cpp +++ b/Marlin/src/lcd/menu/menu_main.cpp @@ -246,7 +246,7 @@ void menu_configuration(); #endif // CUSTOM_MENU_MAIN void menu_main() { - const bool busy = printingIsActive(); + const bool busy = marlin.printingIsActive(); #if HAS_MEDIA const bool card_is_mounted = card.isMounted(), card_open = card_is_mounted && card.isFileOpen(); @@ -410,7 +410,7 @@ void menu_main() { INJECT_MENU_ITEMS(media_menu_items()); #endif - if (TERN0(MACHINE_CAN_PAUSE, printingIsPaused())) + if (TERN0(MACHINE_CAN_PAUSE, marlin.printingIsPaused())) ACTION_ITEM(MSG_RESUME_PRINT, ui.resume_print); #if ENABLED(HOST_START_MENU_ITEM) && defined(ACTION_ON_START) diff --git a/Marlin/src/lcd/menu/menu_mmu2.cpp b/Marlin/src/lcd/menu/menu_mmu2.cpp index 332f96ffe2..7e725bd20c 100644 --- a/Marlin/src/lcd/menu/menu_mmu2.cpp +++ b/Marlin/src/lcd/menu/menu_mmu2.cpp @@ -24,8 +24,6 @@ #if ENABLED(MMU_MENUS) -#include "../../MarlinCore.h" - #if HAS_PRUSA_MMU3 #include "../../feature/mmu3/mmu3.h" #include "../../feature/mmu3/mmu3_reporting.h" @@ -101,7 +99,7 @@ void action_mmu2_unload_filament() { LCD_MESSAGE(MSG_MMU2_UNLOADING_FILAMENT); while (!TERN(HAS_PRUSA_MMU3, mmu3.unload(), mmu2.unload())) { safe_delay(50); - TERN(HAS_PRUSA_MMU3, MMU3::marlin_idle(true), idle()); + TERN(HAS_PRUSA_MMU3, MMU3::marlin_idle(true), marlin.idle()); } ui.reset_status(); } @@ -154,7 +152,7 @@ void menu_mmu3_fail_stats_last_print() { sprintf_P(buffer2, PSTR("%hu"), load_fail_num); START_SCREEN(); - STATIC_ITEM_F(printJobOngoing() ? GET_TEXT_F(MSG_MMU_CURRENT_PRINT_FAILURES) : GET_TEXT_F(MSG_MMU_LAST_PRINT_FAILURES), SS_INVERT); + STATIC_ITEM_F(marlin.printJobOngoing() ? GET_TEXT_F(MSG_MMU_CURRENT_PRINT_FAILURES) : GET_TEXT_F(MSG_MMU_LAST_PRINT_FAILURES), SS_INVERT); #ifndef __AVR__ // TODO: I couldn't make this work on AVR PSTRING_ITEM(MSG_MMU_FAILS, buffer1, SS_FULL); @@ -216,7 +214,7 @@ void menu_mmu3_toolchange_stat_total() { STATIC_ITEM(MSG_MMU_MATERIAL_CHANGES, SS_INVERT); #ifndef __AVR__ // TODO: I couldn't make this work on AVR - if (printJobOngoing()) + if (marlin.printJobOngoing()) PSTRING_ITEM(MSG_MMU_CURRENT_PRINT, buffer1, SS_FULL); else PSTRING_ITEM(MSG_MMU_LAST_PRINT, buffer1, SS_FULL); @@ -233,7 +231,7 @@ void menu_mmu3_statistics() { ACTION_ITEM(MSG_MMU_DEV_INCREMENT_LOAD_FAILS, menu_mmu3_dev_increment_load_fail_stat); #endif - SUBMENU_F(printJobOngoing() ? GET_TEXT_F(MSG_MMU_CURRENT_PRINT_FAILURES) : GET_TEXT_F(MSG_MMU_LAST_PRINT_FAILURES), menu_mmu3_fail_stats_last_print); + SUBMENU_F(marlin.printJobOngoing() ? GET_TEXT_F(MSG_MMU_CURRENT_PRINT_FAILURES) : GET_TEXT_F(MSG_MMU_LAST_PRINT_FAILURES), menu_mmu3_fail_stats_last_print); SUBMENU(MSG_MMU_TOTAL_FAILURES, menu_mmu3_fail_stas_total); SUBMENU(MSG_MMU_MATERIAL_CHANGES, menu_mmu3_toolchange_stat_total); CONFIRM_ITEM(MSG_MMU_RESET_FAIL_STATS, @@ -269,7 +267,7 @@ void action_mmu2_reset() { } void menu_mmu2() { - const bool busy = printJobOngoing(); // printingIsActive(); + const bool busy = marlin.printJobOngoing(); // printingIsActive() START_MENU(); BACK_ITEM(MSG_MAIN_MENU); @@ -377,14 +375,14 @@ void mmu2_M600(const bool automatic/*=false*/) { ui.defer_status_screen(); ui.goto_screen(menu_mmu2_pause); wait_for_mmu_menu = true; - while (wait_for_mmu_menu) idle(); + while (wait_for_mmu_menu) marlin.idle(); } uint8_t mmu2_choose_filament() { ui.defer_status_screen(); ui.goto_screen(menu_mmu2_choose_filament); wait_for_mmu_menu = true; - while (wait_for_mmu_menu) idle(); + while (wait_for_mmu_menu) marlin.idle(); ui.return_to_status(); return feeder_index; } diff --git a/Marlin/src/lcd/sovol_rts/sovol_rts.cpp b/Marlin/src/lcd/sovol_rts/sovol_rts.cpp index c982a2cc32..b79d9541a8 100644 --- a/Marlin/src/lcd/sovol_rts/sovol_rts.cpp +++ b/Marlin/src/lcd/sovol_rts/sovol_rts.cpp @@ -38,7 +38,6 @@ RTS rts; #include #include #include -#include "../../MarlinCore.h" #include "../../sd/cardreader.h" #include "../../module/temperature.h" #include "../../module/planner.h" @@ -518,7 +517,7 @@ void RTS::sdCardStop() { updateTempE0(); updateTempBed(); thermalManager.zero_fan_speeds(); - wait_for_heatup = wait_for_user = false; + marlin.end_waiting(); poweroff_continue = false; #if ALL(HAS_MEDIA, POWER_LOSS_RECOVERY) if (card.flag.mounted) card.removeJobRecoveryFile(); @@ -1102,7 +1101,7 @@ void RTS::handleData() { } #endif - wait_for_heatup = wait_for_user = false; + marlin.end_waiting(); print_state = 0; break; } @@ -1364,7 +1363,7 @@ void RTS::handleData() { case 1: if (FILAMENT_IS_OUT()) break; case 2: updateTempE0(); - wait_for_heatup = wait_for_user = false; + marlin.end_waiting(); break; case 3: pause_menu_response = PAUSE_RESPONSE_EXTRUDE_MORE; break; case 4: pause_menu_response = PAUSE_RESPONSE_RESUME_PRINT; break; @@ -1617,7 +1616,7 @@ void RTS::onIdle() { } } - if (pause_action_flag && !sdcard_pause_check && printingIsPaused() && !planner.has_blocks_queued()) { + if (pause_action_flag && !sdcard_pause_check && marlin.printingIsPaused() && !planner.has_blocks_queued()) { pause_action_flag = false; queue.enqueue_now(F("G0 F3000 X0 Y0\nM18 S0")); } diff --git a/Marlin/src/lcd/tft/touch.cpp b/Marlin/src/lcd/tft/touch.cpp index cefd7cb779..de664695e6 100644 --- a/Marlin/src/lcd/tft/touch.cpp +++ b/Marlin/src/lcd/tft/touch.cpp @@ -53,9 +53,6 @@ TouchControlType Touch::touch_control_type = NONE; #if HAS_DISPLAY_SLEEP millis_t Touch::next_sleep_ms; // = 0 #endif -#if HAS_RESUME_CONTINUE - extern bool wait_for_user; -#endif void Touch::init() { TERN_(TOUCH_SCREEN_CALIBRATION, touch_calibration.calibration_reset()); @@ -91,10 +88,10 @@ void Touch::idle() { #if HAS_RESUME_CONTINUE // UI is waiting for a click anywhere? - if (wait_for_user) { + if (marlin.wait_for_user) { touch_control_type = CLICK; ui.lcd_clicked = true; - if (ui.external_control) wait_for_user = false; + if (ui.external_control) marlin.user_resume(); return; } #endif @@ -203,7 +200,7 @@ void Touch::touch(touch_control_t * const control) { // Specifically, Click to Continue #if HAS_RESUME_CONTINUE - case RESUME_CONTINUE: extern bool wait_for_user; wait_for_user = false; break; + case RESUME_CONTINUE: marlin.user_resume(); break; #endif // Page Up button diff --git a/Marlin/src/lcd/tft/ui_color_ui.cpp b/Marlin/src/lcd/tft/ui_color_ui.cpp index 3287285f69..a81ff3ccc6 100644 --- a/Marlin/src/lcd/tft/ui_color_ui.cpp +++ b/Marlin/src/lcd/tft/ui_color_ui.cpp @@ -295,7 +295,7 @@ void MarlinUI::draw_status_screen() { #if ENABLED(LCD_SHOW_E_TOTAL) && defined(E_MARK_X) && defined(E_MARK_Y) && defined(E_VALUE_X) && defined(E_VALUE_Y) tft.add_text(E_MARK_X, E_MARK_Y, COLOR_AXIS_HOMED, "E"); - if (printingIsActive()) { + if (marlin.printingIsActive()) { const uint8_t escale = e_move_accumulator >= 10000.0f ? 10 : 1; // After 10m switch to cm to fit into 4 digits output of ftostr4sign() tft_string.set(ftostr4sign(e_move_accumulator / escale)); const uint16_t e_value_x = E_VALUE_X; @@ -333,7 +333,7 @@ void MarlinUI::draw_status_screen() { #if ENABLED(TOUCH_SCREEN) add_control(MENU_ICON_X, MENU_ICON_Y, menu_main, imgSettings); #if HAS_MEDIA - const bool cm = card.isMounted(), pa = printingIsActive(); + const bool cm = card.isMounted(), pa = marlin.printingIsActive(); if (cm && pa) add_control(SDCARD_ICON_X, SDCARD_ICON_Y, STOP, imgCancel, true, COLOR_CONTROL_CANCEL); else @@ -382,7 +382,7 @@ void MarlinUI::draw_status_screen() { tft.canvas(REMAINING_TIME_X, REMAINING_TIME_Y, REMAINING_TIME_W, REMAINING_TIME_H); tft.set_background(COLOR_BACKGROUND); tft_string.set(buffer); - color = printingIsActive() ? COLOR_PRINT_TIME : COLOR_INACTIVE; + color = marlin.printingIsActive() ? COLOR_PRINT_TIME : COLOR_INACTIVE; #if defined(REMAINING_TIME_IMAGE_X) && defined(REMAINING_TIME_IMAGE_Y) tft.add_image(REMAINING_TIME_IMAGE_X, REMAINING_TIME_IMAGE_Y, imgTimeRemaining, color); #endif diff --git a/Marlin/src/lcd/tft/ui_move_axis_screen_1024.cpp b/Marlin/src/lcd/tft/ui_move_axis_screen_1024.cpp index a15c05d25e..0aebd39629 100644 --- a/Marlin/src/lcd/tft/ui_move_axis_screen_1024.cpp +++ b/Marlin/src/lcd/tft/ui_move_axis_screen_1024.cpp @@ -137,7 +137,7 @@ void MarlinUI::move_axis_screen() { TERN_(TOUCH_SCREEN, touch.clear()); - const bool busy = printingIsActive(); + const bool busy = marlin.printingIsActive(); // Babysteps during printing? Select babystep for Z probe offset #if ENABLED(BABYSTEP_ZPROBE_OFFSET) diff --git a/Marlin/src/lcd/tft/ui_move_axis_screen_320.cpp b/Marlin/src/lcd/tft/ui_move_axis_screen_320.cpp index 5b1fbaf958..022d6ea270 100644 --- a/Marlin/src/lcd/tft/ui_move_axis_screen_320.cpp +++ b/Marlin/src/lcd/tft/ui_move_axis_screen_320.cpp @@ -150,7 +150,7 @@ void MarlinUI::move_axis_screen() { TERN_(TOUCH_SCREEN, touch.clear()); - const bool busy = printingIsActive(); + const bool busy = marlin.printingIsActive(); // Babysteps during printing? Select babystep for Z probe offset #if ENABLED(BABYSTEP_ZPROBE_OFFSET) diff --git a/Marlin/src/lcd/tft/ui_move_axis_screen_480.cpp b/Marlin/src/lcd/tft/ui_move_axis_screen_480.cpp index 9e42411580..e769825bd4 100644 --- a/Marlin/src/lcd/tft/ui_move_axis_screen_480.cpp +++ b/Marlin/src/lcd/tft/ui_move_axis_screen_480.cpp @@ -150,7 +150,7 @@ void MarlinUI::move_axis_screen() { TERN_(TOUCH_SCREEN, touch.clear()); - const bool busy = printingIsActive(); + const bool busy = marlin.printingIsActive(); // Babysteps during printing? Select babystep for Z probe offset #if ENABLED(BABYSTEP_ZPROBE_OFFSET) diff --git a/Marlin/src/lcd/utf8.cpp b/Marlin/src/lcd/utf8.cpp index 2fe6c14490..5eddb0aff5 100644 --- a/Marlin/src/lcd/utf8.cpp +++ b/Marlin/src/lcd/utf8.cpp @@ -35,7 +35,6 @@ #if HAS_WIRED_LCD #include "marlinui.h" - #include "../MarlinCore.h" #endif #include "utf8.h" diff --git a/Marlin/src/libs/nozzle.cpp b/Marlin/src/libs/nozzle.cpp index 0f92bac812..bfe51ed97a 100644 --- a/Marlin/src/libs/nozzle.cpp +++ b/Marlin/src/libs/nozzle.cpp @@ -28,7 +28,6 @@ Nozzle nozzle; -#include "../MarlinCore.h" #include "../module/motion.h" #if NOZZLE_CLEAN_MIN_TEMP > 20 diff --git a/Marlin/src/module/delta.cpp b/Marlin/src/module/delta.cpp index 5c913cb5c4..d211c3a133 100644 --- a/Marlin/src/module/delta.cpp +++ b/Marlin/src/module/delta.cpp @@ -35,7 +35,6 @@ #include "planner.h" #include "endstops.h" #include "../lcd/marlinui.h" -#include "../MarlinCore.h" #if HAS_BED_PROBE #include "probe.h" diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 821bb2df48..6528e15a2f 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -235,7 +235,7 @@ void Endstops::enable(const bool onoff) { hit_on_purpose(); else { TERN_(SOVOL_SV06_RTS, rts.gotoPageBeep(ID_KillHome_L, ID_KillHome_D)); - kill(GET_TEXT_F(MSG_KILL_HOMING_FAILED)); + marlin.kill(GET_TEXT_F(MSG_KILL_HOMING_FAILED)); } } #endif @@ -893,7 +893,7 @@ void Endstops::update() { #if ENABLED(SPI_ENDSTOPS) - // Called from idle() to read Trinamic stall states + // Called from marlin.idle() to read Trinamic stall states bool Endstops::tmc_spi_homing_check() { bool hit = false; diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 0a3a5a5f5e..bbf4f59bd7 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -621,10 +621,10 @@ void report_current_position_projected() { } /** - * Set a Grbl-compatible state from the current marlin_state + * Set a Grbl-compatible state from the current marlin.state */ M_StateEnum grbl_state_for_marlin_state() { - switch (marlin_state) { + switch (marlin.state) { case MarlinState::MF_INITIALIZING: return M_INIT; case MarlinState::MF_SD_COMPLETE: return M_ALARM; case MarlinState::MF_WAITING: return M_IDLE; @@ -1427,7 +1427,7 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { const millis_t ms = millis(); if (ELAPSED(ms, next_idle_ms)) { next_idle_ms = ms + 200UL; - return idle(); + return marlin.idle(); } thermalManager.task(); // Returns immediately on most calls } @@ -2576,7 +2576,7 @@ void prepare_line_to_destination() { if (endstops.state(es)) { SERIAL_ECHO_MSG("Bad ", C(AXIS_CHAR(axis)), " Endstop?"); - kill(GET_TEXT_F(MSG_KILL_HOMING_FAILED)); + marlin.kill(GET_TEXT_F(MSG_KILL_HOMING_FAILED)); } #endif // DETECT_BROKEN_ENDSTOP diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index 0ebd1b5748..fbce0166a9 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -484,12 +484,12 @@ inline bool all_axes_trusted() { return main_axes_mask == void home_if_needed(const bool keeplev=false); #if ENABLED(NO_MOTION_BEFORE_HOMING) - #define MOTION_CONDITIONS (IsRunning() && !homing_needed_error()) + #define MOTION_CONDITIONS (marlin.isRunning() && !homing_needed_error()) #else - #define MOTION_CONDITIONS IsRunning() + #define MOTION_CONDITIONS marlin.isRunning() #endif -#define BABYSTEP_ALLOWED() ((ENABLED(BABYSTEP_WITHOUT_HOMING) || all_axes_trusted()) && (ENABLED(BABYSTEP_ALWAYS_AVAILABLE) || printer_busy())) +#define BABYSTEP_ALLOWED() ((ENABLED(BABYSTEP_WITHOUT_HOMING) || all_axes_trusted()) && (ENABLED(BABYSTEP_ALWAYS_AVAILABLE) || marlin.printer_busy())) #if HAS_HOME_OFFSET extern xyz_pos_t home_offset; diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 59c7c3638b..6bee1890e3 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -1606,7 +1606,7 @@ bool Planner::busy() { } void Planner::finish_and_disable() { - while (has_blocks_queued() || cleaning_buffer_counter) idle(); + while (has_blocks_queued() || cleaning_buffer_counter) marlin.idle(); stepper.disable_all_steppers(); } @@ -1666,7 +1666,7 @@ float Planner::get_axis_position_mm(const AxisEnum axis) { /** * Block until the planner is finished processing */ -void Planner::synchronize() { while (busy()) idle(); } +void Planner::synchronize() { while (busy()) marlin.idle(); } /** * @brief Add a new linear movement to the planner queue (in terms of steps). @@ -3040,7 +3040,7 @@ bool Planner::buffer_line(const xyze_pos_t &cart, const feedRate_t fr_mm_s void Planner::buffer_page(const page_idx_t page_idx, const uint8_t extruder, const uint16_t num_steps) { if (!last_page_step_rate) { - kill(GET_TEXT_F(MSG_BAD_PAGE_SPEED)); + marlin.kill(GET_TEXT_F(MSG_BAD_PAGE_SPEED)); return; } diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 891357dbe3..2afec3b4ab 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -875,7 +875,7 @@ class Planner { FORCE_INLINE static block_t* get_next_free_block(uint8_t &next_buffer_head, const uint8_t count=1) { // Wait until there are enough slots free - while (moves_free() < count) { idle(); } + while (moves_free() < count) { marlin.idle(); } // Return the first available block next_buffer_head = next_block_index(block_buffer_head); diff --git a/Marlin/src/module/planner_bezier.cpp b/Marlin/src/module/planner_bezier.cpp index bc39d278f1..b88301b2f0 100644 --- a/Marlin/src/module/planner_bezier.cpp +++ b/Marlin/src/module/planner_bezier.cpp @@ -34,7 +34,6 @@ #include "motion.h" #include "temperature.h" -#include "../MarlinCore.h" #include "../gcode/queue.h" // See the meaning in the documentation of cubic_b_spline(). @@ -130,7 +129,7 @@ void cubic_b_spline( millis_t now = millis(); if (ELAPSED(now, next_idle_ms)) { next_idle_ms = now + 200UL; - idle(); + marlin.idle(); } // First try to reduce the step in order to make it sufficiently diff --git a/Marlin/src/module/polargraph.cpp b/Marlin/src/module/polargraph.cpp index 534ec17ef8..10e596efed 100644 --- a/Marlin/src/module/polargraph.cpp +++ b/Marlin/src/module/polargraph.cpp @@ -35,7 +35,6 @@ #include "planner.h" #include "endstops.h" #include "../lcd/marlinui.h" -#include "../MarlinCore.h" // Initialized by settings.load float segments_per_second, polargraph_max_belt_len; diff --git a/Marlin/src/module/printcounter.cpp b/Marlin/src/module/printcounter.cpp index f3d9ec8a9d..ec5bd8c456 100644 --- a/Marlin/src/module/printcounter.cpp +++ b/Marlin/src/module/printcounter.cpp @@ -34,7 +34,6 @@ Stopwatch print_job_timer; // Global Print Job Timer instance #endif #include "printcounter.h" -#include "../MarlinCore.h" #include "../HAL/shared/eeprom_api.h" #if HAS_SOUND && SERVICE_WARNING_BUZZES > 0 diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index ae688a864e..3a8bb2b6c6 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -38,8 +38,6 @@ #include "../gcode/gcode.h" #include "../lcd/marlinui.h" -#include "../MarlinCore.h" // for stop(), disable_e_steppers(), wait_for_user_response() - #if HAS_LEVELING #include "../feature/bedlevel/bedlevel.h" #endif @@ -169,7 +167,7 @@ xyz_pos_t Probe::offset; // Initialized by settings.load ui.return_to_status(); TERN_(HOST_PROMPT_SUPPORT, hostui.continue_prompt(F("Deploy TouchMI"))); - TERN_(HAS_RESUME_CONTINUE, wait_for_user_response()); + TERN_(HAS_RESUME_CONTINUE, marlin.wait_for_user_response()); ui.reset_status(); ui.goto_screen(prev_screen); @@ -392,9 +390,9 @@ FORCE_INLINE void probe_specific_action(const bool deploy) { // Wait for the probe to be attached or detached before asking for explicit user confirmation // Allow the user to interrupt KEEPALIVE_STATE(PAUSED_FOR_USER); - TERN_(HAS_RESUME_CONTINUE, wait_for_user = true); - while (deploy == PROBE_TRIGGERED() && TERN1(HAS_RESUME_CONTINUE, wait_for_user)) idle_no_sleep(); - TERN_(HAS_RESUME_CONTINUE, wait_for_user = false); + TERN_(HAS_RESUME_CONTINUE, marlin.wait_start()); + while (deploy == PROBE_TRIGGERED() && TERN1(HAS_RESUME_CONTINUE, marlin.wait_for_user)) marlin.idle_no_sleep(); + TERN_(HAS_RESUME_CONTINUE, marlin.user_resume()); OKAY_BUZZ(); } #endif @@ -405,7 +403,7 @@ FORCE_INLINE void probe_specific_action(const bool deploy) { #elif ENABLED(EXTENSIBLE_UI) ExtUI::onUserConfirmRequired(ds_fstr); #endif - TERN_(HAS_RESUME_CONTINUE, wait_for_user_response()); + TERN_(HAS_RESUME_CONTINUE, marlin.wait_for_user_response()); ui.reset_alert_level(); //ui.reset_status(); @@ -528,7 +526,7 @@ void Probe::probe_error_stop() { SERIAL_ECHOPGM(STR_STOP_BLTOUCH); #endif SERIAL_ECHOLNPGM(STR_STOP_POST); - stop(); + marlin.stop(); } /** @@ -578,11 +576,11 @@ bool Probe::set_deployed(const bool deploy, const bool no_return/*=false*/) { } if (PROBE_TRIGGERED() == deploy) { // Unchanged after deploy/stow action? - if (IsRunning()) { + if (marlin.isRunning()) { SERIAL_ERROR_MSG("Z-Probe failed"); LCD_ALERTMESSAGE_F("Err: ZPROBE"); } - stop(); + marlin.stop(); return true; } diff --git a/Marlin/src/module/scara.cpp b/Marlin/src/module/scara.cpp index 8274335862..7d1f9ce2ca 100644 --- a/Marlin/src/module/scara.cpp +++ b/Marlin/src/module/scara.cpp @@ -34,7 +34,6 @@ #if ENABLED(AXEL_TPARA) #include "endstops.h" - #include "../MarlinCore.h" #endif float segments_per_second = DEFAULT_SEGMENTS_PER_SECOND; diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 85f837b063..4a3b01c2ed 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -54,7 +54,6 @@ #include "../lcd/marlinui.h" #include "../libs/vector_3.h" // for matrix_3x3 #include "../gcode/gcode.h" -#include "../MarlinCore.h" #if ANY(EEPROM_SETTINGS, SD_FIRMWARE_UPDATE) #include "../HAL/shared/eeprom_api.h" @@ -1698,7 +1697,7 @@ void MarlinSettings::postprocess() { // CONFIGURABLE_MACHINE_NAME // #if ENABLED(CONFIGURABLE_MACHINE_NAME) - EEPROM_WRITE(machine_name); + EEPROM_WRITE(marlin.machine_name); #endif // @@ -2824,7 +2823,7 @@ void MarlinSettings::postprocess() { // CONFIGURABLE_MACHINE_NAME // #if ENABLED(CONFIGURABLE_MACHINE_NAME) - EEPROM_READ(machine_name); + EEPROM_READ(marlin.machine_name); #endif // @@ -3075,7 +3074,7 @@ void MarlinSettings::postprocess() { #if ENABLED(EEPROM_CHITCHAT) && DISABLED(DISABLE_M503) // Report the EEPROM settings - if (!validating && TERN1(EEPROM_BOOT_SILENT, IsRunning())) report(); + if (!validating && TERN1(EEPROM_BOOT_SILENT, marlin.isRunning())) report(); #endif return eeprom_error; @@ -3440,7 +3439,7 @@ void MarlinSettings::reset() { // // CONFIGURABLE_MACHINE_NAME // - TERN_(CONFIGURABLE_MACHINE_NAME, machine_name = PSTR(MACHINE_NAME)); + TERN_(CONFIGURABLE_MACHINE_NAME, marlin.machine_name = PSTR(MACHINE_NAME)); // // TOUCH_SCREEN_CALIBRATION diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index cb1926c318..76efc17e4f 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -84,7 +84,6 @@ Stepper stepper; // Singleton #include "../lcd/marlinui.h" #include "../gcode/queue.h" #include "../sd/cardreader.h" -#include "../MarlinCore.h" #include "../HAL/shared/Delay.h" #if ENABLED(BD_SENSOR) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 6bda47b573..9672e9c895 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -681,7 +681,7 @@ volatile bool Temperature::raw_temps_ready = false; /** * Run the minimal required activities during a tuning loop. - * TODO: Allow tuning routines to call idle() for more complete keepalive. + * TODO: Allow tuning routines to call marlin.idle() for more complete keepalive. */ bool Temperature::tuning_idle(const millis_t &ms) { @@ -856,8 +856,7 @@ void Temperature::factory_reset() { LCD_MESSAGE(MSG_HEATING); // PID Tuning loop - wait_for_heatup = true; - while (wait_for_heatup) { // Can be interrupted with M108 + for (marlin.heatup_start(); marlin.is_heating(); ) { // Can be interrupted with M108 const millis_t ms = millis(); @@ -1020,7 +1019,7 @@ void Temperature::factory_reset() { goto EXIT_M303; } } - wait_for_heatup = false; + marlin.heatup_done(); disable_all_heaters(); @@ -1057,7 +1056,7 @@ void Temperature::factory_reset() { } Temperature::MPC_autotuner::~MPC_autotuner() { - wait_for_heatup = false; + marlin.heatup_done(); ui.reset_status(); @@ -1082,9 +1081,8 @@ void Temperature::factory_reset() { const millis_t test_interval_ms = 10000UL; millis_t next_test_ms = curr_time_ms + test_interval_ms; ambient_temp = current_temp = degHotend(e); - wait_for_heatup = true; - for (;;) { // Can be interrupted with M108 + for (marlin.heatup_start(); ;) { // Can be interrupted with M108 if (housekeeping() == CANCELLED) return CANCELLED; if (ELAPSED(curr_time_ms, next_test_ms)) { @@ -1096,7 +1094,7 @@ void Temperature::factory_reset() { next_test_ms += test_interval_ms; } } - wait_for_heatup = false; + marlin.heatup_done(); #if ENABLED(MPC_AUTOTUNE_DEBUG) SERIAL_ECHOLNPGM("MPC_autotuner::measure_ambient_temp() Completed\n=====\n" @@ -1125,8 +1123,7 @@ void Temperature::factory_reset() { temp_samples[0] = temp_samples[1] = temp_samples[2] = current_temp; time_fastest = rate_fastest = 0; - wait_for_heatup = true; - for (;;) { // Can be interrupted with M108 + for (marlin.heatup_start(); ;) { // Can be interrupted with M108 if (housekeeping() == CANCELLED) return CANCELLED; if (ELAPSED(curr_time_ms, next_test_time_ms)) { @@ -1172,7 +1169,7 @@ void Temperature::factory_reset() { } } } - wait_for_heatup = false; + marlin.heatup_done(); hotend.soft_pwm_amount = 0; @@ -1210,8 +1207,7 @@ void Temperature::factory_reset() { #endif float last_temp = current_temp; - wait_for_heatup = true; - for (;;) { // Can be interrupted with M108 + for (marlin.heatup_start(); ;) { // Can be interrupted with M108 if (housekeeping() == CANCELLED) return CANCELLED; if (ELAPSED(curr_time_ms, next_test_ms)) { @@ -1240,11 +1236,11 @@ void Temperature::factory_reset() { if (!WITHIN(current_temp, get_sample_3_temp() - 15.0f, hotend.target + 15.0f)) { SERIAL_ECHOLNPGM(STR_MPC_TEMPERATURE_ERROR); TERN_(EXTENSIBLE_UI, ExtUI::onMPCTuning(ExtUI::mpcresult_t::MPC_TEMP_ERROR)); - wait_for_heatup = false; + marlin.heatup_done(); return FAILED; } } - wait_for_heatup = false; + marlin.heatup_done(); power_fan0 = total_energy_fan0 / MS_TO_SEC_PRECISE(test_duration); TERN_(HAS_FAN, power_fan255 = (total_energy_fan255 * 1000) / test_duration); @@ -1275,7 +1271,7 @@ void Temperature::factory_reset() { SERIAL_EOL(); } - if (!wait_for_heatup) { + if (!marlin.is_heating()) { SERIAL_ECHOLNPGM(STR_MPC_AUTOTUNE_INTERRUPTED); TERN_(EXTENSIBLE_UI, ExtUI::onMPCTuning(ExtUI::mpcresult_t::MPC_INTERRUPTED)); return MeasurementState::CANCELLED; @@ -1560,7 +1556,7 @@ int16_t Temperature::getHeaterPower(const heater_id_t heater_id) { * @param heater_id: The heater that caused the error */ inline void loud_kill(FSTR_P const lcd_msg, const heater_id_t heater_id) { - marlin_state = MarlinState::MF_KILLED; + marlin.setState(MarlinState::MF_KILLED); thermalManager.disable_all_heaters(); #if HAS_BEEPER for (uint8_t i = 20; i--;) { @@ -1586,7 +1582,7 @@ inline void loud_kill(FSTR_P const lcd_msg, const heater_id_t heater_id) { _FSTR_E(h,1) _FSTR_E(h,2) _FSTR_E(h,3) _FSTR_E(h,4) \ _FSTR_E(h,5) _FSTR_E(h,6) _FSTR_E(h,7) F(STR_E0) - kill(lcd_msg, HEATER_FSTR(heater_id)); + marlin.kill(lcd_msg, HEATER_FSTR(heater_id)); } /** @@ -1606,7 +1602,7 @@ void Temperature::_temp_error( #endif static uint8_t killed = 0; - if (IsRunning() && killed == TERN(HAS_BOGUS_TEMPERATURE_GRACE_PERIOD, 2, 0)) { + if (marlin.isRunning() && killed == TERN(HAS_BOGUS_TEMPERATURE_GRACE_PERIOD, 2, 0)) { SERIAL_ERROR_START(); SERIAL_ECHO(serial_msg); SERIAL_ECHOPGM(STR_STOPPED_HEATER); @@ -2314,14 +2310,15 @@ void Temperature::mintemp_error(const heater_id_t heater_id OPTARG(ERR_INCLUDE_T * - Update the heated bed PID output value */ void Temperature::task() { - if (marlin_state == MarlinState::MF_INITIALIZING) return hal.watchdog_refresh(); // If Marlin isn't started, at least reset the watchdog! + if (marlin.is(MarlinState::MF_INITIALIZING)) return hal.watchdog_refresh(); // If Marlin isn't started, at least reset the watchdog! static bool no_reentry = false; // Prevent recursion if (no_reentry) return; REMEMBER(mh, no_reentry, true); #if ENABLED(EMERGENCY_PARSER) - if (emergency_parser.killed_by_M112) kill(FPSTR(M112_KILL_STR), nullptr, true); + if (emergency_parser.killed_by_M112) + marlin.kill(FPSTR(M112_KILL_STR), nullptr, true); if (emergency_parser.quickstop_by_M410) { emergency_parser.quickstop_by_M410 = false; // quickstop_stepper may call idle so clear this now! @@ -2586,7 +2583,7 @@ void Temperature::task() { SERIAL_ERROR_START(); SERIAL_ECHO(e); SERIAL_ECHOLNPGM(STR_INVALID_EXTRUDER_NUM); - kill(); + marlin.kill(); return 0; } @@ -3517,7 +3514,7 @@ void Temperature::disable_all_heaters() { void Temperature::auto_job_check_timer(const bool can_start, const bool can_stop) { if (auto_job_over_threshold()) { - if (can_start) startOrResumeJob(); + if (can_start) marlin.startOrResumeJob(); } else if (can_stop) { print_job_timer.stop(); @@ -4539,7 +4536,7 @@ void Temperature::isr() { #if ENABLED(AUTO_REPORT_TEMPERATURES) AutoReporter Temperature::auto_reporter; void Temperature::AutoReportTemp::report() { - if (wait_for_heatup) return; + if (marlin.is_heating()) return; print_heater_states(active_extruder OPTARG(HAS_TEMP_REDUNDANT, ENABLED(AUTO_REPORT_REDUNDANT))); SERIAL_EOL(); } @@ -4605,8 +4602,7 @@ void Temperature::isr() { bool wants_to_cool = false; celsius_float_t target_temp = -1.0, old_temp = 9999.0; millis_t now, next_temp_ms = 0, cool_check_ms = 0; - wait_for_heatup = true; - do { + for (marlin.heatup_start(); marlin.is_heating() && TEMP_CONDITIONS; ) { // Target temperature might be changed during the loop if (target_temp != degTargetHotend(target_extruder)) { wants_to_cool = isCoolingHotend(target_extruder); @@ -4631,7 +4627,7 @@ void Temperature::isr() { SERIAL_EOL(); } - idle(); + marlin.idle(); gcode.reset_stepper_timeout(); // Keep steppers powered const celsius_float_t temp = degHotend(target_extruder); @@ -4672,16 +4668,17 @@ void Temperature::isr() { #if G26_CLICK_CAN_CANCEL if (click_to_cancel && ui.use_click()) { - wait_for_heatup = false; + marlin.heatup_done(); TERN_(HAS_MARLINUI_MENU, ui.quick_feedback()); } #endif - } while (wait_for_heatup && TEMP_CONDITIONS); + } // for ... is_heating ... // If wait_for_heatup is set, temperature was reached, no cancel - if (wait_for_heatup) { - wait_for_heatup = false; + // TODO: Use a common function to reset wait_for_heatup and update UI + if (marlin.is_heating()) { + marlin.heatup_done(); #if ENABLED(DWIN_CREALITY_LCD) hmiFlag.heat_flag = 0; duration_t elapsed = print_job_timer.duration(); // Print timer @@ -4698,12 +4695,12 @@ void Temperature::isr() { } return false; - } + } // Temperature::wait_for_hotend #if ENABLED(WAIT_FOR_HOTEND) void Temperature::wait_for_hotend_heating(const uint8_t target_extruder) { if (isHeatingHotend(target_extruder)) { - SERIAL_ECHOLNPGM("Wait for hotend heating..."); + SERIAL_ECHOLNPGM(STR_WAIT_FOR_HOTEND); LCD_MESSAGE(MSG_HEATING); wait_for_hotend(target_extruder); ui.reset_status(); @@ -4799,7 +4796,7 @@ void Temperature::isr() { bool wants_to_cool = false; celsius_float_t target_temp = -1, old_temp = 9999; millis_t now, next_temp_ms = 0, cool_check_ms = 0; - wait_for_heatup = true; + marlin.heatup_start(); do { // Target temperature might be changed during the loop if (target_temp != degTargetBed()) { @@ -4825,7 +4822,7 @@ void Temperature::isr() { SERIAL_EOL(); } - idle(); + marlin.idle(); gcode.reset_stepper_timeout(); // Keep steppers powered const celsius_float_t temp = degBed(); @@ -4864,7 +4861,7 @@ void Temperature::isr() { #if G26_CLICK_CAN_CANCEL if (click_to_cancel && ui.use_click()) { - wait_for_heatup = false; + marlin.heatup_done(); TERN_(HAS_MARLINUI_MENU, ui.quick_feedback()); } #endif @@ -4873,11 +4870,12 @@ void Temperature::isr() { first_loop = false; #endif - } while (wait_for_heatup && TEMP_BED_CONDITIONS); + } while (marlin.is_heating() && TEMP_BED_CONDITIONS); // If wait_for_heatup is set, temperature was reached, no cancel - if (wait_for_heatup) { - wait_for_heatup = false; + // TODO: Use a common function to reset wait_for_heatup and update UI + if (marlin.is_heating()) { + marlin.heatup_done(); ui.reset_status(); return true; } @@ -4887,7 +4885,7 @@ void Temperature::isr() { void Temperature::wait_for_bed_heating() { if (isHeatingBed()) { - SERIAL_ECHOLNPGM("Wait for bed heating..."); + SERIAL_ECHOLNPGM(STR_WAIT_FOR_BED); LCD_MESSAGE(MSG_BED_HEATING); wait_for_bed(); ui.reset_status(); @@ -4918,8 +4916,8 @@ void Temperature::isr() { float old_temp = 9999; millis_t next_temp_ms = 0, next_delta_check_ms = 0; - wait_for_heatup = true; - while (will_wait && wait_for_heatup) { + marlin.heatup_start(); + while (will_wait && marlin.is_heating()) { // Print Temp Reading every 10 seconds while heating up. millis_t now = millis(); @@ -4929,7 +4927,7 @@ void Temperature::isr() { SERIAL_EOL(); } - idle(); + marlin.idle(); gcode.reset_stepper_timeout(); // Keep steppers powered // Break after MIN_DELTA_SLOPE_TIME_PROBE seconds if the temperature @@ -4954,8 +4952,9 @@ void Temperature::isr() { } // If wait_for_heatup is set, temperature was reached, no cancel - if (wait_for_heatup) { - wait_for_heatup = false; + // TODO: Use a common function to reset wait_for_heatup and update UI + if (marlin.is_heating()) { + marlin.heatup_done(); ui.reset_status(); return true; } @@ -4994,7 +4993,7 @@ void Temperature::isr() { bool wants_to_cool = false; float target_temp = -1, old_temp = 9999; millis_t now, next_temp_ms = 0, cool_check_ms = 0; - wait_for_heatup = true; + marlin.heatup_start(); do { // Target temperature might be changed during the loop if (target_temp != degTargetChamber()) { @@ -5020,7 +5019,7 @@ void Temperature::isr() { SERIAL_EOL(); } - idle(); + marlin.idle(); gcode.reset_stepper_timeout(); // Keep steppers powered const float temp = degChamber(); @@ -5052,11 +5051,12 @@ void Temperature::isr() { old_temp = temp; } } - } while (wait_for_heatup && TEMP_CHAMBER_CONDITIONS); + } while (marlin.is_heating() && TEMP_CHAMBER_CONDITIONS); // If wait_for_heatup is set, temperature was reached, no cancel - if (wait_for_heatup) { - wait_for_heatup = false; + // TODO: Use a common function to reset wait_for_heatup and update UI + if (marlin.is_heating()) { + marlin.heatup_done(); ui.reset_status(); return true; } @@ -5094,7 +5094,7 @@ void Temperature::isr() { bool wants_to_cool = false; float target_temp = -1, previous_temp = 9999; millis_t now, next_temp_ms = 0, next_cooling_check_ms = 0; - wait_for_heatup = true; + marlin.heatup_start(); do { // Target temperature might be changed during the loop if (target_temp != degTargetCooler()) { @@ -5120,7 +5120,7 @@ void Temperature::isr() { SERIAL_EOL(); } - idle(); + marlin.idle(); gcode.reset_stepper_timeout(); // Keep steppers powered const celsius_float_t current_temp = degCooler(); @@ -5153,11 +5153,12 @@ void Temperature::isr() { } } - } while (wait_for_heatup && TEMP_COOLER_CONDITIONS); + } while (marlin.is_heating() && TEMP_COOLER_CONDITIONS); // If wait_for_heatup is set, temperature was reached, no cancel - if (wait_for_heatup) { - wait_for_heatup = false; + // TODO: Use a common function to reset wait_for_heatup and update UI + if (marlin.is_heating()) { + marlin.heatup_done(); ui.reset_status(); return true; } diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index 85254ea598..ab5e7fd5a7 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -430,7 +430,7 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. } else if (kill_on_error && (!tool_sensor_disabled || disable)) { sensor_tries++; - if (sensor_tries > 10) kill(F("Tool Sensor error")); + if (sensor_tries > 10) marlin.kill(F("Tool Sensor error")); safe_delay(5); } else { @@ -853,7 +853,7 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. const float xhome = x_home_pos(active_extruder); if (dual_x_carriage_mode == DXC_AUTO_PARK_MODE // If Auto-Park mode is enabled - && IsRunning() && !no_move // ...and movement is permitted + && marlin.isRunning() && !no_move // ...and movement is permitted && (delayed_move_time || current_position.x != xhome) // ...and delayed_move_time is set OR not "already parked"... ) { DEBUG_ECHOLNPGM("MoveX to ", xhome); @@ -1333,7 +1333,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { #endif // Return to position and lower again - const bool should_move = safe_to_move && !no_move && IsRunning(); + const bool should_move = safe_to_move && !no_move && marlin.isRunning(); if (should_move) { #if ANY(SINGLENOZZLE_STANDBY_TEMP, SINGLENOZZLE_STANDBY_FAN) diff --git a/Marlin/src/pins/pinsDebug.h b/Marlin/src/pins/pinsDebug.h index f897343ffc..5df96e3837 100644 --- a/Marlin/src/pins/pinsDebug.h +++ b/Marlin/src/pins/pinsDebug.h @@ -163,7 +163,7 @@ const PinInfo pin_array[] PROGMEM = { #endif #include "pinsDebug_list.h" - #line 168 + #line 167 }; @@ -173,8 +173,6 @@ const PinInfo pin_array[] PROGMEM = { #define M43_NEVER_TOUCH(Q) false #endif -bool pin_is_protected(const pin_t pin); - static void printPinIOState(const bool isout) { SERIAL_ECHO(isout ? F("Output ") : F("Input ")); } @@ -221,7 +219,7 @@ inline void printPinStateExt(const pin_t pin, const bool ignore, const bool exte } printPinNameByIndex(x); if (extended) { - if (pin_is_protected(pin) && !ignore) + if (marlin.pin_is_protected(pin) && !ignore) SERIAL_ECHOPGM("protected "); else { if (alt_pin_echo(pin)) { diff --git a/Marlin/src/pins/pinsDebug_list.h b/Marlin/src/pins/pinsDebug_list.h index 4bc2eeed52..a6807f5c69 100644 --- a/Marlin/src/pins/pinsDebug_list.h +++ b/Marlin/src/pins/pinsDebug_list.h @@ -33,7 +33,7 @@ #define ANALOG_OK(PN) WITHIN(PN, 0, NUM_ANALOG_INPUTS - 1) #endif -#line 35 // set __LINE__ to a known value for both passes +#line 37 // set __LINE__ to a known value for both passes // // Analog Pin Assignments diff --git a/Marlin/src/sd/Sd2Card.cpp b/Marlin/src/sd/Sd2Card.cpp index 97157f9718..c31501edd9 100644 --- a/Marlin/src/sd/Sd2Card.cpp +++ b/Marlin/src/sd/Sd2Card.cpp @@ -38,8 +38,6 @@ #include "Sd2Card.h" -#include "../MarlinCore.h" - #if DISABLED(SD_NO_DEFAULT_TIMEOUT) #ifndef SD_INIT_TIMEOUT #define SD_INIT_TIMEOUT 2000U // (ms) Init timeout diff --git a/Marlin/src/sd/SdBaseFile.cpp b/Marlin/src/sd/SdBaseFile.cpp index cc14ca9c29..fb3b51b47d 100644 --- a/Marlin/src/sd/SdBaseFile.cpp +++ b/Marlin/src/sd/SdBaseFile.cpp @@ -39,7 +39,6 @@ #include "SdBaseFile.h" -#include "../MarlinCore.h" SdBaseFile *SdBaseFile::cwd_ = 0; // Pointer to Current Working Directory // callback function for date/time diff --git a/Marlin/src/sd/SdVolume.cpp b/Marlin/src/sd/SdVolume.cpp index 1b8cdbdcae..875673be1e 100644 --- a/Marlin/src/sd/SdVolume.cpp +++ b/Marlin/src/sd/SdVolume.cpp @@ -35,8 +35,6 @@ #include "SdVolume.h" -#include "../MarlinCore.h" - #if !USE_MULTIPLE_CARDS // raw block cache uint32_t SdVolume::cacheBlockNumber_; // current block number diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 723f86a07e..9d91173d7b 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -32,7 +32,6 @@ #include "cardreader.h" -#include "../MarlinCore.h" #include "../libs/hex_print.h" #include "../lcd/marlinui.h" @@ -74,6 +73,9 @@ PGMSTR(M21_STR, "M21"); PGMSTR(M23_STR, "M23 %s"); PGMSTR(M24_STR, "M24"); +// Functional instance. Stub instance maintained in MarlinCore.cpp. +CardReader card; + // public: card_flags_t CardReader::flag; @@ -502,7 +504,7 @@ void CardReader::mount() { cdroot(); else { #if ANY(HAS_SD_DETECT, HAS_USB_FLASH_DRIVE) - if (marlin_state != MarlinState::MF_INITIALIZING) { + if (!marlin.is(MarlinState::MF_INITIALIZING)) { if (isSDCardSelected()) LCD_ALERTMESSAGE(MSG_MEDIA_INIT_FAIL_SD); else if (isFlashDriveSelected()) @@ -807,7 +809,7 @@ void CardReader::openFileRead(const char * const path, const uint8_t subcall_typ // Too deep? The firmware has to bail. if (file_subcall_ctr > SD_PROCEDURE_DEPTH - 1) { SERIAL_ERROR_MSG("Exceeded max SUBROUTINE depth:", SD_PROCEDURE_DEPTH); - kill(GET_TEXT_F(MSG_KILL_SUBCALL_OVERFLOW)); + marlin.kill(GET_TEXT_F(MSG_KILL_SUBCALL_OVERFLOW)); return; } @@ -1646,8 +1648,8 @@ void CardReader::fileHasFinished() { endFilePrintNow(TERN_(SD_RESORT, true)); - flag.sdprintdone = true; // Stop getting bytes from the SD card - marlin_state = MarlinState::MF_SD_COMPLETE; // Tell Marlin to enqueue M1001 soon + flag.sdprintdone = true; // Stop getting bytes from the SD card + marlin.setState(MarlinState::MF_SD_COMPLETE); // Tell Marlin to enqueue M1001 soon } #if ENABLED(AUTO_REPORT_SD_STATUS) diff --git a/docs/Queue.md b/docs/Queue.md index e0f50e7807..5d2fef0cae 100644 --- a/docs/Queue.md +++ b/docs/Queue.md @@ -39,10 +39,10 @@ Here's a basic flowchart of Marlin command processing: +--------------------------------------+ ``` -Marlin is a single-threaded application with a main `loop()` that manages the command queue and an `idle()` routine that manages the hardware. The command queue is handled in two stages: +Marlin is a single-threaded application with a main `loop()` that manages the command queue and a `marlin.idle()` routine to manage the hardware. The command queue is handled in two stages: -1. The `idle()` routine reads all inputs and attempts to enqueue any completed command lines. -2. The main `loop()` gets the command at the front the G-code queue (if any) and runs it. Each G-code command blocks the main loop, preventing the queue from advancing until it returns. To keep essential tasks and the UI running, any commands that run a long process need to call `idle()` frequently. +1. The `marlin.idle()` routine reads all inputs and attempts to enqueue any completed command lines. +2. The main `loop()` gets the command at the front the G-code queue (if any) and runs it. Each G-code command blocks the main loop, preventing the queue from advancing until it returns. To keep essential tasks and the UI running, any commands that run a long process must call `marlin.idle()` frequently. ## Synchronization From 333608a69242b10a75d2ef25c66ca4e4af99f7fa Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 2 Dec 2025 00:33:25 +0000 Subject: [PATCH 19/47] [cron] Bump distribution date (2025-12-02) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index c884bcea7a..545d23b782 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-01" +//#define STRING_DISTRIBUTION_DATE "2025-12-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 3aa89f99b0..2c8d257744 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-01" + #define STRING_DISTRIBUTION_DATE "2025-12-02" #endif /** From bfe98856039090f376ab495063f47e812b1b9f9f Mon Sep 17 00:00:00 2001 From: InsanityAutomation <38436470+InsanityAutomation@users.noreply.github.com> Date: Tue, 2 Dec 2025 16:12:35 -0500 Subject: [PATCH 20/47] =?UTF-8?q?=F0=9F=9A=B8=20Extra=20parsing=20of=20saf?= =?UTF-8?q?ety=20commands=20(#26944)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/feature/e_parser.h | 2 ++ Marlin/src/feature/pause.cpp | 2 +- Marlin/src/gcode/control/M108_M112_M410.cpp | 5 ----- Marlin/src/gcode/gcode.cpp | 16 +++++----------- Marlin/src/gcode/gcode.h | 20 +++++++++++--------- Marlin/src/gcode/host/M876.cpp | 3 +++ Marlin/src/gcode/queue.cpp | 14 ++++++-------- Marlin/src/inc/Conditionals-4-adv.h | 2 +- Marlin/src/module/temperature.cpp | 7 +++---- Marlin/src/sd/cardreader.cpp | 4 +++- ini/features.ini | 2 +- 11 files changed, 36 insertions(+), 41 deletions(-) diff --git a/Marlin/src/feature/e_parser.h b/Marlin/src/feature/e_parser.h index 17e85a331d..9f74a38116 100644 --- a/Marlin/src/feature/e_parser.h +++ b/Marlin/src/feature/e_parser.h @@ -86,6 +86,8 @@ public: static void update(State &state, const uint8_t c); + static bool isEnabled() { return enabled; } + private: static bool enabled; }; diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index 715ec087e1..025bcb8383 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -298,10 +298,10 @@ bool load_filament(const float slow_load_length/*=0*/, const float fast_load_len // Show "Purge More" / "Resume" menu and wait for reply KEEPALIVE_STATE(PAUSED_FOR_USER); marlin.user_resume(); + pause_menu_response = PAUSE_RESPONSE_WAIT_FOR; #if ANY(HAS_MARLINUI_MENU, EXTENSIBLE_UI) ui.pause_show_message(PAUSE_MESSAGE_OPTION); // MarlinUI and MKS UI also set PAUSE_RESPONSE_WAIT_FOR #else - pause_menu_response = PAUSE_RESPONSE_WAIT_FOR; TERN_(SOVOL_SV06_RTS, rts.gotoPage(ID_PurgeMore_L, ID_PurgeMore_D)); #endif while (pause_menu_response == PAUSE_RESPONSE_WAIT_FOR) marlin.idle_no_sleep(); diff --git a/Marlin/src/gcode/control/M108_M112_M410.cpp b/Marlin/src/gcode/control/M108_M112_M410.cpp index cde970c54f..e2ca9b2247 100644 --- a/Marlin/src/gcode/control/M108_M112_M410.cpp +++ b/Marlin/src/gcode/control/M108_M112_M410.cpp @@ -21,9 +21,6 @@ */ #include "../../inc/MarlinConfig.h" - -#if DISABLED(EMERGENCY_PARSER) - #include "../gcode.h" #include "../../module/motion.h" // for quickstop_stepper @@ -50,5 +47,3 @@ void GcodeSuite::M112() { void GcodeSuite::M410() { quickstop_stepper(); } - -#endif // !EMERGENCY_PARSER diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index c5b05583e2..10a6f3d65b 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -597,17 +597,11 @@ void GcodeSuite::process_parsed_command(bool no_ok/*=false*/) { case 110: M110(); break; // M110: Set Current Line Number case 111: M111(); break; // M111: Set debug level - #if DISABLED(EMERGENCY_PARSER) - case 108: M108(); break; // M108: Cancel Waiting - case 112: M112(); break; // M112: Full Shutdown - case 410: M410(); break; // M410: Quickstop - Abort all the planned moves. - #if ENABLED(HOST_PROMPT_SUPPORT) - case 876: M876(); break; // M876: Handle Host prompt responses - #endif - #else - case 108: case 112: case 410: - TERN_(HOST_PROMPT_SUPPORT, case 876:) - break; + case 108: M108(); break; // M108: Cancel Waiting + case 112: M112(); break; // M112: Full Shutdown + case 410: M410(); break; // M410: Quickstop - Abort all the planned moves. + #if ENABLED(HOST_PROMPT_SUPPORT) + case 876: M876(); break; // M876: Handle Host prompt responses #endif #if ENABLED(HOST_KEEPALIVE_FEATURE) diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 9b48813732..378a1a73f4 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -140,7 +140,7 @@ * M105 - Report current temperatures. * M106 - Set print fan speed. * M107 - Print fan off. - * M108 - Break out of heating loops (M109, M190, M303). With no controller, breaks out of M0/M1. (Requires EMERGENCY_PARSER) + * M108 - Break out of heating loops (M109, M190, M303). With no controller, breaks out of M0/M1. * M109 - S Wait for extruder current temp to reach target temp. ** Wait only when heating! ** * R Wait for extruder current temp to reach target temp. ** Wait for heating or cooling. ** * If AUTOTEMP is enabled, S B F. Exit autotemp by any M109 without F @@ -310,7 +310,7 @@ * M869 - Report position encoder module error. * * 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) + * M876 - Handle Prompt Response. (Requires HOST_PROMPT_SUPPORT) * 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) @@ -354,6 +354,7 @@ */ #include "../inc/MarlinConfig.h" +#include "../module/temperature.h" #include "parser.h" #if ENABLED(I2C_POSITION_ENCODERS) @@ -382,6 +383,9 @@ typedef bits_t(NUM_REL_MODES) relative_t; extern const char G28_STR[]; class GcodeSuite { + + friend void Temperature::task(); + public: static relative_t axis_relative; @@ -785,13 +789,11 @@ private: static void M107(); #endif - #if DISABLED(EMERGENCY_PARSER) - static void M108(); - static void M112(); - static void M410(); - #if ENABLED(HOST_PROMPT_SUPPORT) - static void M876(); - #endif + static void M108(); + static void M112(); + static void M410(); + #if ENABLED(HOST_PROMPT_SUPPORT) + static void M876(); #endif static void M110(); diff --git a/Marlin/src/gcode/host/M876.cpp b/Marlin/src/gcode/host/M876.cpp index d2f7bf5ecc..26f975f670 100644 --- a/Marlin/src/gcode/host/M876.cpp +++ b/Marlin/src/gcode/host/M876.cpp @@ -24,6 +24,9 @@ #if HAS_GCODE_M876 +#if ENABLED(EMERGENCY_PARSER) + #include "../../feature/e_parser.h" +#endif #include "../../feature/host_actions.h" #include "../gcode.h" diff --git a/Marlin/src/gcode/queue.cpp b/Marlin/src/gcode/queue.cpp index d733a0e3be..0014ca44a5 100644 --- a/Marlin/src/gcode/queue.cpp +++ b/Marlin/src/gcode/queue.cpp @@ -535,14 +535,12 @@ void GCodeQueue::get_serial_commands() { } } - #if DISABLED(EMERGENCY_PARSER) - // Process critical commands early - if (command[0] == 'M') switch (command[3]) { - case '8': if (command[2] == '0' && command[1] == '1') { marlin.end_waiting(); } break; - case '2': if (command[2] == '1' && command[1] == '1') marlin.kill(FPSTR(M112_KILL_STR), nullptr, true); break; - case '0': if (command[1] == '4' && command[2] == '1') quickstop_stepper(); break; - } - #endif + // Process critical commands early + if (command[0] == 'M') switch (command[3]) { + case '8': if (command[2] == '0' && command[1] == '1') { marlin.end_waiting(); } break; + case '2': if (command[2] == '1' && command[1] == '1') marlin.kill(FPSTR(M112_KILL_STR), nullptr, true); break; + case '0': if (command[1] == '4' && command[2] == '1') quickstop_stepper(); break; + } #if NO_TIMEOUTS > 0 last_command_time = ms; diff --git a/Marlin/src/inc/Conditionals-4-adv.h b/Marlin/src/inc/Conditionals-4-adv.h index 32cd506760..4dadeecad2 100644 --- a/Marlin/src/inc/Conditionals-4-adv.h +++ b/Marlin/src/inc/Conditionals-4-adv.h @@ -1136,7 +1136,7 @@ #undef SERIAL_XON_XOFF #endif -#if ENABLED(HOST_PROMPT_SUPPORT) && DISABLED(EMERGENCY_PARSER) +#if ENABLED(HOST_PROMPT_SUPPORT) #define HAS_GCODE_M876 1 #endif diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 9672e9c895..7d009c1c46 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -2317,19 +2317,18 @@ void Temperature::task() { REMEMBER(mh, no_reentry, true); #if ENABLED(EMERGENCY_PARSER) - if (emergency_parser.killed_by_M112) - marlin.kill(FPSTR(M112_KILL_STR), nullptr, true); + if (emergency_parser.killed_by_M112) gcode.M112(); if (emergency_parser.quickstop_by_M410) { emergency_parser.quickstop_by_M410 = false; // quickstop_stepper may call idle so clear this now! - quickstop_stepper(); + gcode.M410(); } #if HAS_MEDIA if (emergency_parser.sd_abort_by_M524) { // abort SD print immediately emergency_parser.sd_abort_by_M524 = false; card.flag.abort_sd_printing = true; - gcode.process_subcommands_now(F("M524")); + gcode.M524(); } #endif #endif diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 9d91173d7b..b5b89d4848 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -1103,7 +1103,9 @@ void CardReader::closefile(const bool store_location/*=false*/) { flag.saving = flag.logging = false; sdpos = 0; - TERN_(EMERGENCY_PARSER, emergency_parser.enable()); + #if DISABLED(SDCARD_READONLY) + TERN_(EMERGENCY_PARSER, emergency_parser.enable()); + #endif if (store_location) { // TODO: Store printer state, filename, position diff --git a/ini/features.ini b/ini/features.ini index 4afdc3dc4c..d9b0928237 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -233,7 +233,7 @@ USE_CONTROLLER_FAN = build_src_filter=+ HAS_MOTOR_CURRENT_DAC = build_src_filter=+ DIRECT_STEPPING = build_src_filter=+ + -EMERGENCY_PARSER = build_src_filter=+ - +EMERGENCY_PARSER = build_src_filter=+ EASYTHREED_UI = build_src_filter=+ I2C_POSITION_ENCODERS = build_src_filter=+ IIC_BL24CXX_EEPROM = build_src_filter=+ From 61a1c05d3ac7d555b7b606ac49b2f0c33bde7865 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 2 Dec 2025 11:59:58 -0600 Subject: [PATCH 21/47] =?UTF-8?q?=F0=9F=8E=A8=20Consistent=20tests=20paths?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/tests/core/test_macros.cpp | 2 +- Marlin/tests/feature/test_runout.cpp | 2 +- Marlin/tests/gcode/test_gcode.cpp | 4 ++-- test/unit_tests.cpp | 2 ++ test/unit_tests.h | 4 ++++ 5 files changed, 10 insertions(+), 4 deletions(-) diff --git a/Marlin/tests/core/test_macros.cpp b/Marlin/tests/core/test_macros.cpp index 75a1e88f71..38d9ae2732 100644 --- a/Marlin/tests/core/test_macros.cpp +++ b/Marlin/tests/core/test_macros.cpp @@ -21,7 +21,7 @@ */ #include "../test/unit_tests.h" -#include +#include "src/core/macros.h" // These represent enabled and disabled configuration options for testing. // They will be used by multiple tests. diff --git a/Marlin/tests/feature/test_runout.cpp b/Marlin/tests/feature/test_runout.cpp index 296e70916d..f3f2183085 100644 --- a/Marlin/tests/feature/test_runout.cpp +++ b/Marlin/tests/feature/test_runout.cpp @@ -24,7 +24,7 @@ #if ENABLED(FILAMENT_RUNOUT_SENSOR) -#include +#include "src/feature/runout.h" MARLIN_TEST(runout, poll_runout_states) { FilamentSensorBase sensor; diff --git a/Marlin/tests/gcode/test_gcode.cpp b/Marlin/tests/gcode/test_gcode.cpp index be364cb905..a64bb2b51f 100644 --- a/Marlin/tests/gcode/test_gcode.cpp +++ b/Marlin/tests/gcode/test_gcode.cpp @@ -21,8 +21,8 @@ */ #include "../test/unit_tests.h" -#include -#include +#include "src/gcode/gcode.h" +#include "src/gcode/parser.h" MARLIN_TEST(gcode, process_parsed_command) { GcodeSuite suite; diff --git a/test/unit_tests.cpp b/test/unit_tests.cpp index 174ad2ef7f..c7aed1fe8c 100644 --- a/test/unit_tests.cpp +++ b/test/unit_tests.cpp @@ -21,6 +21,8 @@ */ /** + * unit_tests.cpp - Unit for running tests in the Marlin/tests/ folder. + * * Provide the main() function used for all compiled unit test binaries. * It collects all the tests defined in the code and runs them through Unity. */ diff --git a/test/unit_tests.h b/test/unit_tests.h index f60c6c1da6..dd63406c9a 100644 --- a/test/unit_tests.h +++ b/test/unit_tests.h @@ -21,6 +21,10 @@ */ #pragma once +/** + * unit_tests.h - Unit Tests class used by cpp files in the Marlin/tests/ folder. + */ + #include #include #include From 0265975178564ccd926711b12d201ec39a0f80f3 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 2 Dec 2025 15:16:44 -0600 Subject: [PATCH 22/47] =?UTF-8?q?=E2=9C=A8=20FT=5FMOTION=20>=20FTM=5FPOLYS?= =?UTF-8?q?=20(2)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to #28197 --- Marlin/src/lcd/menu/menu_motion.cpp | 44 ++++++++++++++++++++--------- 1 file changed, 30 insertions(+), 14 deletions(-) diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index 8bc29739ac..6b14467277 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -500,7 +500,9 @@ void menu_move() { }; #else auto _shaper_name = [](const AxisEnum a) { return get_shaper_name(a); }; - auto _dmode = []{ return get_dyn_freq_mode_name(); }; + #if HAS_DYNAMIC_FREQ + auto _dmode = []{ return get_dyn_freq_mode_name(); }; + #endif #if ENABLED(FTM_POLYS) auto _traj_name = []{ return get_trajectory_name(); }; #endif @@ -554,9 +556,12 @@ void menu_move() { void menu_tune_ft_motion() { // Define stuff ahead of the menu loop ft_config_t &c = ftMotion.cfg; + #ifdef __AVR__ + // Copy Flash strings to RAM for C-string substitution // For U8G paged rendering check and skip extra string copy + #if HAS_X_AXIS MString<20> shaper_name; #if CACHE_FOR_SPEED @@ -570,6 +575,7 @@ void menu_move() { return shaper_name; }; #endif + #if HAS_DYNAMIC_FREQ MString<20> dmode; #if CACHE_FOR_SPEED @@ -583,22 +589,32 @@ void menu_move() { return dmode; }; #endif - MString<20> traj_name; - #if CACHE_FOR_SPEED - bool got_t = false; + + #if ENABLED(FTM_POLYS) + MString<20> traj_name; + #if CACHE_FOR_SPEED + bool got_t = false; + #endif + auto _traj_name = [&]{ + if (TERN1(CACHE_FOR_SPEED, !got_t)) { + TERN_(CACHE_FOR_SPEED, got_t = true); + traj_name = get_trajectory_name(); + } + return traj_name; + }; #endif - auto _traj_name = [&]{ - if (TERN1(CACHE_FOR_SPEED, !got_t)) { - TERN_(CACHE_FOR_SPEED, got_t = true); - traj_name = get_trajectory_name(); - } - return traj_name; - }; + #else // !__AVR__ + auto _shaper_name = [](const AxisEnum a) { return get_shaper_name(a); }; - auto _dmode = []{ return get_dyn_freq_mode_name(); }; - auto _traj_name = []{ return get_trajectory_name(); }; - #endif + #if HAS_DYNAMIC_FREQ + auto _dmode = []{ return get_dyn_freq_mode_name(); }; + #endif + #if ENABLED(FTM_POLYS) + auto _traj_name = []{ return get_trajectory_name(); }; + #endif + + #endif // !__AVR__ START_MENU(); BACK_ITEM(MSG_TUNE); From 14bed5aee8fc1872926c3135c52536dc6b8cec4e Mon Sep 17 00:00:00 2001 From: David Buezas Date: Tue, 2 Dec 2025 22:35:54 +0100 Subject: [PATCH 23/47] =?UTF-8?q?=E2=9A=A1=EF=B8=8F=20FTMotion=20optimized?= =?UTF-8?q?=20timing=20(#28187)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/Configuration_adv.h | 6 +- Marlin/src/HAL/STM32/timers.h | 2 +- Marlin/src/inc/Conditionals-5-post.h | 4 +- Marlin/src/module/ft_motion.cpp | 64 +---- Marlin/src/module/ft_motion.h | 42 ++-- .../module/ft_motion/resonance_generator.cpp | 5 +- Marlin/src/module/ft_motion/shaping.h | 5 + Marlin/src/module/ft_motion/smoothing.h | 5 + Marlin/src/module/ft_motion/stepping.cpp | 115 --------- Marlin/src/module/ft_motion/stepping.h | 229 ++++++++++++++++-- Marlin/src/module/stepper.cpp | 4 +- 11 files changed, 249 insertions(+), 232 deletions(-) delete mode 100644 Marlin/src/module/ft_motion/stepping.cpp diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 410b08ab2f..272d1a09e7 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1162,7 +1162,10 @@ //#define FT_MOTION_MENU // Provide a MarlinUI menu to set M493 and M494 parameters //#define FTM_HOME_AND_PROBE // Use FT Motion for homing / probing. Disable if FT Motion breaks these functions. - #define FTM_DEFAULT_DYNFREQ_MODE dynFreqMode_DISABLED // Default mode of dynamic frequency calculation. (DISABLED, Z_BASED, MASS_BASED) + //#define FTM_DYNAMIC_FREQ // Enable for linear adjustment of XY shaping frequency according to Z or E + #if ENABLED(FTM_DYNAMIC_FREQ) + #define FTM_DEFAULT_DYNFREQ_MODE dynFreqMode_DISABLED // Default mode of dynamic frequency calculation. (DISABLED, Z_BASED, MASS_BASED) + #endif #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 @@ -1219,7 +1222,6 @@ #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 #endif // FT_MOTION diff --git a/Marlin/src/HAL/STM32/timers.h b/Marlin/src/HAL/STM32/timers.h index c8c4845d98..e931daa72e 100644 --- a/Marlin/src/HAL/STM32/timers.h +++ b/Marlin/src/HAL/STM32/timers.h @@ -51,7 +51,7 @@ #define TEMP_TIMER_FREQUENCY 1000 // Temperature::isr() is expected to be called at around 1kHz // TODO: get rid of manual rate/prescale/ticks/cycles taken for procedures in stepper.cpp -#define STEPPER_TIMER_RATE 2000000 // 2 Mhz +#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 diff --git a/Marlin/src/inc/Conditionals-5-post.h b/Marlin/src/inc/Conditionals-5-post.h index f2b3e361c6..e2d2952e1b 100644 --- a/Marlin/src/inc/Conditionals-5-post.h +++ b/Marlin/src/inc/Conditionals-5-post.h @@ -3687,9 +3687,7 @@ // Fixed-Time Motion #if ENABLED(FT_MOTION) - #define FTM_TS (1.0f / FTM_FS) // (s) Time step for trajectory generation. (Reciprocal of FTM_FS) - #define FTM_STEPS_PER_UNIT_TIME (FTM_STEPPER_FS / FTM_FS) // Interpolated stepper commands per unit time - #define FTM_MIN_TICKS ((STEPPER_TIMER_RATE) / (FTM_STEPPER_FS)) // Minimum stepper ticks between steps + #define FTM_TS (1.0f / FTM_FS) // (s) Time step for trajectory generation. (Reciprocal of FTM_FS) #define FTM_RATIO (FTM_FS / FTM_MIN_SHAPE_FREQ) // Factor for use in FTM_ZMAX. DON'T CHANGE. #define FTM_SMOOTH_MAX_I uint32_t(TERN0(FTM_SMOOTHING, CEIL(FTM_FS * FTM_MAX_SMOOTHING_TIME))) // Max delays for smoothing #define FTM_ZMAX (FTM_RATIO * 2 + FTM_SMOOTH_MAX_I) // Maximum delays for shaping functions (even numbers only!) diff --git a/Marlin/src/module/ft_motion.cpp b/Marlin/src/module/ft_motion.cpp index 8c596f1fa3..30c16077c0 100644 --- a/Marlin/src/module/ft_motion.cpp +++ b/Marlin/src/module/ft_motion.cpp @@ -83,13 +83,6 @@ 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}; - -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 @@ -191,7 +184,7 @@ void FTMotion::loop() { // Set busy status for use by planner.busy() const bool oldBusy = busy; - busy = stepping.bresenham_iterations_pending > 0 || !stepper_plan_is_empty(); + busy = stepping.is_busy(); if (oldBusy && !busy) moving_axis_flags.reset(); } @@ -234,15 +227,9 @@ void FTMotion::reset() { const bool did_suspend = stepper.suspend(); endPos_prevBlock.reset(); tau = 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); - SHAPED_MAP(_RESET_ZI); - shaping.zi_idx = 0; - #endif + shaping.reset(); + TERN_(FTM_SMOOTHING, smoothing.reset();); TERN_(HAS_EXTRUDERS, prev_traj_e = 0.0f); // Reset linear advance variables. TERN_(DISTINCT_E_FACTORS, block_extruder_axis = E_AXIS); @@ -514,49 +501,12 @@ xyze_float_t FTMotion::calc_traj_point(const float dist) { 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; -} - /** * Generate stepper data of the trajectory. * Called from FTMotion::loop() */ void FTMotion::fill_stepper_plan_buffer() { - while (!stepper_plan_is_full()) { + while (!stepping.is_full()) { float total_duration = currentGenerator->getTotalDuration(); // If the current plan is empty, it will have zero duration. while (tau + FTM_TS > total_duration) { /** @@ -581,10 +531,8 @@ void FTMotion::fill_stepper_plan_buffer() { // Get distance from trajectory generator xyze_float_t traj_coords = calc_traj_point(currentGenerator->getDistanceAtTime(tau)); - stepper_plan_t plan = calc_stepper_plan(traj_coords); - - // Store in buffer - enqueue_stepper_plan(plan); + // 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 d26fa8b882..9e78195264 100644 --- a/Marlin/src/module/ft_motion.h +++ b/Marlin/src/module/ft_motion.h @@ -44,7 +44,7 @@ #define FTM_VERSION 2 // Change version when hosts need to know -#if HAS_X_AXIS && (HAS_Z_AXIS || HAS_EXTRUDERS) +#if ENABLED(FTM_DYNAMIC_FREQ) #define HAS_DYNAMIC_FREQ 1 #if HAS_Z_AXIS #define HAS_DYNAMIC_FREQ_MM 1 @@ -191,29 +191,20 @@ class FTMotion { return cfg.active ? axis_move_dir[axis] : stepper.last_direction_bits[axis]; } + // A frame of the stepping plan 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]; + + // Add a single set of coordinates in the stepping plan + FORCE_INLINE static void stepping_enqueue(const xyze_float_t traj_coords) { + #define _TOSTEPS_q16(A, B) int64_t(traj_coords.A * planner.settings.axis_steps_per_mm[B] * (1ULL << 16)) + XYZEval next_steps_q48_16 = LOGICAL_AXIS_ARRAY( + _TOSTEPS_q16(e, block_extruder_axis), + _TOSTEPS_q16(x, X_AXIS), _TOSTEPS_q16(y, Y_AXIS), _TOSTEPS_q16(z, Z_AXIS), + _TOSTEPS_q16(i, I_AXIS), _TOSTEPS_q16(j, J_AXIS), _TOSTEPS_q16(k, K_AXIS), + _TOSTEPS_q16(u, U_AXIS), _TOSTEPS_q16(v, V_AXIS), _TOSTEPS_q16(w, W_AXIS) + ); + #undef _TOSTEPS_q16 + stepping.enqueue(next_steps_q48_16); } private: @@ -262,12 +253,7 @@ class FTMotion { 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 diff --git a/Marlin/src/module/ft_motion/resonance_generator.cpp b/Marlin/src/module/ft_motion/resonance_generator.cpp index bfc2f9263d..2c2297e312 100644 --- a/Marlin/src/module/ft_motion/resonance_generator.cpp +++ b/Marlin/src/module/ft_motion/resonance_generator.cpp @@ -53,7 +53,7 @@ void ResonanceGenerator::reset() { void ResonanceGenerator::fill_stepper_plan_buffer() { xyze_float_t traj_coords = {}; - while (!ftMotion.stepper_plan_is_full()) { + while (!ftMotion.stepping.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); @@ -77,9 +77,8 @@ void ResonanceGenerator::fill_stepper_plan_buffer() { #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); + ftMotion.stepping_enqueue(traj_coords); // Increment time for the next point rt_time += FTM_TS; } diff --git a/Marlin/src/module/ft_motion/shaping.h b/Marlin/src/module/ft_motion/shaping.h index 4a62acddcc..113d0fa3ef 100644 --- a/Marlin/src/module/ft_motion/shaping.h +++ b/Marlin/src/module/ft_motion/shaping.h @@ -114,4 +114,9 @@ typedef struct Shaping { // 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])); } + void reset(){ + #define _RESET_ZI(A) ZERO(A.d_zi); + SHAPED_MAP(_RESET_ZI); + zi_idx = 0; + } } shaping_t; diff --git a/Marlin/src/module/ft_motion/smoothing.h b/Marlin/src/module/ft_motion/smoothing.h index ae8c088b30..9d4043c028 100644 --- a/Marlin/src/module/ft_motion/smoothing.h +++ b/Marlin/src/module/ft_motion/smoothing.h @@ -44,4 +44,9 @@ typedef struct Smoothing { // 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 + void reset() { + #define _CLEAR(A) ZERO(A.smoothing_pass); + LOGICAL_AXIS_MAP(_CLEAR); + #undef _CLEAR + } } smoothing_t; diff --git a/Marlin/src/module/ft_motion/stepping.cpp b/Marlin/src/module/ft_motion/stepping.cpp deleted file mode 100644 index f86d07cf7c..0000000000 --- a/Marlin/src/module/ft_motion/stepping.cpp +++ /dev/null @@ -1,115 +0,0 @@ -/** - * 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_LIST_1(1UL << 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 - // 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) 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 (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; - } - - // 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) 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 - - 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 index fc3a5858fd..cacdd5d69a 100644 --- a/Marlin/src/module/ft_motion/stepping.h +++ b/Marlin/src/module/ft_motion/stepping.h @@ -23,31 +23,222 @@ #include "../../inc/MarlinConfig.h" +// +// uint64-free equivalent of: ((uint64_t)a * b) >> 16 +// +FORCE_INLINE constexpr uint32_t a_times_b_shift_16(uint32_t a, uint32_t b) { + uint32_t hi = a >> 16; + uint32_t lo = a & 0xFFFFu; + return (hi * b) + ((lo * b) >> 16); +} +#define FTM_NEVER (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 in a frame +static_assert(FRAME_TICKS < FTM_NEVER, "(STEPPER_TIMER_RATE / FTM_FS) must be < 2^16 (otherwise fixed-point numbers exceed uint16 vars)."); +constexpr uint32_t FTM_Q_INT = 32u - __builtin_clz(FRAME_TICKS + 1); // Bits to represent the max value (duration of a frame, +1 one for FTM_NEVER). + // "clz" counts leading zeroes. +constexpr uint32_t FTM_Q = 16 - FTM_Q_INT; // uint16 interval fractional bits. + // Intervals buffer has fixed point numbers with the point on this position + +// 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 +// E.g number_fp = number << FTM_Q +// number == (number_fp >> FTM_Q) +constexpr uint32_t ONE_FP = 1 << FTM_Q; // Number 1 in fixed point format +constexpr uint32_t FP_FLOOR_MASK = ~(ONE_FP - 1); // Bit mask to do FLOOR in fixed point +constexpr uint32_t FRAME_TICKS_FP = FRAME_TICKS << FTM_Q; // Ticks in a frame in fixed point + typedef struct stepper_plan { AxisBits dir_bits; - xyze_ulong_t advance_dividend_q0_32{0}; - void reset() { advance_dividend_q0_32.reset(); } + xyze_uint_t first_interval_fp; + xyze_uint_t interval_fp; } stepper_plan_t; // Stepping plan handles steps for a whole 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) + // + // ISR part + // + + AxisBits dir_bits; + AxisBits step_bits; + + xyze_ulong_t axis_interval_fp{ LOGICAL_AXIS_LIST_1(FTM_NEVER) }; + xyze_ulong_t ticks_left_per_axis_fp{ LOGICAL_AXIS_LIST_1(FTM_NEVER) }; + uint32_t ticks_left_in_frame_fp = 0; + + // Return how many full ticks we must wait before + // generating the next step pulse. The call is inexpensive: + // - no heap, no locks – pure arithmetic on pre-computed data + FORCE_INLINE uint32_t advance_until_step() { + step_bits = 0; + uint32_t ticks_to_wait_fp = 0; + + for (;;) { + // Smallest remaining tick count among all axes – next step time + const uint32_t ticks_to_next_step_fp = ticks_left_per_axis_fp.small(); + + // Does the frame finish before this next step occurs? + if (ticks_to_next_step_fp > ticks_left_in_frame_fp) { + // Frame ends before next step + if (is_empty()) { + ticks_left_in_frame_fp = 0; + ticks_left_per_axis_fp = FTM_NEVER; + return FTM_NEVER; + } + + // Consume the rest of this frame's time + const uint32_t wait_floor_fp = ticks_left_in_frame_fp & FP_FLOOR_MASK; + ticks_to_wait_fp += wait_floor_fp; + ticks_left_in_frame_fp -= wait_floor_fp; + + // + // Pull the next plan – it already contains: + // - direction bits + // - first_interval_fp (time to the first step) + // - interval_fp (repeating step period) + // + const stepper_plan_t next = dequeue(); + dir_bits = next.dir_bits; + axis_interval_fp = next.interval_fp.asUInt32(); + + // Note the frame will actually end a fraction of a tick in the future, and ticks_left_in_frame_fp still has that fraction. + // Instead of discarding that time, we delay both the end of the next frame, and all first steps by that amount. + ticks_left_per_axis_fp = next.first_interval_fp.asUInt32(); + ticks_left_per_axis_fp += ticks_left_in_frame_fp; + ticks_left_in_frame_fp += FRAME_TICKS_FP; // Start a fresh frame + } + else { + // Step happens before frame end + // Advance to it + const uint32_t wait_floor_fp = ticks_to_next_step_fp & FP_FLOOR_MASK; + ticks_to_wait_fp += wait_floor_fp; + ticks_left_in_frame_fp -= wait_floor_fp; + ticks_left_per_axis_fp -= wait_floor_fp; + + // Build step_bits: any axis whose counter < ONE_FP should step before the next tick, so we tick now + // unless the frame ends earlier. + uint32_t limit_fp = _MIN(ONE_FP - 1, ticks_left_in_frame_fp); + auto _set_step_bit = [&](const AxisEnum A) __attribute__((always_inline)) { + if (ticks_left_per_axis_fp[A] <= limit_fp) { + step_bits[A] = 1; + ticks_left_per_axis_fp[A] += axis_interval_fp[A]; + } + }; + LOGICAL_AXIS_CALL(_set_step_bit); + + return ticks_to_wait_fp >> FTM_Q; // Convert fixed point back to whole ticks + } + } // loop forever + } + + FORCE_INLINE void reset() { + step_bits = 0; + axis_interval_fp = FTM_NEVER; + ticks_left_per_axis_fp = FTM_NEVER; + ticks_left_in_frame_fp = 0; + + stepper_plan_tail = stepper_plan_head = 0; + curr_steps_q48_16.reset(); + } + + // + // Buffering part + // + + 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}; + + FORCE_INLINE void enqueue(XYZEval next_steps_q48_16) { + + stepper_plan_t stepper_plan; + constexpr uint32_t HALF_PHASE_OFFSET = (1UL << 15); // to make steps at .5 crossings instead of integers to center the error + + auto _run_axis = [&](const AxisEnum A) __attribute__((always_inline)) { + // Add half-phase offset to keep step error centred + const int64_t offset_curr_q48_16 = curr_steps_q48_16[A] + HALF_PHASE_OFFSET, + offset_next_q48_16 = next_steps_q48_16[A] + HALF_PHASE_OFFSET; + curr_steps_q48_16[A] = next_steps_q48_16[A]; + + // Determine direction change + const bool new_dir = offset_next_q48_16 >= offset_curr_q48_16; + stepper_plan.dir_bits[A] = new_dir; + + // Δsteps in Q16.16 format – magnitude only + const uint32_t delta_q16_16 = abs(offset_next_q48_16 - offset_curr_q48_16); + + // Current / next phase (fractional part of the position) + uint32_t curr_phase_q1_16 = offset_curr_q48_16 & 0xFFFF, + next_phase_q1_16 = offset_next_q48_16 & 0xFFFF; + if (!new_dir) { + // When going backwards, the phase is 1-phase + curr_phase_q1_16 = (1UL<<16) - curr_phase_q1_16; + next_phase_q1_16 = (1UL<<16) - next_phase_q1_16; + } + // When going, e.g., from 0.6 to 1.0, the delta is not a whole step, + // but the phase overflow indicates a step. + const uint32_t carry = curr_phase_q1_16 > next_phase_q1_16; + + // steps_to_make = integer steps + potential fraction crossing an integer + const uint16_t steps_to_make = (delta_q16_16 >> 16) + carry; + + if (steps_to_make == 0) { // No steps on this axis + stepper_plan.first_interval_fp[A] = FTM_NEVER; + stepper_plan.interval_fp[A] = FTM_NEVER; + return; + } + + // Compute the exact time between steps. + // interval = ticks_per_frame / delta + // current_frame_phase_fp = interval * curr_phase + const uint32_t interval_fp = (FRAME_TICKS_FP << 16) / delta_q16_16, + current_frame_phase_fp = a_times_b_shift_16(interval_fp, curr_phase_q1_16); + uint32_t first_interval_fp = interval_fp - current_frame_phase_fp; + + // The calculation of interval_fp may undershoot its value by a fraction + // due to integer (floor) division. This small fractional error can + // occasionally make a spurious step fit inside this frame. + // To avoid that corner case, the first interval is incremented just enough + // for it to not fit. + const uint32_t tick_of_spurious_step_fp = first_interval_fp + interval_fp * steps_to_make; + if (tick_of_spurious_step_fp <= FRAME_TICKS_FP) { + first_interval_fp += FRAME_TICKS_FP - tick_of_spurious_step_fp + 1; + } + + stepper_plan.first_interval_fp[A] = _MIN(first_interval_fp, FTM_NEVER); + stepper_plan.interval_fp[A] = _MIN(interval_fp, FTM_NEVER); + }; + + LOGICAL_AXIS_CALL(_run_axis); + + // Store the plan into the circular buffer + stepper_plan_buff[stepper_plan_head] = stepper_plan; + 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(); this is ok + FORCE_INLINE stepper_plan_t& dequeue() { + const uint32_t i = stepper_plan_tail; + stepper_plan_tail = (i + 1U) & FTM_BUFFER_MASK; + return stepper_plan_buff[i]; + } + + // + // Simple helper predicates + // + + FORCE_INLINE bool is_busy() { + return !(is_empty() && ticks_left_in_frame_fp == 0); + } + FORCE_INLINE bool is_empty() { + return stepper_plan_head == stepper_plan_tail; + } + FORCE_INLINE bool is_full() { + return ((stepper_plan_head + 1) & FTM_BUFFER_MASK) == stepper_plan_tail; + } } stepping_t; diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 76efc17e4f..060d51c0cc 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -3585,9 +3585,7 @@ void Stepper::report_positions() { */ void Stepper::ftMotion_stepper() { AxisBits &step_bits = ftMotion.stepping.step_bits; // Aliases for prettier code - AxisBits &dir_bits = ftMotion.stepping.stepper_plan.dir_bits; - - if (step_bits.bits == 0) return; + AxisBits &dir_bits = ftMotion.stepping.dir_bits; USING_TIMED_PULSE(); From dd02b5ff0aae40e978782f16280b7f4bc499ae98 Mon Sep 17 00:00:00 2001 From: Andrew <18502096+classicrocker883@users.noreply.github.com> Date: Tue, 2 Dec 2025 16:42:25 -0500 Subject: [PATCH 24/47] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20and=20clean=20up=20s?= =?UTF-8?q?ome=20stuff=20(#28201)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/types.h | 4 ++-- Marlin/src/feature/powerloss.h | 2 ++ Marlin/src/module/endstops.cpp | 18 +++++++++--------- Marlin/src/module/stepper/indirection.h | 8 +++++--- 4 files changed, 18 insertions(+), 14 deletions(-) diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h index 173ab7fbd6..c72f02558f 100644 --- a/Marlin/src/core/types.h +++ b/Marlin/src/core/types.h @@ -816,9 +816,9 @@ struct XYZval { FI XYZval& operator-=(const XYZEval &rs) { NUM_AXIS_CODE(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); return *this; } FI XYZval& operator*=(const XYZEval &rs) { NUM_AXIS_CODE(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); return *this; } FI XYZval& operator/=(const XYZEval &rs) { NUM_AXIS_CODE(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); return *this; } - FI XYZval& operator*=(const float p) { NUM_AXIS_CODE(x *= p, y *= p, z *= p, i *= p, j *= p, k *= p, u *= p, v *= p, w *= p); return *this; } + FI XYZval& operator*=(const float &p) { NUM_AXIS_CODE(x *= p, y *= p, z *= p, i *= p, j *= p, k *= p, u *= p, v *= p, w *= p); return *this; } FI XYZval& operator*=(const int &p) { NUM_AXIS_CODE(x *= p, y *= p, z *= p, i *= p, j *= p, k *= p, u *= p, v *= p, w *= p); return *this; } - FI XYZval& operator/=(const float p) { NUM_AXIS_CODE(x /= p, y /= p, z /= p, i /= p, j /= p, k /= p, u /= p, v /= p, w /= p); return *this; } + FI XYZval& operator/=(const float &p) { NUM_AXIS_CODE(x /= p, y /= p, z /= p, i /= p, j /= p, k /= p, u /= p, v /= p, w /= p); return *this; } FI XYZval& operator>>=(const int &p) { NUM_AXIS_CODE(_RSE(x), _RSE(y), _RSE(z), _RSE(i), _RSE(j), _RSE(k), _RSE(u), _RSE(v), _RSE(w)); return *this; } FI XYZval& operator<<=(const int &p) { NUM_AXIS_CODE(_LSE(x), _LSE(y), _LSE(z), _LSE(i), _LSE(j), _LSE(k), _LSE(u), _LSE(v), _LSE(w)); return *this; } diff --git a/Marlin/src/feature/powerloss.h b/Marlin/src/feature/powerloss.h index 0fcd167d78..bfa5b4717f 100644 --- a/Marlin/src/feature/powerloss.h +++ b/Marlin/src/feature/powerloss.h @@ -201,9 +201,11 @@ class PrintJobRecovery { static void close() { file.close(); } static bool check(); + #if ENABLED(PLR_HEAT_BED_ON_REBOOT) static void set_bed_temp(const bool turn_on); #endif + static void resume(); static void purge(); diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 6528e15a2f..5b7be5d00c 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -984,23 +984,23 @@ void Endstops::update() { void Endstops::clear_endstop_state() { #define _ES_CLEAR(S) CBI(live_state, S##_ENDSTOP); - #define ES_CLEAR(S) TERN_(S##_SPI_SENSORLESS, CBI(live_state, S##_ENDSTOP)); + #define ES_CLEAR(S) TERN_(S##_SPI_SENSORLESS, _ES_CLEAR(S)); ES_CLEAR(X); #if ALL(X_SPI_SENSORLESS, X_DUAL_ENDSTOPS) - CBI(live_state, X2_ENDSTOP); + _ES_CLEAR(X2); #endif ES_CLEAR(Y); #if ALL(Y_SPI_SENSORLESS, Y_DUAL_ENDSTOPS) - CBI(live_state, Y2_ENDSTOP); + _ES_CLEAR(Y2); #endif ES_CLEAR(Z); #if ALL(Z_SPI_SENSORLESS, Z_MULTI_ENDSTOPS) - CBI(live_state, Z2_ENDSTOP); + _ES_CLEAR(Z2); #if NUM_Z_STEPPERS >= 3 - CBI(live_state, Z3_ENDSTOP); + _ES_CLEAR(Z3); #if NUM_Z_STEPPERS >= 4 - CBI(live_state, Z4_ENDSTOP); + _ES_CLEAR(Z4); #endif #endif #endif @@ -1040,9 +1040,9 @@ void Endstops::update() { #define ES_REPORT_CHANGE(S) TERF(USE_##S, _ES_REPORT_CHANGE)(S) if (endstop_change) { - MAP(ES_REPORT_CHANGE, X_MIN, X_MAX, Y_MIN, Y_MAX, Z_MIN, Z_MAX, - , Z_MIN_PROBE, CALIBRATION, - , X2_MIN, X2_MAX, Y2_MIN, Y2_MAX, Z2_MIN, Z2_MAX, Z3_MIN, Z3_MAX, Z4_MIN, Z4_MAX, + MAP(ES_REPORT_CHANGE, X_MIN, X_MAX, Y_MIN, Y_MAX, Z_MIN, Z_MAX + , Z_MIN_PROBE, CALIBRATION + , X2_MIN, X2_MAX, Y2_MIN, Y2_MAX, Z2_MIN, Z2_MAX, Z3_MIN, Z3_MAX, Z4_MIN, Z4_MAX , I_MIN, I_MAX, J_MIN, J_MAX, K_MIN, K_MAX, U_MIN, U_MAX, V_MIN, V_MAX, W_MIN, W_MAX); SERIAL_ECHOLNPGM("\n"); hal.set_pwm_duty(pin_t(LED_PIN), local_LED_status); diff --git a/Marlin/src/module/stepper/indirection.h b/Marlin/src/module/stepper/indirection.h index 05adff7a4e..f2004c88dd 100644 --- a/Marlin/src/module/stepper/indirection.h +++ b/Marlin/src/module/stepper/indirection.h @@ -577,6 +577,7 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset * Extruder indirection for the single E axis */ #if HAS_SWITCHING_EXTRUDER // One stepper driver per two extruders, reversed on odd index + #if EXTRUDERS > 7 #define E_STEP_WRITE(E,V) do{ if (E < 2) { E0_STEP_WRITE(V); } else if (E < 4) { E1_STEP_WRITE(V); } else if (E < 6) { E2_STEP_WRITE(V); } else { E3_STEP_WRITE(V); } }while(0) #define FWD_E_DIR(E) do{ switch (E) { \ @@ -758,15 +759,16 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #elif E_STEPPERS > 2 - #define _E_STEP_WRITE(E,V) do{ switch (E) { case 0: E0_STEP_WRITE(V); break; case 1: E1_STEP_WRITE(V); break; case 2: E2_STEP_WRITE(V); } }while(0) - #define _FWD_E_DIR(E) do{ switch (E) { case 0: E0_DIR_WRITE(HIGH); break; case 1: E1_DIR_WRITE(HIGH); break; case 2: E2_DIR_WRITE(HIGH); } }while(0) - #define _REV_E_DIR(E) do{ switch (E) { case 0: E0_DIR_WRITE(LOW ); break; case 1: E1_DIR_WRITE(LOW ); break; case 2: E2_DIR_WRITE(LOW ); } }while(0) + #define _E_STEP_WRITE(E,V) do{ switch (E) { case 0: E0_STEP_WRITE(V); break; case 1: E1_STEP_WRITE(V); break; case 2: E2_STEP_WRITE(V); break; } }while(0) + #define _FWD_E_DIR(E) do{ switch (E) { case 0: E0_DIR_WRITE(HIGH); break; case 1: E1_DIR_WRITE(HIGH); break; case 2: E2_DIR_WRITE(HIGH); break; } }while(0) + #define _REV_E_DIR(E) do{ switch (E) { case 0: E0_DIR_WRITE(LOW ); break; case 1: E1_DIR_WRITE(LOW ); break; case 2: E2_DIR_WRITE(LOW ); break; } }while(0) #else #define _E_STEP_WRITE(E,V) do{ if (E == 0) { E0_STEP_WRITE(V); } else { E1_STEP_WRITE(V); } }while(0) #define _FWD_E_DIR(E) do{ if (E == 0) { E0_DIR_WRITE(HIGH); } else { E1_DIR_WRITE(HIGH); } }while(0) #define _REV_E_DIR(E) do{ if (E == 0) { E0_DIR_WRITE(LOW ); } else { E1_DIR_WRITE(LOW ); } }while(0) + #endif #if HAS_DUPLICATION_MODE From 291a90ace4c8e40b0a47824af0e9f4829846ad0c Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 2 Dec 2025 16:05:35 -0600 Subject: [PATCH 25/47] =?UTF-8?q?=F0=9F=A9=B9=20Trajectory=20FTM=5FPOLYS?= =?UTF-8?q?=20followup?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to #28197 --- Marlin/src/gcode/feature/ft_motion/M494.cpp | 11 +----- Marlin/src/inc/Conditionals-4-adv.h | 3 -- Marlin/src/lcd/menu/menu_motion.cpp | 20 +++-------- Marlin/src/module/ft_motion.cpp | 39 ++++++++++++++------- Marlin/src/module/ft_motion.h | 16 +++++---- 5 files changed, 41 insertions(+), 48 deletions(-) diff --git a/Marlin/src/gcode/feature/ft_motion/M494.cpp b/Marlin/src/gcode/feature/ft_motion/M494.cpp index a359ab5269..6573716b6d 100644 --- a/Marlin/src/gcode/feature/ft_motion/M494.cpp +++ b/Marlin/src/gcode/feature/ft_motion/M494.cpp @@ -28,18 +28,9 @@ #include "../../../module/stepper.h" #include "../../../module/planner.h" -static FSTR_P get_trajectory_type_name() { - switch (ftMotion.getTrajectoryType()) { - default: - case TrajectoryType::TRAPEZOIDAL: return GET_TEXT_F(MSG_FTM_TRAPEZOIDAL); - case TrajectoryType::POLY5: return GET_TEXT_F(MSG_FTM_POLY5); - case TrajectoryType::POLY6: return GET_TEXT_F(MSG_FTM_POLY6); - } -} - void say_ftm_settings() { #if ENABLED(FTM_POLYS) - SERIAL_ECHOLN(F(" Trajectory: "), get_trajectory_type_name(), C('('), (uint8_t)ftMotion.getTrajectoryType(), C(')')); + SERIAL_ECHOLN(F(" Trajectory: "), ftMotion.getTrajectoryName(), C('('), (uint8_t)ftMotion.getTrajectoryType(), C(')')); #endif const ft_config_t &c = ftMotion.cfg; diff --git a/Marlin/src/inc/Conditionals-4-adv.h b/Marlin/src/inc/Conditionals-4-adv.h index 4dadeecad2..41e2e914f1 100644 --- a/Marlin/src/inc/Conditionals-4-adv.h +++ b/Marlin/src/inc/Conditionals-4-adv.h @@ -1541,9 +1541,6 @@ #if !HAS_EXTRUDERS #undef FTM_SHAPER_E #endif - #if DISABLED(FTM_POLYS) - #define FTM_TRAJECTORY_TYPE TRAPEZOIDAL - #endif #endif // Multi-Stepping Limit diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index 6b14467277..4cc22f6c3b 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -327,18 +327,6 @@ void menu_move() { } } - #if ENABLED(FTM_POLYS) - FSTR_P get_trajectory_name() { - switch (ftMotion.getTrajectoryType()) { - default: - case TrajectoryType::TRAPEZOIDAL: return GET_TEXT_F(MSG_FTM_TRAPEZOIDAL); - case TrajectoryType::POLY5: return GET_TEXT_F(MSG_FTM_POLY5); - case TrajectoryType::POLY6: return GET_TEXT_F(MSG_FTM_POLY6); - - } - } - #endif // FTM_POLYS - #if HAS_DYNAMIC_FREQ FSTR_P get_dyn_freq_mode_name() { switch (ftMotion.cfg.dynFreqMode) { @@ -494,7 +482,7 @@ void menu_move() { auto _traj_name = [&]{ if (TERN1(CACHE_FOR_SPEED, !got_t)) { TERN_(CACHE_FOR_SPEED, got_t = true); - traj_name = get_trajectory_name(); + traj_name = ftMotion.getTrajectoryName(); } return traj_name; }; @@ -504,7 +492,7 @@ void menu_move() { auto _dmode = []{ return get_dyn_freq_mode_name(); }; #endif #if ENABLED(FTM_POLYS) - auto _traj_name = []{ return get_trajectory_name(); }; + auto _traj_name = []{ return ftMotion.getTrajectoryName(); }; #endif #endif @@ -598,7 +586,7 @@ void menu_move() { auto _traj_name = [&]{ if (TERN1(CACHE_FOR_SPEED, !got_t)) { TERN_(CACHE_FOR_SPEED, got_t = true); - traj_name = get_trajectory_name(); + traj_name = ftMotion.getTrajectoryName(); } return traj_name; }; @@ -611,7 +599,7 @@ void menu_move() { auto _dmode = []{ return get_dyn_freq_mode_name(); }; #endif #if ENABLED(FTM_POLYS) - auto _traj_name = []{ return get_trajectory_name(); }; + auto _traj_name = []{ return ftMotion.getTrajectoryName(); }; #endif #endif // !__AVR__ diff --git a/Marlin/src/module/ft_motion.cpp b/Marlin/src/module/ft_motion.cpp index 30c16077c0..2310b111ed 100644 --- a/Marlin/src/module/ft_motion.cpp +++ b/Marlin/src/module/ft_motion.cpp @@ -74,11 +74,11 @@ float FTMotion::tau = 0.0f; // (s) Time since start of b // Trajectory generators TrapezoidalTrajectoryGenerator FTMotion::trapezoidalGenerator; #if ENABLED(FTM_POLYS) + TrajectoryType FTMotion::trajectoryType = TrajectoryType::FTM_TRAJECTORY_TYPE; Poly5TrajectoryGenerator FTMotion::poly5Generator; Poly6TrajectoryGenerator FTMotion::poly6Generator; + TrajectoryGenerator* FTMotion::currentGenerator = &FTMotion::trapezoidalGenerator; #endif -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 @@ -288,20 +288,33 @@ void FTMotion::plan_runout_block() { void FTMotion::init() { update_shaping_params(); TERN_(FTM_SMOOTHING, update_smoothing_params()); - setTrajectoryType(cfg.trajectory_type); + TERN_(FTM_POLYS, setTrajectoryType(cfg.trajectory_type)); reset(); // Precautionary. } -// Set trajectory generator type -void FTMotion::setTrajectoryType(const TrajectoryType type) { - cfg.trajectory_type = trajectoryType = type; - switch (type) { - default: cfg.trajectory_type = trajectoryType = TrajectoryType::FTM_TRAJECTORY_TYPE; - case TrajectoryType::TRAPEZOIDAL: currentGenerator = &trapezoidalGenerator; break; - #if ENABLED(FTM_POLYS) - case TrajectoryType::POLY5: currentGenerator = &poly5Generator; break; - case TrajectoryType::POLY6: currentGenerator = &poly6Generator; break; - #endif +#if ENABLED(FTM_POLYS) + + // Set trajectory generator type + void FTMotion::setTrajectoryType(const TrajectoryType type) { + cfg.trajectory_type = trajectoryType = type; + switch (type) { + default: + case TrajectoryType::TRAPEZOIDAL: currentGenerator = &trapezoidalGenerator; break; + #if ENABLED(FTM_POLYS) + case TrajectoryType::POLY5: currentGenerator = &poly5Generator; break; + case TrajectoryType::POLY6: currentGenerator = &poly6Generator; break; + #endif + } + } + +#endif // FTM_POLYS + +FSTR_P FTMotion::getTrajectoryName() { + switch (getTrajectoryType()) { + default: + case TrajectoryType::TRAPEZOIDAL: return GET_TEXT_F(MSG_FTM_TRAPEZOIDAL); + case TrajectoryType::POLY5: return GET_TEXT_F(MSG_FTM_POLY5); + case TrajectoryType::POLY6: return GET_TEXT_F(MSG_FTM_POLY6); } } diff --git a/Marlin/src/module/ft_motion.h b/Marlin/src/module/ft_motion.h index 9e78195264..60f3a67b9a 100644 --- a/Marlin/src/module/ft_motion.h +++ b/Marlin/src/module/ft_motion.h @@ -84,9 +84,11 @@ typedef struct FTConfig { ft_smoothed_float_t smoothingTime; // Smoothing time. [s] #endif - TrajectoryType trajectory_type = TrajectoryType::FTM_TRAJECTORY_TYPE; // Trajectory generator type #if ENABLED(FTM_POLYS) float poly6_acceleration_overshoot; // Overshoot factor for Poly6 (1.25 to 2.0) + TrajectoryType trajectory_type = TrajectoryType::FTM_TRAJECTORY_TYPE; // Trajectory generator type + #else + static constexpr TrajectoryType trajectory_type = TrajectoryType::TRAPEZOIDAL; #endif } ft_config_t; @@ -140,10 +142,9 @@ class FTMotion { #if ENABLED(FTM_POLYS) cfg.poly6_acceleration_overshoot = FTM_POLY6_ACCELERATION_OVERSHOOT; + setTrajectoryType(TrajectoryType::FTM_TRAJECTORY_TYPE); #endif - setTrajectoryType(TrajectoryType::FTM_TRAJECTORY_TYPE); - reset(); } @@ -182,7 +183,8 @@ class FTMotion { // Trajectory generator selection static void setTrajectoryType(const TrajectoryType type); - static TrajectoryType getTrajectoryType() { return trajectoryType; } + static TrajectoryType getTrajectoryType() { return TERN(FTM_POLYS, trajectoryType, TrajectoryType::TRAPEZOIDAL); } + static FSTR_P getTrajectoryName(); FORCE_INLINE static bool axis_is_moving(const AxisEnum axis) { return cfg.active ? moving_axis_flags[axis] : stepper.axis_is_moving(axis); @@ -219,9 +221,11 @@ class FTMotion { #if ENABLED(FTM_POLYS) static Poly5TrajectoryGenerator poly5Generator; static Poly6TrajectoryGenerator poly6Generator; + static TrajectoryType trajectoryType; + static TrajectoryGenerator* currentGenerator; + #else + static constexpr TrajectoryGenerator *currentGenerator = trapezoidalGenerator; #endif - static TrajectoryGenerator* currentGenerator; - static TrajectoryType trajectoryType; #if FTM_HAS_LIN_ADVANCE static bool use_advance_lead; From 3ee18bc6676e00e31aec06246d7982bcd70b46a6 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 2 Dec 2025 16:10:49 -0600 Subject: [PATCH 26/47] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20FT=20?= =?UTF-8?q?Motion=20accessors,=20G-code=20style?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/calibrate/G28.cpp | 7 +- Marlin/src/gcode/feature/ft_motion/M493.cpp | 88 ++++++++++----------- Marlin/src/gcode/feature/ft_motion/M494.cpp | 24 +++--- Marlin/src/lcd/menu/menu_motion.cpp | 7 +- Marlin/src/module/ft_motion.cpp | 4 +- Marlin/src/module/ft_motion.h | 14 ++++ 6 files changed, 79 insertions(+), 65 deletions(-) diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index 20b50cd7f1..4d3d7841e7 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -129,15 +129,14 @@ #if ENABLED(Z_SAFE_HOMING) inline void home_z_safely() { - - // Potentially disable Fixed-Time Motion for homing - TERN_(FT_MOTION, FTM_DISABLE_IN_SCOPE()); - DEBUG_SECTION(log_G28, "home_z_safely", DEBUGGING(LEVELING)); // Disallow Z homing if X or Y homing is needed if (homing_needed_error(_BV(X_AXIS) | _BV(Y_AXIS))) return; + // Potentially disable Fixed-Time Motion for homing + TERN_(FT_MOTION, FTM_DISABLE_IN_SCOPE()); + sync_plan_position(); /** diff --git a/Marlin/src/gcode/feature/ft_motion/M493.cpp b/Marlin/src/gcode/feature/ft_motion/M493.cpp index 6696ae64af..e3f4bea8cb 100644 --- a/Marlin/src/gcode/feature/ft_motion/M493.cpp +++ b/Marlin/src/gcode/feature/ft_motion/M493.cpp @@ -208,12 +208,14 @@ void GcodeSuite::M493() { if (!parser.seen_any()) flag.report = true; + ft_config_t &c = ftMotion.cfg; + // Parse 'S' mode parameter. if (parser.seen('S')) { const bool active = parser.value_bool(); - if (active != ftMotion.cfg.active) { + if (active != c.active) { stepper.ftMotion_syncPosition(); - ftMotion.cfg.active = active; + c.active = active; flag.report = true; } } @@ -228,8 +230,8 @@ void GcodeSuite::M493() { return; } auto set_shaper = [&](const AxisEnum axis, ftMotionShaper_t newsh) { - if (newsh != ftMotion.cfg.shaper[axis]) { - ftMotion.cfg.shaper[axis] = newsh; + if (newsh != c.shaper[axis]) { + c.shaper[axis] = newsh; flag.update = flag.report = true; } }; @@ -243,8 +245,8 @@ void GcodeSuite::M493() { // 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; + if (enabled != c.axis_sync_enabled) { + c.axis_sync_enabled = enabled; flag.report = true; } } @@ -263,7 +265,7 @@ void GcodeSuite::M493() { case dynFreqMode_MASS_BASED: #endif case dynFreqMode_DISABLED: - ftMotion.cfg.dynFreqMode = val; + c.dynFreqMode = val; flag.report = true; break; default: @@ -271,22 +273,18 @@ void GcodeSuite::M493() { break; } } - else { - SERIAL_ECHOLNPGM("?Wrong shaper for (D)ynamic Frequency Mode ", ftMotion.cfg.dynFreqMode, "."); - } + else + SERIAL_ECHOLNPGM("?Shaper required for (D)ynamic Frequency Mode ", c.dynFreqMode, "."); } - const bool modeUsesDynFreq = ( - TERN0(HAS_DYNAMIC_FREQ_MM, ftMotion.cfg.dynFreqMode == dynFreqMode_Z_BASED) - || TERN0(HAS_DYNAMIC_FREQ_G, ftMotion.cfg.dynFreqMode == dynFreqMode_MASS_BASED) - ); + const bool modeUsesDynFreq = c.modeUsesDynFreq(); #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); + const bool goodBaseFreq = seenA && c.goodBaseFreq(baseFreqVal); if (seenA && !goodBaseFreq) SERIAL_ECHOLN(F("?Invalid "), F("(A) Base Frequency value. ("), int(FTM_MIN_SHAPE_FREQ), C('-'), int((FTM_FS) / 2), C(')')); @@ -301,14 +299,14 @@ void GcodeSuite::M493() { // 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); + const bool goodZeta = seenI && c.goodZeta(zetaVal); if (seenI && !goodZeta) 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); + const bool goodVtol = seenQ && c.goodVtol(vtolVal); if (seenQ && !goodVtol) SERIAL_ECHOLN(F("?Invalid "), F("(Q) Vibration Tolerance value. (0.0-1.0)")); // VTol out of range @@ -323,18 +321,18 @@ void GcodeSuite::M493() { 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; + c.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."); + 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; + c.dynFreqK.x = baseDynFreqVal; flag.report = true; } #endif @@ -343,24 +341,24 @@ void GcodeSuite::M493() { if (seenI) { if (AXIS_IS_SHAPING(X)) { if (goodZeta) { - ftMotion.cfg.zeta.x = zetaVal; + c.zeta.x = zetaVal; flag.update = true; } } else - SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_A_NAME), " zeta parameter."); + SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_A_NAME), " (I) zeta parameter."); } // Parse X vtol parameter if (seenQ) { if (AXIS_IS_EISHAPING(X)) { if (goodVtol) { - ftMotion.cfg.vtol.x = vtolVal; + c.vtol.x = vtolVal; flag.update = true; } } else - SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_A_NAME), " vtol parameter."); + SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_A_NAME), " (Q) vtol parameter."); } } @@ -374,18 +372,18 @@ void GcodeSuite::M493() { if (seenA) { if (AXIS_IS_SHAPING(Y)) { if (goodBaseFreq) { - ftMotion.cfg.baseFreq.y = baseFreqVal; + c.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."); + 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; + c.dynFreqK.y = baseDynFreqVal; flag.report = true; } #endif @@ -394,24 +392,24 @@ void GcodeSuite::M493() { if (seenI) { if (AXIS_IS_SHAPING(Y)) { if (goodZeta) { - ftMotion.cfg.zeta.y = zetaVal; + c.zeta.y = zetaVal; flag.update = true; } } else - SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_B_NAME), " zeta parameter."); + SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_B_NAME), " (I) zeta parameter."); } // Parse Y vtol parameter if (seenQ) { if (AXIS_IS_EISHAPING(Y)) { if (goodVtol) { - ftMotion.cfg.vtol.y = vtolVal; + c.vtol.y = vtolVal; flag.update = true; } } else - SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_B_NAME), " vtol parameter."); + SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_B_NAME), " (Q) vtol parameter."); } } @@ -425,18 +423,18 @@ void GcodeSuite::M493() { if (seenA) { if (AXIS_IS_SHAPING(Z)) { if (goodBaseFreq) { - ftMotion.cfg.baseFreq.z = baseFreqVal; + c.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."); + 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; + c.dynFreqK.z = baseDynFreqVal; flag.report = true; } #endif @@ -445,24 +443,24 @@ void GcodeSuite::M493() { if (seenI) { if (AXIS_IS_SHAPING(Z)) { if (goodZeta) { - ftMotion.cfg.zeta.z = zetaVal; + c.zeta.z = zetaVal; flag.update = true; } } else - SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_C_NAME), " zeta parameter."); + SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_C_NAME), " (I) zeta parameter."); } // Parse Z vtol parameter if (seenQ) { if (AXIS_IS_EISHAPING(Z)) { if (goodVtol) { - ftMotion.cfg.vtol.z = vtolVal; + c.vtol.z = vtolVal; flag.update = true; } } else - SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_C_NAME), " vtol parameter."); + SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_C_NAME), " (Q) vtol parameter."); } } @@ -476,18 +474,18 @@ void GcodeSuite::M493() { if (seenA) { if (AXIS_IS_SHAPING(E)) { if (goodBaseFreq) { - ftMotion.cfg.baseFreq.e = baseFreqVal; + c.baseFreq.e = baseFreqVal; flag.update = flag.report = true; } } else // Mode doesn't use frequency. - SERIAL_ECHOLNPGM("?Wrong mode for ", C('E'), " [A] 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; + c.dynFreqK.e = baseDynFreqVal; flag.report = true; } #endif @@ -496,24 +494,24 @@ void GcodeSuite::M493() { if (seenI) { if (AXIS_IS_SHAPING(E)) { if (goodZeta) { - ftMotion.cfg.zeta.e = zetaVal; + c.zeta.e = zetaVal; flag.update = true; } } else - SERIAL_ECHOLNPGM("?Wrong mode for ", C('E'), " zeta parameter."); + SERIAL_ECHOLNPGM("?Wrong mode for ", C('E'), " (I) zeta parameter."); } // Parse E vtol parameter if (seenQ) { if (AXIS_IS_EISHAPING(E)) { if (goodVtol) { - ftMotion.cfg.vtol.e = vtolVal; + c.vtol.e = vtolVal; flag.update = true; } } else - SERIAL_ECHOLNPGM("?Wrong mode for ", C('E'), " vtol parameter."); + SERIAL_ECHOLNPGM("?Wrong mode for ", C('E'), " (Q) vtol parameter."); } } diff --git a/Marlin/src/gcode/feature/ft_motion/M494.cpp b/Marlin/src/gcode/feature/ft_motion/M494.cpp index 6573716b6d..26d2b7d2b8 100644 --- a/Marlin/src/gcode/feature/ft_motion/M494.cpp +++ b/Marlin/src/gcode/feature/ft_motion/M494.cpp @@ -55,19 +55,18 @@ void GcodeSuite::M494_report(const bool forReplay/*=true*/) { SERIAL_ECHOPGM(" M494 T", (uint8_t)ftMotion.getTrajectoryType()); #if ENABLED(FTM_SMOOTHING) - SERIAL_ECHOPGM( - CARTES_PAIRED_LIST( - " X", c.smoothingTime.X, " Y", c.smoothingTime.Y, - " Z", c.smoothingTime.Z, " E", c.smoothingTime.E - ) - ); - #endif // FTM_SMOOTHING + SERIAL_ECHOPGM(CARTES_PAIRED_LIST( + " X", c.smoothingTime.X, + " Y", c.smoothingTime.Y, + " Z", c.smoothingTime.Z, + " E", c.smoothingTime.E + )); + #endif #if ENABLED(FTM_POLYS) - if (ftMotion.getTrajectoryType() == TrajectoryType::POLY6) SERIAL_ECHOPGM(" O", c.poly6_acceleration_overshoot); - #endif // FTM_POLYS + #endif SERIAL_EOL(); } @@ -97,8 +96,9 @@ void GcodeSuite::M494() { report = true; } else - SERIAL_ECHOLN(F("?Invalid "), F("trajectory type [T] value. Use 0=TRAPEZOIDAL, 1=POLY5, 2=POLY6")); + SERIAL_ECHOLN(F("?Invalid "), F("(T)rajectory type value. Use 0=TRAPEZOIDAL, 1=POLY5, 2=POLY6")); } + // Parse overshoot parameter. if (parser.seenval('O')) { const float val = parser.value_float(); @@ -107,7 +107,7 @@ void GcodeSuite::M494() { report = true; } else - SERIAL_ECHOLN(F("?Invalid "), F("overshoot [O] value. Range 1.25-1.875")); + SERIAL_ECHOLN(F("?Invalid "), F("(O)vershoot value. Range 1.25-1.875")); } #endif // FTM_POLYS @@ -122,7 +122,7 @@ void GcodeSuite::M494() { report = true; \ } \ else \ - SERIAL_ECHOLNPGM("?Invalid ", C(N), " smoothing time [", C(CHARIFY(A)), "] value."); \ + SERIAL_ECHOLNPGM("?Invalid ", C(N), " smoothing time (", C(CHARIFY(A)), ") value."); \ } CARTES_GANG( diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index 4cc22f6c3b..8f644361f4 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -542,6 +542,7 @@ void menu_move() { } // menu_ft_motion void menu_tune_ft_motion() { + // Define stuff ahead of the menu loop ft_config_t &c = ftMotion.cfg; @@ -551,10 +552,10 @@ void menu_move() { // For U8G paged rendering check and skip extra string copy #if HAS_X_AXIS - MString<20> shaper_name; #if CACHE_FOR_SPEED int8_t prev_a = -1; #endif + MString<20> shaper_name; auto _shaper_name = [&](const AxisEnum a) { if (TERN1(CACHE_FOR_SPEED, a != prev_a)) { TERN_(CACHE_FOR_SPEED, prev_a = a); @@ -565,10 +566,10 @@ void menu_move() { #endif #if HAS_DYNAMIC_FREQ - MString<20> dmode; #if CACHE_FOR_SPEED bool got_d = false; #endif + MString<20> dmode; auto _dmode = [&]{ if (TERN1(CACHE_FOR_SPEED, !got_d)) { TERN_(CACHE_FOR_SPEED, got_d = true); @@ -579,10 +580,10 @@ void menu_move() { #endif #if ENABLED(FTM_POLYS) - MString<20> traj_name; #if CACHE_FOR_SPEED bool got_t = false; #endif + MString<20> traj_name; auto _traj_name = [&]{ if (TERN1(CACHE_FOR_SPEED, !got_t)) { TERN_(CACHE_FOR_SPEED, got_t = true); diff --git a/Marlin/src/module/ft_motion.cpp b/Marlin/src/module/ft_motion.cpp index 2310b111ed..d402439c04 100644 --- a/Marlin/src/module/ft_motion.cpp +++ b/Marlin/src/module/ft_motion.cpp @@ -81,7 +81,9 @@ TrapezoidalTrajectoryGenerator FTMotion::trapezoidalGenerator; #endif // Resonance Test -TERN_(FTM_RESONANCE_TEST,ResonanceGenerator FTMotion::rtg;) // Resonance trajectory generator instance +#if ENABLED(FTM_RESONANCE_TEST) + ResonanceGenerator FTMotion::rtg; // Resonance trajectory generator instance +#endif #if FTM_HAS_LIN_ADVANCE bool FTMotion::use_advance_lead; diff --git a/Marlin/src/module/ft_motion.h b/Marlin/src/module/ft_motion.h index 60f3a67b9a..497c04e474 100644 --- a/Marlin/src/module/ft_motion.h +++ b/Marlin/src/module/ft_motion.h @@ -90,6 +90,20 @@ typedef struct FTConfig { #else static constexpr TrajectoryType trajectory_type = TrajectoryType::TRAPEZOIDAL; #endif + + #if HAS_FTM_SHAPING + constexpr bool goodZeta(const float z) { return WITHIN(z, 0.01f, 1.0f); } + constexpr bool goodVtol(const float v) { return WITHIN(v, 0.00f, 1.0f); } + #if HAS_DYNAMIC_FREQ + bool modeUsesDynFreq() const { + return (TERN0(HAS_DYNAMIC_FREQ_MM, dynFreqMode == dynFreqMode_Z_BASED) + || TERN0(HAS_DYNAMIC_FREQ_G, dynFreqMode == dynFreqMode_MASS_BASED)); + } + #endif + #endif // HAS_FTM_SHAPING + + constexpr bool goodBaseFreq(const float f) { return WITHIN(f, FTM_MIN_SHAPE_FREQ, (FTM_FS) / 2); } + } ft_config_t; /** From a6d8c6d5b09c56dffd8a3d131b77ac47a205b8e2 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 3 Dec 2025 00:32:57 +0000 Subject: [PATCH 27/47] [cron] Bump distribution date (2025-12-03) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 545d23b782..cedc4fd8d1 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-02" +//#define STRING_DISTRIBUTION_DATE "2025-12-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 2c8d257744..fb8a209572 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-02" + #define STRING_DISTRIBUTION_DATE "2025-12-03" #endif /** From 09e943a10c90c7bd8074e3ec5b69f96ac0535397 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 3 Dec 2025 00:21:49 -0600 Subject: [PATCH 28/47] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20durat?= =?UTF-8?q?ion=5Ft::remainingEstimate?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/libs/duration_t.h | 23 +++++++++++++++++++++++ 1 file changed, 23 insertions(+) diff --git a/Marlin/src/libs/duration_t.h b/Marlin/src/libs/duration_t.h index d648924dc9..acfbf0d7a8 100644 --- a/Marlin/src/libs/duration_t.h +++ b/Marlin/src/libs/duration_t.h @@ -211,5 +211,28 @@ struct duration_t { } } + /** + * @brief Get the estimated remaining time + * @details Use the given start time and sdpos values to estimate the + * remaining time (as reckoned from this duration_t value). + * Should be superseded by 'M73 R' (SET_REMAINING_TIME). + * This estimate is rendered meaningless by M808, but reset start_time for per-object estimates. + * The UI should consider a "start_sdpos" of 0 to be unset and show "---" + * + * @param start_time The time to consider the "real" start of the print. Saved time of the first E move with X and/or Y. + * @param start_sdpos The sdpos of the first printing move (E move with X and/or Y). + * @param end_sdpos The sdpos of the end of the print (before cooldown). + * @param sdpos The current sdpos of the print job. + */ + uint32_t remainingEstimate(const uint32_t start_time, const uint32_t start_sdpos, const uint32_t end_sdpos, const uint32_t sdpos) const { + const float elapsed_data = float(sdpos - start_sdpos), // Ex: 460b - 280b = 180b + total_data = float(end_sdpos - start_sdpos), // Ex: 1000b - 280b = 720b + sd_percent = elapsed_data / total_data, // Ex: 180b / 720b = 0.25 + sd_ratio = (1.0f - sd_percent) / sd_percent; // Ex: (1.0 - 0.25) / 0.25 = 3.0 + + const uint32_t elapsed_time = value - start_time; // Ex: T2 - T1 = 300s + return uint32_t(elapsed_time * sd_ratio); // Ex: 300s * 3.0f = 900s + } + #pragma GCC diagnostic pop }; From 92da094c9f60590da4533b4ae97e31db76006650 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 3 Dec 2025 16:57:26 -0600 Subject: [PATCH 29/47] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Edito?= =?UTF-8?q?rconfig=20for=20contributed=20HAL/DUE/usb?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/DUE/usb/.editorconfig | 5 +++++ 1 file changed, 5 insertions(+) create mode 100644 Marlin/src/HAL/DUE/usb/.editorconfig diff --git a/Marlin/src/HAL/DUE/usb/.editorconfig b/Marlin/src/HAL/DUE/usb/.editorconfig new file mode 100644 index 0000000000..f2c26de5ee --- /dev/null +++ b/Marlin/src/HAL/DUE/usb/.editorconfig @@ -0,0 +1,5 @@ +# editorconfig.org + +[{*.c,*.cpp,*.h}] +indent_style = tab +indent_size = 4 From 4cb827b51e3f4317f52741f685102864dea42ae6 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 3 Dec 2025 18:10:23 -0600 Subject: [PATCH 30/47] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Edito?= =?UTF-8?q?rconfig=20for=20contributed=20lib-uhs3?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/sd/usb_flashdrive/lib-uhs3/.editorconfig | 5 +++++ 1 file changed, 5 insertions(+) create mode 100644 Marlin/src/sd/usb_flashdrive/lib-uhs3/.editorconfig diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs3/.editorconfig b/Marlin/src/sd/usb_flashdrive/lib-uhs3/.editorconfig new file mode 100644 index 0000000000..36ad080de0 --- /dev/null +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs3/.editorconfig @@ -0,0 +1,5 @@ +# editorconfig.org + +[{*.c,*.cpp,*.h}] +indent_style = space +indent_size = 8 From 938d3db36f954d492152eb21dcb45ee2bb4ed584 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 3 Dec 2025 18:03:39 -0600 Subject: [PATCH 31/47] =?UTF-8?q?=F0=9F=8E=A8=20PSTR()=20=3D>=20F()?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/extui/mks_ui/draw_z_offset_wizard.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/lcd/extui/mks_ui/draw_z_offset_wizard.cpp b/Marlin/src/lcd/extui/mks_ui/draw_z_offset_wizard.cpp index 2ad9816e01..7f4f12b930 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_z_offset_wizard.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_z_offset_wizard.cpp @@ -111,7 +111,7 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { // On cancel the Z position needs correction #if HOMING_Z_WITH_PROBE && defined(PROBE_OFFSET_WIZARD_START_Z) set_axis_never_homed(Z_AXIS); - queue.inject_P(PSTR("G28Z")); + queue.inject(F("G28Z")); #else do_z_post_clearance(); #endif @@ -151,7 +151,7 @@ void lv_draw_z_offset_wizard() { set_bed_leveling_enabled(mks_leveling_was_active); #endif - queue.inject_P(PSTR("G28")); + queue.inject(F("G28")); z_offset_ref = 0; // Set Z Value for Wizard Position to 0 calculated_z_offset = probe.offset.z + current_position.z - z_offset_ref; From d23ac65dd4f0c3f68615980e3c59d499c57bc56f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 3 Dec 2025 16:22:33 -0600 Subject: [PATCH 32/47] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Controller=20Fan=20S?= =?UTF-8?q?oft=20PWM=20speed?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-Authored-By: wrathernaut <97267123+wrathernaut@users.noreply.github.com> --- Marlin/src/feature/controllerfan.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/feature/controllerfan.cpp b/Marlin/src/feature/controllerfan.cpp index 243f0606ce..0636402136 100644 --- a/Marlin/src/feature/controllerfan.cpp +++ b/Marlin/src/feature/controllerfan.cpp @@ -134,7 +134,7 @@ void ControllerFan::update() { } while (0) #if ENABLED(FAN_SOFT_PWM) - soft_pwm_speed = speed; + soft_pwm_speed = speed >> 1; // Controller Fan Soft PWM uses 0-127 as 0-100% so cut the 0-255 range in half. #else SET_CONTROLLER_FAN(); #if PIN_EXISTS(CONTROLLER_FAN2) From e819ba832e06c5eb3bdcdba8375f384aa6597228 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 4 Dec 2025 00:35:26 +0000 Subject: [PATCH 33/47] [cron] Bump distribution date (2025-12-04) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index cedc4fd8d1..78b982decf 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-03" +//#define STRING_DISTRIBUTION_DATE "2025-12-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 fb8a209572..7ca426c5a9 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-03" + #define STRING_DISTRIBUTION_DATE "2025-12-04" #endif /** From e42059f34a1a7d6be7f54416abb3ff91ff0f7569 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 3 Dec 2025 20:02:09 -0600 Subject: [PATCH 34/47] =?UTF-8?q?=F0=9F=8E=A8=20Misc.=20cleanup=20Dec=204?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/RP2040/HAL_MinSerial.cpp | 18 +++++++++--------- Marlin/src/HAL/SAMD21/timers.h | 3 +-- Marlin/src/MarlinCore.cpp | 14 +++++++------- Marlin/src/MarlinCore.h | 6 +++--- Marlin/src/gcode/control/M999.cpp | 2 +- .../generic/change_filament_screen.cpp | 2 +- .../generic/status_screen.cpp | 2 +- .../lcd/extui/ia_creality/FileNavigator.cpp | 4 ++-- Marlin/src/lcd/extui/mks_ui/draw_printing.cpp | 4 ++-- Marlin/src/lcd/extui/mks_ui/draw_ui.cpp | 2 +- Marlin/src/lcd/extui/ui_api.cpp | 2 +- Marlin/src/lcd/sovol_rts/sovol_rts.cpp | 10 ++++++---- Marlin/src/lcd/tft/tft_image.h | 2 +- Marlin/src/module/ft_motion/shaping.h | 10 +++++----- Marlin/src/module/motion.cpp | 16 ++++++++-------- Marlin/src/module/settings.cpp | 2 +- Marlin/src/module/temperature.cpp | 4 ++-- Marlin/src/module/tool_change.cpp | 2 +- Marlin/src/sd/cardreader.cpp | 6 +++--- 19 files changed, 56 insertions(+), 55 deletions(-) diff --git a/Marlin/src/HAL/RP2040/HAL_MinSerial.cpp b/Marlin/src/HAL/RP2040/HAL_MinSerial.cpp index d829edff24..dc332053bc 100644 --- a/Marlin/src/HAL/RP2040/HAL_MinSerial.cpp +++ b/Marlin/src/HAL/RP2040/HAL_MinSerial.cpp @@ -44,15 +44,15 @@ static void TXBegin() { #endif } -static void TX(char b){ - #if SERIAL_PORT == -1 - USBSerial - #elif SERIAL_PORT == 0 - USBSerial - #elif SERIAL_PORT == 1 - Serial1 - #endif - .write(b); +static void TX(char b) { + #if SERIAL_PORT == -1 + USBSerial + #elif SERIAL_PORT == 0 + USBSerial + #elif SERIAL_PORT == 1 + Serial1 + #endif + .write(b); } // A SW memory barrier, to ensure GCC does not overoptimize loops diff --git a/Marlin/src/HAL/SAMD21/timers.h b/Marlin/src/HAL/SAMD21/timers.h index c558b89791..b3c53e7416 100644 --- a/Marlin/src/HAL/SAMD21/timers.h +++ b/Marlin/src/HAL/SAMD21/timers.h @@ -143,9 +143,8 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { Rtc * const rtc = timer_config[timer_num].pRtc; // Clear interrupt flag rtc->MODE0.INTFLAG.reg = RTC_MODE0_INTFLAG_CMP0| RTC_MODE0_INTFLAG_OVF; - } - else if (timer_config[timer_num].type == TimerType::tcc){ + else if (timer_config[timer_num].type == TimerType::tcc) { Tcc * const tc = timer_config[timer_num].pTcc; // Clear interrupt flag tc->INTFLAG.reg = TCC_INTFLAG_OVF; diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index c5ceb15943..5b44b5c7b9 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -282,7 +282,7 @@ Marlin marlin; #endif // Global state of the firmware -MarlinState Marlin::state = MarlinState::MF_INITIALIZING; +MarlinState Marlin::state = MF_INITIALIZING; // For M109 and M190, this flag may be cleared (by M108) to exit the wait loop bool Marlin::wait_for_heatup = false; @@ -404,8 +404,8 @@ void Marlin::startOrResumeJob() { } inline void finishSDPrinting() { - if (queue.enqueue_one(F("M1001"))) { // Keep trying until it gets queued - marlin.setState(MarlinState::MF_RUNNING); // Signal to stop trying + if (queue.enqueue_one(F("M1001"))) { // Keep trying until it gets queued + marlin.setState(MF_RUNNING); // Signal to stop trying TERN_(PASSWORD_AFTER_SD_PRINT_END, password.lock_machine()); TERN_(DGUS_LCD_UI_MKS, screen.sdPrintingFinished()); } @@ -803,7 +803,7 @@ void Marlin::idle(const bool no_stepper_sleep/*=false*/) { TERN_(MAX7219_DEBUG, max7219.idle_tasks()); // Return if setup() isn't completed - if (state == MarlinState::MF_INITIALIZING) goto IDLE_DONE; + if (is(MF_INITIALIZING)) goto IDLE_DONE; // TODO: Still causing errors TERN_(TOOL_SENSOR, (void)check_tool_sensor_stats(active_extruder, true)); @@ -996,7 +996,7 @@ void Marlin::stop() { SERIAL_ERROR_MSG(STR_ERR_STOPPED); LCD_MESSAGE(MSG_STOPPED); safe_delay(350); // Allow enough time for messages to get out before stopping - state = MarlinState::MF_STOPPED; + setState(MF_STOPPED); } } // Marlin::stop() @@ -1709,7 +1709,7 @@ void setup() { SETUP_RUN(ftMotion.init()); #endif - marlin.setState(MarlinState::MF_RUNNING); + marlin.setState(MF_RUNNING); #ifdef STARTUP_TUNE // Play a short startup tune before continuing. @@ -1741,7 +1741,7 @@ void loop() { #if HAS_MEDIA if (card.flag.abort_sd_printing) abortSDPrinting(); - if (marlin.is(MarlinState::MF_SD_COMPLETE)) finishSDPrinting(); + if (marlin.is(MF_SD_COMPLETE)) finishSDPrinting(); #endif queue.advance(); diff --git a/Marlin/src/MarlinCore.h b/Marlin/src/MarlinCore.h index cfc5eeca80..35482983ec 100644 --- a/Marlin/src/MarlinCore.h +++ b/Marlin/src/MarlinCore.h @@ -28,7 +28,7 @@ #include // Global State of the firmware -enum class MarlinState : uint8_t { +enum MarlinState : uint8_t { MF_INITIALIZING = 0, MF_STOPPED, MF_KILLED, @@ -54,8 +54,8 @@ public: static MarlinState state; static void setState(const MarlinState s) { state = s; } static bool is(const MarlinState s) { return state == s; } - static bool isStopped() { return is(MarlinState::MF_STOPPED); } - static bool isRunning() { return state >= MarlinState::MF_RUNNING; } + static bool isStopped() { return is(MF_STOPPED); } + static bool isRunning() { return state >= MF_RUNNING; } static bool printingIsActive(); static bool printJobOngoing(); diff --git a/Marlin/src/gcode/control/M999.cpp b/Marlin/src/gcode/control/M999.cpp index e1408a576a..863ab8eb90 100644 --- a/Marlin/src/gcode/control/M999.cpp +++ b/Marlin/src/gcode/control/M999.cpp @@ -36,7 +36,7 @@ * existing command buffer. */ void GcodeSuite::M999() { - marlin.setState(MarlinState::MF_RUNNING); + marlin.setState(MF_RUNNING); ui.reset_alert_level(); if (parser.boolval('S')) return; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.cpp index 8c687ce05d..9163a63ce1 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.cpp @@ -190,7 +190,7 @@ void ChangeFilamentScreen::onRedraw(draw_mode_t what) { .text(TEXT_POS(E0_TEMP_POS), e0_str) .colors(normal_btn); - if DISABLED(HAS_MULTI_HOTEND) { + if (DISABLED(HAS_MULTI_HOTEND)) { cmd.font(font_small).cmd(COLOR_RGB(gray_color_1)); } else if (getTargetTemp_celsius(H1) > 0) { diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.cpp index 7b9e8f9f34..19a015404c 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.cpp @@ -220,7 +220,7 @@ void StatusScreen::draw_temperature(draw_mode_t what) { } cmd.tag(5).font(font_medium).button(TEXT_POS(FAN_POS), fan_str); - if DISABLED(HAS_MULTI_HOTEND) { + if (DISABLED(HAS_MULTI_HOTEND)) { cmd.font(font_xsmall).fgcolor(gray_color_1); } else if (getTargetTemp_celsius(H1) > 0) { diff --git a/Marlin/src/lcd/extui/ia_creality/FileNavigator.cpp b/Marlin/src/lcd/extui/ia_creality/FileNavigator.cpp index 3254da3a37..df6019f4f8 100644 --- a/Marlin/src/lcd/extui/ia_creality/FileNavigator.cpp +++ b/Marlin/src/lcd/extui/ia_creality/FileNavigator.cpp @@ -60,12 +60,12 @@ void FileNavigator::reset() { void FileNavigator::refresh() { filelist.refresh(); } -bool FileNavigator::getIndexisDir(uint16_t index){ +bool FileNavigator::getIndexisDir(uint16_t index) { filelist.seek(index); return filelist.isDir(); } -const char *FileNavigator::getIndexName(uint16_t index){ +const char *FileNavigator::getIndexName(uint16_t index) { filelist.seek(index); return filelist.shortFilename(); } diff --git a/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp b/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp index 0027ee6194..b8eb84244b 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp @@ -294,7 +294,7 @@ void setProBarRate() { lv_label_set_text(bar1ValueText, public_buf_l); lv_obj_align(bar1ValueText, bar1, LV_ALIGN_CENTER, 0, 0); - if (marlin.is(MarlinState::MF_SD_COMPLETE)) { + if (marlin.is(MF_SD_COMPLETE)) { if (once_flag == 0) { stop_print_time(); @@ -309,7 +309,7 @@ void setProBarRate() { if (gCfgItems.finish_power_off) { gcode.process_subcommands_now(F("M1001")); queue.inject(F("M81")); - marlin.setState(MarlinState::MF_RUNNING); + marlin.setState(MF_RUNNING); } #endif } diff --git a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp index 8f91279e8c..45ec98cefd 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp @@ -757,7 +757,7 @@ void GUI_RefreshPage() { disp_print_time(); disp_fan_Zpos(); } - if (printing_rate_update_flag || marlin.is(MarlinState::MF_SD_COMPLETE)) { + if (printing_rate_update_flag || marlin.is(MF_SD_COMPLETE)) { printing_rate_update_flag = false; if (!gcode_preview_over) setProBarRate(); } diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index 2f96d08c10..608e632854 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -1112,7 +1112,7 @@ namespace ExtUI { void onSurviveInKilled() { thermalManager.disable_all_heaters(); flags.printer_killed = 0; - marlin.setState(MarlinState::MF_RUNNING); + marlin.setState(MF_RUNNING); //SERIAL_ECHOLNPGM("survived at: ", millis()); } diff --git a/Marlin/src/lcd/sovol_rts/sovol_rts.cpp b/Marlin/src/lcd/sovol_rts/sovol_rts.cpp index b79d9541a8..82a80bdd4a 100644 --- a/Marlin/src/lcd/sovol_rts/sovol_rts.cpp +++ b/Marlin/src/lcd/sovol_rts/sovol_rts.cpp @@ -1624,15 +1624,17 @@ void RTS::onIdle() { TERN_(HAS_Z_AXIS, sendData(current_position.z * 10.0f, AXIS_Z_COORD_VP)); #if HAS_HOTEND - if (last_target_temperature[0] != thermalManager.degTargetHotend(0)) + if (last_target_temperature[0] != thermalManager.degTargetHotend(0)) { last_target_temperature[0] = thermalManager.degTargetHotend(0); - updateTempE0(); + updateTempE0(); + } #endif #if HAS_HEATED_BED - if (last_target_temperature_bed != thermalManager.degTargetBed()) + if (last_target_temperature_bed != thermalManager.degTargetBed()) { last_target_temperature_bed = thermalManager.degTargetBed(); - updateTempBed(); + updateTempBed(); + } #endif #if HAS_HOTEND diff --git a/Marlin/src/lcd/tft/tft_image.h b/Marlin/src/lcd/tft/tft_image.h index e1f078a90b..44be2564fb 100644 --- a/Marlin/src/lcd/tft/tft_image.h +++ b/Marlin/src/lcd/tft/tft_image.h @@ -32,7 +32,7 @@ #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) { (void *)custom_bootscreen_##W##x##H##x16, W, H, HIGHCOLOR } #define CUSTOM_BOOTSCREEN_CHOSEN(W,H) _CUSTOM_BOOTSCREEN_CHOSEN(W,H) #endif #endif diff --git a/Marlin/src/module/ft_motion/shaping.h b/Marlin/src/module/ft_motion/shaping.h index 113d0fa3ef..5b37c2930d 100644 --- a/Marlin/src/module/ft_motion/shaping.h +++ b/Marlin/src/module/ft_motion/shaping.h @@ -114,9 +114,9 @@ typedef struct Shaping { // 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])); } - void reset(){ - #define _RESET_ZI(A) ZERO(A.d_zi); - SHAPED_MAP(_RESET_ZI); - zi_idx = 0; - } + void reset() { + #define _RESET_ZI(A) ZERO(A.d_zi); + SHAPED_MAP(_RESET_ZI); + zi_idx = 0; + } } shaping_t; diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index bbf4f59bd7..37d9188863 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -625,14 +625,14 @@ void report_current_position_projected() { */ M_StateEnum grbl_state_for_marlin_state() { switch (marlin.state) { - case MarlinState::MF_INITIALIZING: return M_INIT; - case MarlinState::MF_SD_COMPLETE: return M_ALARM; - case MarlinState::MF_WAITING: return M_IDLE; - case MarlinState::MF_STOPPED: return M_END; - case MarlinState::MF_RUNNING: return M_RUNNING; - case MarlinState::MF_PAUSED: return M_HOLD; - case MarlinState::MF_KILLED: return M_ERROR; - default: return M_IDLE; + case MF_INITIALIZING: return M_INIT; + case MF_SD_COMPLETE: return M_ALARM; + case MF_WAITING: return M_IDLE; + case MF_STOPPED: return M_END; + case MF_RUNNING: return M_RUNNING; + case MF_PAUSED: return M_HOLD; + case MF_KILLED: return M_ERROR; + default: return M_IDLE; } } diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 4a3b01c2ed..e7ce0204c7 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -2230,7 +2230,7 @@ void MarlinSettings::postprocess() { #if ENABLED(PTC_PROBE) EEPROM_READ(ptc.z_offsets_probe); #endif - # if ENABLED(PTC_BED) + #if ENABLED(PTC_BED) EEPROM_READ(ptc.z_offsets_bed); #endif #if ENABLED(PTC_HOTEND) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 7d009c1c46..83deaa6694 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -1556,7 +1556,7 @@ int16_t Temperature::getHeaterPower(const heater_id_t heater_id) { * @param heater_id: The heater that caused the error */ inline void loud_kill(FSTR_P const lcd_msg, const heater_id_t heater_id) { - marlin.setState(MarlinState::MF_KILLED); + marlin.setState(MF_KILLED); thermalManager.disable_all_heaters(); #if HAS_BEEPER for (uint8_t i = 20; i--;) { @@ -2310,7 +2310,7 @@ void Temperature::mintemp_error(const heater_id_t heater_id OPTARG(ERR_INCLUDE_T * - Update the heated bed PID output value */ void Temperature::task() { - if (marlin.is(MarlinState::MF_INITIALIZING)) return hal.watchdog_refresh(); // If Marlin isn't started, at least reset the watchdog! + if (marlin.is(MF_INITIALIZING)) return hal.watchdog_refresh(); // If Marlin isn't started, at least reset the watchdog! static bool no_reentry = false; // Prevent recursion if (no_reentry) return; diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index ab5e7fd5a7..e13d75d5c4 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -924,7 +924,7 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. * Returns TRUE if too cold to move (also echos message: STR_ERR_HOTEND_TOO_COLD) * Returns FALSE if able to move. */ - bool too_cold(uint8_t toolID){ + bool too_cold(uint8_t toolID) { if (!DEBUGGING(DRYRUN) && thermalManager.targetTooColdToExtrude(toolID)) { SERIAL_ECHO_MSG(STR_ERR_HOTEND_TOO_COLD); return true; diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index b5b89d4848..1fb12f44a2 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -504,7 +504,7 @@ void CardReader::mount() { cdroot(); else { #if ANY(HAS_SD_DETECT, HAS_USB_FLASH_DRIVE) - if (!marlin.is(MarlinState::MF_INITIALIZING)) { + if (!marlin.is(MF_INITIALIZING)) { if (isSDCardSelected()) LCD_ALERTMESSAGE(MSG_MEDIA_INIT_FAIL_SD); else if (isFlashDriveSelected()) @@ -1650,8 +1650,8 @@ void CardReader::fileHasFinished() { endFilePrintNow(TERN_(SD_RESORT, true)); - flag.sdprintdone = true; // Stop getting bytes from the SD card - marlin.setState(MarlinState::MF_SD_COMPLETE); // Tell Marlin to enqueue M1001 soon + flag.sdprintdone = true; // Stop getting bytes from the SD card + marlin.setState(MF_SD_COMPLETE); // Tell Marlin to enqueue M1001 soon } #if ENABLED(AUTO_REPORT_SD_STATUS) From 54f26e61dc5a130195ac595f8e7265344a421fbd Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 5 Dec 2025 00:33:49 +0000 Subject: [PATCH 35/47] [cron] Bump distribution date (2025-12-05) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 78b982decf..d83252ddc7 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-04" +//#define STRING_DISTRIBUTION_DATE "2025-12-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 7ca426c5a9..46fd6b39f7 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-04" + #define STRING_DISTRIBUTION_DATE "2025-12-05" #endif /** From 5f9205ef8fd43d8540aa835c91bb34d95311ef34 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 4 Dec 2025 15:55:59 -0600 Subject: [PATCH 36/47] =?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 --- Marlin/Configuration_adv.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 272d1a09e7..e5dd8f155b 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -4214,7 +4214,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. + //#define BUTTON1_IMMEDIATE // Skip the queue and execute immediately. Rarely needed. #endif //#define BUTTON2_PIN -1 From a995cbef501c75a1547094f02f28189fe4200982 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 4 Dec 2025 13:10:03 -0600 Subject: [PATCH 37/47] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Secon?= =?UTF-8?q?ds=20units?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/libs/stopwatch.cpp | 10 +++++----- Marlin/src/libs/stopwatch.h | 10 +++++----- Marlin/src/module/printcounter.cpp | 19 +++++++++---------- Marlin/src/module/printcounter.h | 10 +++++----- 4 files changed, 24 insertions(+), 25 deletions(-) diff --git a/Marlin/src/libs/stopwatch.cpp b/Marlin/src/libs/stopwatch.cpp index 4178807951..8790c2b3db 100644 --- a/Marlin/src/libs/stopwatch.cpp +++ b/Marlin/src/libs/stopwatch.cpp @@ -29,9 +29,9 @@ #endif Stopwatch::State Stopwatch::state; -millis_t Stopwatch::accumulator; -millis_t Stopwatch::startTimestamp; -millis_t Stopwatch::stopTimestamp; +uint32_t Stopwatch::accumulator; +uint32_t Stopwatch::startTimestamp; +uint32_t Stopwatch::stopTimestamp; bool Stopwatch::stop() { debug(F("stop")); @@ -73,7 +73,7 @@ bool Stopwatch::start() { else return false; } -void Stopwatch::resume(const millis_t with_time) { +void Stopwatch::resume(const uint32_t with_time) { debug(F("resume")); reset(); @@ -89,7 +89,7 @@ void Stopwatch::reset() { accumulator = 0; } -millis_t Stopwatch::duration() { +uint32_t Stopwatch::duration() { return accumulator + MS_TO_SEC((isRunning() ? millis() : stopTimestamp) - startTimestamp); } diff --git a/Marlin/src/libs/stopwatch.h b/Marlin/src/libs/stopwatch.h index 829d510050..13fa3de4b4 100644 --- a/Marlin/src/libs/stopwatch.h +++ b/Marlin/src/libs/stopwatch.h @@ -36,9 +36,9 @@ class Stopwatch { enum State : char { STOPPED, RUNNING, PAUSED }; static Stopwatch::State state; - static millis_t accumulator; - static millis_t startTimestamp; - static millis_t stopTimestamp; + static uint32_t accumulator; // (seconds) + static uint32_t startTimestamp; + static uint32_t stopTimestamp; public: /** @@ -75,7 +75,7 @@ class Stopwatch { * @brief Resume the stopwatch * @details Resume a timer from a given duration */ - static void resume(const millis_t with_time); + static void resume(const uint32_t with_time); /** * @brief Reset the stopwatch @@ -102,7 +102,7 @@ class Stopwatch { * @details Return the total number of seconds the timer has been running. * @return the delta since starting the stopwatch */ - static millis_t duration(); + static uint32_t duration(); #ifdef DEBUG_STOPWATCH diff --git a/Marlin/src/module/printcounter.cpp b/Marlin/src/module/printcounter.cpp index ec5bd8c456..89e3716543 100644 --- a/Marlin/src/module/printcounter.cpp +++ b/Marlin/src/module/printcounter.cpp @@ -69,12 +69,12 @@ printStatistics PrintCounter::data; const PrintCounter::eeprom_address_t PrintCounter::address = STATS_EEPROM_ADDRESS; -millis_t PrintCounter::lastDuration; +uint32_t PrintCounter::lastDuration; bool PrintCounter::loaded = false; -millis_t PrintCounter::deltaDuration() { +uint32_t PrintCounter::deltaDuration() { TERN_(DEBUG_PRINTCOUNTER, debug(PSTR("deltaDuration"))); - millis_t tmp = lastDuration; + const uint32_t tmp = lastDuration; lastDuration = duration(); return lastDuration - tmp; } @@ -236,25 +236,24 @@ void PrintCounter::showStats() { void PrintCounter::tick() { if (!isRunning()) return; - millis_t now = millis(); - + const millis_t now = millis(); static millis_t update_next; // = 0 if (ELAPSED(now, update_next)) { update_next = now + updateInterval; TERN_(DEBUG_PRINTCOUNTER, debug(PSTR("tick"))); - millis_t delta = deltaDuration(); - data.printTime += delta; + const uint32_t delta_s = deltaDuration(); + data.printTime += delta_s; #if SERVICE_INTERVAL_1 > 0 - data.nextService1 -= _MIN(delta, data.nextService1); + data.nextService1 -= _MIN(delta_s, data.nextService1); #endif #if SERVICE_INTERVAL_2 > 0 - data.nextService2 -= _MIN(delta, data.nextService2); + data.nextService2 -= _MIN(delta_s, data.nextService2); #endif #if SERVICE_INTERVAL_3 > 0 - data.nextService3 -= _MIN(delta, data.nextService3); + data.nextService3 -= _MIN(delta_s, data.nextService3); #endif } diff --git a/Marlin/src/module/printcounter.h b/Marlin/src/module/printcounter.h index ebf61a3a1c..dd8d6fbf62 100644 --- a/Marlin/src/module/printcounter.h +++ b/Marlin/src/module/printcounter.h @@ -35,13 +35,13 @@ struct printStatistics { // 16 bytes //const uint8_t magic; // Magic header, it will always be 0x16 uint16_t totalPrints; // Number of prints uint16_t finishedPrints; // Number of complete prints - uint32_t printTime; // Accumulated printing time - uint32_t longestPrint; // Longest successful print job + uint32_t printTime; // (s) Accumulated printing time + uint32_t longestPrint; // (s) Longest successful print job #if HAS_EXTRUDERS float filamentUsed; // Accumulated filament consumed in mm #endif #if SERVICE_INTERVAL_1 > 0 - uint32_t nextService1; // Service intervals (or placeholders) + uint32_t nextService1; // (s) Service intervals (or placeholders) #endif #if SERVICE_INTERVAL_2 > 0 uint32_t nextService2; @@ -86,7 +86,7 @@ class PrintCounter: public Stopwatch { * @details Store the timestamp of the last deltaDuration(), this is * required due to the updateInterval cycle. */ - static millis_t lastDuration; + static uint32_t lastDuration; /** * @brief Stats were loaded from EEPROM @@ -102,7 +102,7 @@ class PrintCounter: public Stopwatch { * used internally for print statistics accounting is not intended to be a * user callable function. */ - static millis_t deltaDuration(); + static uint32_t deltaDuration(); public: From 98875d424f6b05954a50e7dcc78fa0c3a7a4d88f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 4 Dec 2025 19:18:51 -0600 Subject: [PATCH 38/47] =?UTF-8?q?=F0=9F=9A=B8=20Show=20estimated=20remaini?= =?UTF-8?q?ng=20time?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../lcd/dogm/status_screen_lite_ST7920.cpp | 2 +- Marlin/src/lcd/e3v2/jyersui/dwin.cpp | 12 ++--- Marlin/src/lcd/e3v2/jyersui/dwin.h | 2 +- Marlin/src/lcd/e3v2/proui/dwin.cpp | 49 ++++++++++--------- Marlin/src/lcd/extui/mks_ui/draw_printing.cpp | 2 +- 5 files changed, 35 insertions(+), 32 deletions(-) diff --git a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp index af0330402c..ac7941f844 100644 --- a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp +++ b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp @@ -693,7 +693,7 @@ bool ST7920_Lite_Status_Screen::indicators_changed() { #if ENABLED(SHOW_REMAINING_TIME) void MarlinUI::drawRemain() { lightUI.drawRemain(); } void ST7920_Lite_Status_Screen::drawRemain() { - const duration_t remaint = TERN0(SET_REMAINING_TIME, ui.get_remaining_time()); + const duration_t remaint = ui.get_remaining_time(); if (marlin.printJobOngoing() && remaint.value) { draw_progress_string(PPOS, prepare_time_string(remaint, 'R')); } diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp index 1ddd54904d..2cede088ec 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -685,7 +685,7 @@ void JyersDWIN::drawPrintScreen() { updateStatusBar(true); drawPrintProgressBar(); drawPrintProgressElapsed(); - TERN_(SET_REMAINING_TIME, drawPrintProgressRemain()); + TERN_(SHOW_REMAINING_TIME, drawPrintProgressRemain()); drawPrintFilename(true); } @@ -711,10 +711,10 @@ void JyersDWIN::drawPrintProgressBar() { dwinDrawString(false, DWIN_FONT_MENU, getColor(eeprom_settings.progress_percent, COLOR_PERCENT), COLOR_BG_BLACK, 133, 133, F("%")); } -#if ENABLED(SET_REMAINING_TIME) +#if ENABLED(SHOW_REMAINING_TIME) void JyersDWIN::drawPrintProgressRemain() { - uint16_t remainingtime = ui.get_remaining_time(); + const uint16_t remainingtime = ui.get_remaining_time(); dwinDrawIntValue(true, true, 1, DWIN_FONT_MENU, getColor(eeprom_settings.progress_time, COLOR_WHITE), COLOR_BG_BLACK, 2, 176, 187, remainingtime / 3600); dwinDrawIntValue(true, true, 1, DWIN_FONT_MENU, getColor(eeprom_settings.progress_time, COLOR_WHITE), COLOR_BG_BLACK, 2, 200, 187, (remainingtime % 3600) / 60); if (eeprom_settings.time_format_textual) { @@ -4890,7 +4890,7 @@ void JyersDWIN::startPrint(const bool sd) { else strcpy_P(filename, PSTR("Host Print")); TERN_(SET_PROGRESS_PERCENT, ui.set_progress(0)); - TERN_(SET_REMAINING_TIME, ui.set_remaining_time(0)); + TERN_(SET_REMAINING_TIME, ui.reset_remaining_time()); drawPrintScreen(); } } @@ -4900,7 +4900,7 @@ void JyersDWIN::stopPrint() { sdprint = false; thermalManager.cooldown(); TERN_(SET_PROGRESS_PERCENT, ui.set_progress(100 * (PROGRESS_SCALE))); - TERN_(SET_REMAINING_TIME, ui.set_remaining_time(0)); + TERN_(SET_REMAINING_TIME, ui.reset_remaining_time()); drawPrintConfirm(); } @@ -4977,7 +4977,7 @@ void JyersDWIN::screenUpdate() { if (process == Proc_Print) { drawPrintProgressBar(); drawPrintProgressElapsed(); - TERN_(SET_REMAINING_TIME, drawPrintProgressRemain()); + TERN_(SHOW_REMAINING_TIME, drawPrintProgressRemain()); } } diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.h b/Marlin/src/lcd/e3v2/jyersui/dwin.h index 067516b2fd..890cc79999 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.h +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.h @@ -192,7 +192,7 @@ public: static void drawPrintScreen(); static void drawPrintFilename(const bool reset=false); static void drawPrintProgressBar(); - #if ENABLED(SET_REMAINING_TIME) + #if ENABLED(SHOW_REMAINING_TIME) static void drawPrintProgressRemain(); #endif static void drawPrintProgressElapsed(); diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index baf95d942f..ae94ee0025 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -573,7 +573,7 @@ void drawPrintProgressBar() { void drawPrintProgressElapsed() { MString<12> buf; - duration_t elapsed = print_job_timer.duration(); // Print timer + const duration_t elapsed = print_job_timer.duration(); // Print timer buf.setf(F("%02i:%02i "), uint16_t(elapsed.value / 3600), (uint16_t(elapsed.value) % 3600) / 60); DWINUI::drawString(hmiData.colorText, hmiData.colorBackground, 47, 192, buf); } @@ -1355,39 +1355,42 @@ void eachMomentUpdate() { if (ELAPSED(ms, next_rts_update_ms)) { next_rts_update_ms = ms + DWIN_UPDATE_INTERVAL; - if ((isPrinting() != hmiFlag.printing_flag) && !hmiFlag.home_flag) { - hmiFlag.printing_flag = isPrinting(); - if (hmiFlag.printing_flag) - dwinPrintStarted(); - else if (hmiFlag.abort_flag) - dwinPrintAborted(); - else - dwinPrintFinished(); - } - - if ((hmiFlag.pause_flag != marlin.printingIsPaused()) && !hmiFlag.home_flag) { - hmiFlag.pause_flag = marlin.printingIsPaused(); - if (hmiFlag.pause_flag) - dwinPrintPause(); - else if (hmiFlag.abort_flag) - dwinPrintAborted(); - else - dwinPrintResume(); + if (!hmiFlag.home_flag) { + if (hmiFlag.printing_flag != isPrinting()) { + hmiFlag.printing_flag = isPrinting(); + if (hmiFlag.printing_flag) + dwinPrintStarted(); + else if (hmiFlag.abort_flag) + dwinPrintAborted(); + else + dwinPrintFinished(); + } + if (hmiFlag.pause_flag != marlin.printingIsPaused()) { + hmiFlag.pause_flag = marlin.printingIsPaused(); + if (hmiFlag.pause_flag) + dwinPrintPause(); + else if (hmiFlag.abort_flag) + dwinPrintAborted(); + else + dwinPrintResume(); + } } if (checkkey == ID_PrintProcess) { // Print process // Progress percent static uint8_t _percent_done = 255; - if (_percent_done != ui.get_progress_percent()) { - _percent_done = ui.get_progress_percent(); + const uint8_t pp = ui.get_progress_percent(); + if (_percent_done != pp) { + _percent_done = pp; drawPrintProgressBar(); } // Remaining time #if ENABLED(SHOW_REMAINING_TIME) - if (_remain_time != ui.get_remaining_time()) { - _remain_time = ui.get_remaining_time(); + const uint32_t rt = ui.get_remaining_time(); + if (_remain_time != rt) { + _remain_time = rt; drawPrintProgressRemain(); } #endif diff --git a/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp b/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp index b8eb84244b..5c13eeaa01 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_printing.cpp @@ -244,7 +244,7 @@ void disp_fan_speed() { } void disp_print_time() { - #if ENABLED(SET_REMAINING_TIME) + #if ENABLED(SHOW_REMAINING_TIME) const uint32_t r = ui.get_remaining_time(); sprintf_P(public_buf_l, PSTR("%02d:%02d R"), r / 3600, (r % 3600) / 60); #else From f139ffed7599fa4eb084b3d298b67a0044142c2f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 4 Dec 2025 19:18:55 -0600 Subject: [PATCH 39/47] =?UTF-8?q?=E2=9C=A8=20REMAINING=5FTIME=5FPRIME?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 8 ++++ Marlin/src/gcode/stats/M75-M78.cpp | 13 +++++++ Marlin/src/gcode/temp/M104_M109.cpp | 10 ++++- Marlin/src/gcode/temp/M140_M190.cpp | 7 ++++ Marlin/src/lcd/marlinui.h | 10 +++-- Marlin/src/lcd/tft/ui_color_ui.cpp | 16 ++------ Marlin/src/libs/duration_t.h | 23 ------------ Marlin/src/libs/stopwatch.cpp | 6 +++ Marlin/src/libs/stopwatch.h | 57 +++++++++++++++++++++++++++++ buildroot/tests/STM32F103RE | 3 +- 10 files changed, 113 insertions(+), 40 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index e5dd8f155b..1f56d184fc 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1799,6 +1799,14 @@ #define PE_LEDS_COMPLETED_TIME (30*60) // (seconds) Time to keep the LED "done" color before restoring normal illumination #endif + /** + * Priming for the Remaining Time estimate + * Long processes at the start of a G-code file can skew the Remaining Time estimate. + * Enable these options to start this estimation at a later point in the G-code file. + */ + //#define REMAINING_TIME_PRIME // Provide G-code 'M75 R' to prime the Remaining Time estimate + //#define REMAINING_TIME_AUTOPRIME // Prime the Remaining Time estimate later (e.g., at the end of 'M109') + /** * Continue after Power-Loss (Creality3D) * diff --git a/Marlin/src/gcode/stats/M75-M78.cpp b/Marlin/src/gcode/stats/M75-M78.cpp index b5daa8809c..8c7378c977 100644 --- a/Marlin/src/gcode/stats/M75-M78.cpp +++ b/Marlin/src/gcode/stats/M75-M78.cpp @@ -38,9 +38,22 @@ * * ProUI: If the print fails to start and any text is * included in the command, print it in the header. + * + * With REMAINING_TIME_PRIME: + * + * 'M75 R' : Prime Remaining Time Estimate with the current job time and SD file position and return. + * */ void GcodeSuite::M75() { + #if ENABLED(REMAINING_TIME_PRIME) + if (parser.seen_test('R')) { + print_job_timer.primeRemainingTimeEstimate(card.getIndex(), card.getFileSize()); + return; + } + #endif + marlin.startOrResumeJob(); // ... ExtUI::onPrintTimerStarted() + #if ENABLED(DWIN_LCD_PROUI) // TODO: Remove if M75 is never used if (!card.isStillPrinting()) dwinPrintHeader(parser.has_string() ? parser.string_arg : GET_TEXT(MSG_HOST_START_PRINT)); diff --git a/Marlin/src/gcode/temp/M104_M109.cpp b/Marlin/src/gcode/temp/M104_M109.cpp index badc8b7fe7..d27ff75d39 100644 --- a/Marlin/src/gcode/temp/M104_M109.cpp +++ b/Marlin/src/gcode/temp/M104_M109.cpp @@ -130,8 +130,16 @@ void GcodeSuite::M104_M109(const bool isM109) { TERN_(AUTOTEMP, thermalManager.autotemp_M104_M109()); - if (isM109 && got_temp) + if (isM109 && got_temp) { (void)thermalManager.wait_for_hotend(target_extruder, no_wait_for_cooling); + #if ENABLED(REMAINING_TIME_AUTOPRIME) + if (card.isStillPrinting()) { + print_job_timer.primeRemainingTimeEstimate(card.getIndex(), card.getFileSize()); + //SERIAL_ECHOLN(F("M109 - Prime Remaining Time Estimate: "), print_job_timer.duration(), C(' '), card.getIndex(), C(' '), card.getFileSize() - card.getIndex()); + } + #endif + } + } #if ENABLED(AUTOTEMP) diff --git a/Marlin/src/gcode/temp/M140_M190.cpp b/Marlin/src/gcode/temp/M140_M190.cpp index 7d2de2084a..f153be4ab5 100644 --- a/Marlin/src/gcode/temp/M140_M190.cpp +++ b/Marlin/src/gcode/temp/M140_M190.cpp @@ -121,6 +121,13 @@ void GcodeSuite::M140_M190(const bool isM190) { #endif thermalManager.wait_for_bed(no_wait_for_cooling); + + #if ENABLED(REMAINING_TIME_AUTOPRIME) + if (card.isStillPrinting()) { + print_job_timer.primeRemainingTimeEstimate(card.getIndex(), card.getFileSize()); + //SERIAL_ECHOLN(F("M190 - Prime Remaining Time Estimate: "), print_job_timer.duration(), C(' '), card.getIndex(), C(' '), card.getFileSize() - card.getIndex()); + } + #endif } else { ui.set_status_reset_fn([]{ diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index 85d05887e3..94a333629a 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -328,9 +328,13 @@ public: #endif #if ANY(SHOW_REMAINING_TIME, SET_PROGRESS_MANUALLY) static uint32_t _calculated_remaining_time() { - const duration_t elapsed = print_job_timer.duration(); - const progress_t progress = _get_progress(); - return progress ? elapsed.value * (100 * (PROGRESS_SCALE) - progress) / progress : 0; + #if ANY(REMAINING_TIME_PRIME, REMAINING_TIME_AUTOPRIME) + return print_job_timer.remainingTimeEstimate(card.getIndex()); + #else + const uint32_t elapsed = print_job_timer.duration(); + const progress_t progress = _get_progress(); + return progress ? elapsed * (100U * (PROGRESS_SCALE) - progress) / progress : 0; + #endif } #if ENABLED(SET_REMAINING_TIME) static uint32_t remaining_time; diff --git a/Marlin/src/lcd/tft/ui_color_ui.cpp b/Marlin/src/lcd/tft/ui_color_ui.cpp index a81ff3ccc6..53b3b0d068 100644 --- a/Marlin/src/lcd/tft/ui_color_ui.cpp +++ b/Marlin/src/lcd/tft/ui_color_ui.cpp @@ -346,8 +346,6 @@ void MarlinUI::draw_status_screen() { duration_t elapsed = print_job_timer.duration(); #endif - const progress_t progress = TERN(HAS_PRINT_PROGRESS_PERMYRIAD, get_progress_permyriad, get_progress_percent)(); - #if ENABLED(SHOW_ELAPSED_TIME) elapsed.toDigital(buffer); tft.canvas(ELAPSED_TIME_X, ELAPSED_TIME_Y, ELAPSED_TIME_W, ELAPSED_TIME_H); @@ -360,15 +358,8 @@ void MarlinUI::draw_status_screen() { #endif #if ENABLED(SHOW_REMAINING_TIME) - // Get the estimate, first from M73 - uint32_t estimate_remaining = (0 - #if ALL(SET_PROGRESS_MANUALLY, SET_REMAINING_TIME) - + get_remaining_time() - #endif - ); - // If no M73 estimate is available but we have progress data, calculate time remaining assuming time elapsed is linear with progress - if (!estimate_remaining && progress > 0) - estimate_remaining = elapsed.value * (100 * (PROGRESS_SCALE) - progress) / progress; + // Get a Remaining Time estimate from M73 R, a primed calculation, or percent/time calculation + const uint32_t estimate_remaining = get_remaining_time(); // Generate estimate string if (!estimate_remaining) @@ -387,13 +378,14 @@ void MarlinUI::draw_status_screen() { tft.add_image(REMAINING_TIME_IMAGE_X, REMAINING_TIME_IMAGE_Y, imgTimeRemaining, color); #endif tft.add_text(REMAINING_TIME_TEXT_X, REMAINING_TIME_TEXT_Y, color, tft_string); - #endif + #endif // SHOW_REMAINING_TIME // Progress bar // TODO: print percentage text for SHOW_PROGRESS_PERCENT tft.canvas(PROGRESS_BAR_X, PROGRESS_BAR_Y, PROGRESS_BAR_W, PROGRESS_BAR_H); tft.set_background(COLOR_PROGRESS_BG); tft.add_rectangle(0, 0, PROGRESS_BAR_W, PROGRESS_BAR_H, COLOR_PROGRESS_FRAME); + const progress_t progress = TERN(HAS_PRINT_PROGRESS_PERMYRIAD, get_progress_permyriad, get_progress_percent)(); if (progress) tft.add_bar(1, 1, ((PROGRESS_BAR_W - 2) * progress / (PROGRESS_SCALE)) / 100, 7, COLOR_PROGRESS_BAR); diff --git a/Marlin/src/libs/duration_t.h b/Marlin/src/libs/duration_t.h index acfbf0d7a8..d648924dc9 100644 --- a/Marlin/src/libs/duration_t.h +++ b/Marlin/src/libs/duration_t.h @@ -211,28 +211,5 @@ struct duration_t { } } - /** - * @brief Get the estimated remaining time - * @details Use the given start time and sdpos values to estimate the - * remaining time (as reckoned from this duration_t value). - * Should be superseded by 'M73 R' (SET_REMAINING_TIME). - * This estimate is rendered meaningless by M808, but reset start_time for per-object estimates. - * The UI should consider a "start_sdpos" of 0 to be unset and show "---" - * - * @param start_time The time to consider the "real" start of the print. Saved time of the first E move with X and/or Y. - * @param start_sdpos The sdpos of the first printing move (E move with X and/or Y). - * @param end_sdpos The sdpos of the end of the print (before cooldown). - * @param sdpos The current sdpos of the print job. - */ - uint32_t remainingEstimate(const uint32_t start_time, const uint32_t start_sdpos, const uint32_t end_sdpos, const uint32_t sdpos) const { - const float elapsed_data = float(sdpos - start_sdpos), // Ex: 460b - 280b = 180b - total_data = float(end_sdpos - start_sdpos), // Ex: 1000b - 280b = 720b - sd_percent = elapsed_data / total_data, // Ex: 180b / 720b = 0.25 - sd_ratio = (1.0f - sd_percent) / sd_percent; // Ex: (1.0 - 0.25) / 0.25 = 3.0 - - const uint32_t elapsed_time = value - start_time; // Ex: T2 - T1 = 300s - return uint32_t(elapsed_time * sd_ratio); // Ex: 300s * 3.0f = 900s - } - #pragma GCC diagnostic pop }; diff --git a/Marlin/src/libs/stopwatch.cpp b/Marlin/src/libs/stopwatch.cpp index 8790c2b3db..1afa2615e2 100644 --- a/Marlin/src/libs/stopwatch.cpp +++ b/Marlin/src/libs/stopwatch.cpp @@ -33,6 +33,12 @@ uint32_t Stopwatch::accumulator; uint32_t Stopwatch::startTimestamp; uint32_t Stopwatch::stopTimestamp; +#if ANY(REMAINING_TIME_PRIME, REMAINING_TIME_AUTOPRIME) + uint32_t Stopwatch::lap_start_time; // Reckon from this start time + float Stopwatch::lap_start_sdpos, // Reckon from this start file position + Stopwatch::lap_total_data; // Total size from start_sdpos to end of file +#endif + bool Stopwatch::stop() { debug(F("stop")); diff --git a/Marlin/src/libs/stopwatch.h b/Marlin/src/libs/stopwatch.h index 13fa3de4b4..6404d8426f 100644 --- a/Marlin/src/libs/stopwatch.h +++ b/Marlin/src/libs/stopwatch.h @@ -40,6 +40,12 @@ class Stopwatch { static uint32_t startTimestamp; static uint32_t stopTimestamp; + #if ANY(REMAINING_TIME_PRIME, REMAINING_TIME_AUTOPRIME) + static uint32_t lap_start_time; // Reckon from this start time + static float lap_start_sdpos, // Reckon from this start file position + lap_total_data; // Total size from start_sdpos to end of file + #endif + public: /** * @brief Initialize the stopwatch @@ -104,6 +110,57 @@ class Stopwatch { */ static uint32_t duration(); + #if ANY(REMAINING_TIME_PRIME, REMAINING_TIME_AUTOPRIME) + + /** + * @brief Get the estimated remaining time based on the elapsed time + * @details Use the given start time and sdpos values to estimate the + * remaining time as reckoned from duration(). + * Should be superseded by 'M73 R' (SET_REMAINING_TIME). + * Get per-object time estimate with M808 by putting 'M75 R' at the start of the loop. + * The UI should consider a "start_sdpos" of 0 to be unset and show ---. + * + * @param start_time The time to consider the "real" start of the print. Saved time of the first E move with X and/or Y. + * @param sdpos The current sdpos of the print job. + * @param start_sdpos The sdpos of the first printing move (E move with X and/or Y), as a float. + * @param total_data The pre-calculated end_sdpos - start_sdpos as a float. + */ + uint32_t remainingTimeEstimate(const uint32_t start_time, const uint32_t sdpos, const float start_sdpos, const float total_data) const { + const float elapsed_data = float(sdpos) - start_sdpos; // Ex: 460b - 280b = 180b + if (elapsed_data < 200 || total_data == 0) return 0; // ...not yet... + const float //total_data = float(end_sdpos - start_sdpos), // Ex: 999b-280b+1 = 720b + sd_percent = elapsed_data / total_data, // Ex: 180b / 720b = 0.25 + sd_ratio = (1.0f - sd_percent) / sd_percent; // Ex: (1.0 - 0.25) / 0.25 = 3.0 + const uint32_t elapsed_time = duration() - start_time; // Ex: T2 - T1 = 300s + return uint32_t(elapsed_time * sd_ratio); // Ex: 300s * 3.0f = 900s + } + + FORCE_INLINE uint32_t remainingTimeEstimate(const uint32_t sdpos) const { + return remainingTimeEstimate(lap_start_time, sdpos, lap_start_sdpos, lap_total_data); + } + + /** + * Start a completion time estimate given a time, start spos, and end sdpos, + * Use the 'M75 R' command to call primeRemainingTimeEstimate at the first actual printing move. + * TODO: + * + * TODO: Whenever the printer does an E + XY move call primeRemainingTimeEstimate. + * If the flag is still 'false' set it to 'true', record the current + * print time and sdpos to pass to this method. + */ + FORCE_INLINE static void primeRemainingTimeEstimate(const uint32_t start_time, const uint32_t start_sdpos, const uint32_t end_sdpos) { + lap_start_time = start_time; + lap_start_sdpos = float(start_sdpos); + lap_total_data = float(end_sdpos - start_sdpos + 1UL); + } + + // Start estimation using the current time as with print_job_timer.primeRemainingTimeEstimate(...) + FORCE_INLINE void primeRemainingTimeEstimate(const uint32_t start_sdpos, const uint32_t end_sdpos) { + primeRemainingTimeEstimate(duration(), start_sdpos, end_sdpos); + } + + #endif // REMAINING_TIME_PRIME || REMAINING_TIME_AUTOPRIME + #ifdef DEBUG_STOPWATCH /** diff --git a/buildroot/tests/STM32F103RE b/buildroot/tests/STM32F103RE index f97b04c520..fbdee52c21 100755 --- a/buildroot/tests/STM32F103RE +++ b/buildroot/tests/STM32F103RE @@ -15,7 +15,8 @@ opt_set MOTHERBOARD BOARD_STM32F103RE SERIAL_PORT -1 EXTRUDERS 2 \ NOZZLE_CLEAN_END_POINT "{ { 10, 20, 3 } }" 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 + BAUD_RATE_GCODE GCODE_MACROS NOZZLE_PARK_FEATURE NOZZLE_CLEAN_FEATURE \ + REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER SHOW_REMAINING_TIME REMAINING_TIME_PRIME REMAINING_TIME_AUTOPRIME exec_test $1 $2 "STM32F1R EEPROM_SETTINGS EEPROM_CHITCHAT SDSUPPORT PAREN_COMMENTS GCODE_MOTION_MODES" "$3" # cleanup From 1acaa6dc15c3ac87b8b5ca792a54d961e5159d56 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 6 Dec 2025 00:31:28 +0000 Subject: [PATCH 40/47] [cron] Bump distribution date (2025-12-06) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index d83252ddc7..4922561f67 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-05" +//#define STRING_DISTRIBUTION_DATE "2025-12-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 46fd6b39f7..4b3d753f0e 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-05" + #define STRING_DISTRIBUTION_DATE "2025-12-06" #endif /** From 3551a2613de7399b4e030496d9facbca30e25cd1 Mon Sep 17 00:00:00 2001 From: Miguel Risco-Castillo Date: Sat, 6 Dec 2025 12:01:43 -0500 Subject: [PATCH 41/47] =?UTF-8?q?=F0=9F=A9=B9=20Consistent=20FTM=20timer?= =?UTF-8?q?=20types=20(#28204)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/HAL/AVR/timers.h | 2 +- Marlin/src/HAL/DUE/timers.h | 2 +- Marlin/src/HAL/ESP32/timers.h | 2 +- Marlin/src/HAL/GD32_MFL/timers.h | 4 ++-- Marlin/src/HAL/HC32/timers.h | 2 +- Marlin/src/HAL/LINUX/timers.h | 2 +- Marlin/src/HAL/LPC1768/timers.h | 2 +- Marlin/src/HAL/NATIVE_SIM/timers.h | 2 +- Marlin/src/HAL/RP2040/timers.h | 2 +- Marlin/src/HAL/SAMD21/timers.h | 2 +- Marlin/src/HAL/SAMD51/timers.h | 2 +- Marlin/src/HAL/STM32F1/timers.h | 2 +- Marlin/src/HAL/TEENSY31_32/timers.h | 2 +- Marlin/src/HAL/TEENSY35_36/timers.h | 2 +- Marlin/src/HAL/TEENSY40_41/timers.h | 2 +- Marlin/src/MarlinCore.cpp | 2 +- Marlin/src/module/ft_motion/stepping.h | 7 +++---- Marlin/src/module/motion.cpp | 2 +- Marlin/src/module/planner.cpp | 2 +- Marlin/src/module/stepper.cpp | 2 +- 20 files changed, 23 insertions(+), 24 deletions(-) diff --git a/Marlin/src/HAL/AVR/timers.h b/Marlin/src/HAL/AVR/timers.h index 892e0e493b..46993ead33 100644 --- a/Marlin/src/HAL/AVR/timers.h +++ b/Marlin/src/HAL/AVR/timers.h @@ -28,7 +28,7 @@ // ------------------------ typedef uint16_t hal_timer_t; -#define HAL_TIMER_TYPE_MAX 0xFFFFU +#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT16_MAX) // ------------------------ // Defines diff --git a/Marlin/src/HAL/DUE/timers.h b/Marlin/src/HAL/DUE/timers.h index c63e051ef3..6d02033ed5 100644 --- a/Marlin/src/HAL/DUE/timers.h +++ b/Marlin/src/HAL/DUE/timers.h @@ -34,7 +34,7 @@ #define FORCE_INLINE __attribute__((always_inline)) inline typedef uint32_t hal_timer_t; -#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFUL +#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT32_MAX) #define HAL_TIMER_PRESCALER 2 #define HAL_TIMER_RATE ((F_CPU) / (HAL_TIMER_PRESCALER)) // frequency of timers peripherals diff --git a/Marlin/src/HAL/ESP32/timers.h b/Marlin/src/HAL/ESP32/timers.h index 4e5f92d671..2ba034d9b6 100644 --- a/Marlin/src/HAL/ESP32/timers.h +++ b/Marlin/src/HAL/ESP32/timers.h @@ -30,7 +30,7 @@ #define FORCE_INLINE __attribute__((always_inline)) inline typedef uint64_t hal_timer_t; -#define HAL_TIMER_TYPE_MAX 0xFFFF'FFFF'FFFF'FFFFULL +#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT64_MAX) #ifndef MF_TIMER_STEP #define MF_TIMER_STEP 0 // Timer Index for Stepper diff --git a/Marlin/src/HAL/GD32_MFL/timers.h b/Marlin/src/HAL/GD32_MFL/timers.h index d45e3d1767..00a757d4e0 100644 --- a/Marlin/src/HAL/GD32_MFL/timers.h +++ b/Marlin/src/HAL/GD32_MFL/timers.h @@ -34,8 +34,8 @@ #define MF_TIMER_TEMP 1 #define MF_TIMER_PULSE MF_TIMER_STEP -#define hal_timer_t uint32_t -#define HAL_TIMER_TYPE_MAX UINT16_MAX +typedef uint32_t hal_timer_t; +#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT16_MAX) extern uint32_t GetStepperTimerClkFreq(); diff --git a/Marlin/src/HAL/HC32/timers.h b/Marlin/src/HAL/HC32/timers.h index 9b898101dc..9992033e0e 100644 --- a/Marlin/src/HAL/HC32/timers.h +++ b/Marlin/src/HAL/HC32/timers.h @@ -27,7 +27,7 @@ // typedef Timer0 *timer_channel_t; typedef uint16_t hal_timer_t; -#define HAL_TIMER_TYPE_MAX 0xFFFFU +#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT16_MAX) // // Timer instances diff --git a/Marlin/src/HAL/LINUX/timers.h b/Marlin/src/HAL/LINUX/timers.h index cbca970bb2..ea64f1517d 100644 --- a/Marlin/src/HAL/LINUX/timers.h +++ b/Marlin/src/HAL/LINUX/timers.h @@ -34,7 +34,7 @@ #define FORCE_INLINE __attribute__((always_inline)) inline typedef uint32_t hal_timer_t; -#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFUL +#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT32_MAX) #define HAL_TIMER_RATE ((SystemCoreClock) / 4) // frequency of timers peripherals diff --git a/Marlin/src/HAL/LPC1768/timers.h b/Marlin/src/HAL/LPC1768/timers.h index e29aa273a1..6e158f9290 100644 --- a/Marlin/src/HAL/LPC1768/timers.h +++ b/Marlin/src/HAL/LPC1768/timers.h @@ -57,7 +57,7 @@ #define _HAL_TIMER_ISR(T) __HAL_TIMER_ISR(T) typedef uint32_t hal_timer_t; -#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFUL +#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT32_MAX) #define HAL_TIMER_RATE ((F_CPU) / 4) // (Hz) Frequency of timers peripherals diff --git a/Marlin/src/HAL/NATIVE_SIM/timers.h b/Marlin/src/HAL/NATIVE_SIM/timers.h index 6609774d12..af3e5ff992 100644 --- a/Marlin/src/HAL/NATIVE_SIM/timers.h +++ b/Marlin/src/HAL/NATIVE_SIM/timers.h @@ -34,7 +34,7 @@ #define FORCE_INLINE __attribute__((always_inline)) inline typedef uint64_t hal_timer_t; -#define HAL_TIMER_TYPE_MAX 0xFFFF'FFFF'FFFF'FFFFULL +#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT64_MAX) #define HAL_TIMER_RATE ((SystemCoreClock) / 4) // frequency of timers peripherals diff --git a/Marlin/src/HAL/RP2040/timers.h b/Marlin/src/HAL/RP2040/timers.h index 06deb152f7..fd078ae4a9 100644 --- a/Marlin/src/HAL/RP2040/timers.h +++ b/Marlin/src/HAL/RP2040/timers.h @@ -41,7 +41,7 @@ #define _HAL_TIMER_ISR(T) __HAL_TIMER_ISR(T) typedef uint64_t hal_timer_t; -#define HAL_TIMER_TYPE_MAX 0xFFFF'FFFF'FFFF'FFFFULL +#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT64_MAX) #define HAL_TIMER_RATE (1'000'000ULL) // fixed value as we use a microsecond timesource #ifndef MF_TIMER_STEP diff --git a/Marlin/src/HAL/SAMD21/timers.h b/Marlin/src/HAL/SAMD21/timers.h index b3c53e7416..55034459c3 100644 --- a/Marlin/src/HAL/SAMD21/timers.h +++ b/Marlin/src/HAL/SAMD21/timers.h @@ -33,7 +33,7 @@ // -------------------------------------------------------------------------- typedef uint32_t hal_timer_t; -#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFUL +#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT32_MAX) #define HAL_TIMER_RATE F_CPU // frequency of timers peripherals diff --git a/Marlin/src/HAL/SAMD51/timers.h b/Marlin/src/HAL/SAMD51/timers.h index d39ac0254a..b69c131406 100644 --- a/Marlin/src/HAL/SAMD51/timers.h +++ b/Marlin/src/HAL/SAMD51/timers.h @@ -32,7 +32,7 @@ // -------------------------------------------------------------------------- typedef uint32_t hal_timer_t; -#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFUL +#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT32_MAX) #define HAL_TIMER_RATE F_CPU // frequency of timers peripherals diff --git a/Marlin/src/HAL/STM32F1/timers.h b/Marlin/src/HAL/STM32F1/timers.h index 10ee2e4f9e..2aee309c38 100644 --- a/Marlin/src/HAL/STM32F1/timers.h +++ b/Marlin/src/HAL/STM32F1/timers.h @@ -40,7 +40,7 @@ */ typedef uint16_t hal_timer_t; -#define HAL_TIMER_TYPE_MAX 0xFFFFU +#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT16_MAX) #define HAL_TIMER_RATE uint32_t(F_CPU) // frequency of timers peripherals diff --git a/Marlin/src/HAL/TEENSY31_32/timers.h b/Marlin/src/HAL/TEENSY31_32/timers.h index 7de8cccde4..c22ffc21f9 100644 --- a/Marlin/src/HAL/TEENSY31_32/timers.h +++ b/Marlin/src/HAL/TEENSY31_32/timers.h @@ -34,7 +34,7 @@ #define FORCE_INLINE __attribute__((always_inline)) inline typedef uint32_t hal_timer_t; -#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFUL +#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT32_MAX) #define FTM0_TIMER_PRESCALE 8 #define FTM1_TIMER_PRESCALE 4 diff --git a/Marlin/src/HAL/TEENSY35_36/timers.h b/Marlin/src/HAL/TEENSY35_36/timers.h index 60b35faa38..9c55af6228 100644 --- a/Marlin/src/HAL/TEENSY35_36/timers.h +++ b/Marlin/src/HAL/TEENSY35_36/timers.h @@ -34,7 +34,7 @@ #define FORCE_INLINE __attribute__((always_inline)) inline typedef uint32_t hal_timer_t; -#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFUL +#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT32_MAX) #define FTM0_TIMER_PRESCALE 8 #define FTM1_TIMER_PRESCALE 4 diff --git a/Marlin/src/HAL/TEENSY40_41/timers.h b/Marlin/src/HAL/TEENSY40_41/timers.h index 49b5c32836..14a9587486 100644 --- a/Marlin/src/HAL/TEENSY40_41/timers.h +++ b/Marlin/src/HAL/TEENSY40_41/timers.h @@ -34,7 +34,7 @@ #define FORCE_INLINE __attribute__((always_inline)) inline typedef uint32_t hal_timer_t; -#define HAL_TIMER_TYPE_MAX 0xFFFFFFFEUL +#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT32_MAX-1UL) #define GPT_TIMER_RATE (F_CPU / 4) // 150MHz (Can't use F_BUS_ACTUAL because it's extern volatile) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 5b44b5c7b9..6610e90ab7 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -724,7 +724,7 @@ void Marlin::manage_inactivity(const bool no_stepper_sleep/*=false*/) { // handle delayed move timeout if (delayed_move_time && ELAPSED(ms, delayed_move_time) && isRunning()) { // travel moves have been received so enact them - delayed_move_time = 0xFFFFFFFFUL; // force moves to be done + delayed_move_time = UINT32_MAX; // force moves to be done destination = current_position; prepare_line_to_destination(); planner.synchronize(); diff --git a/Marlin/src/module/ft_motion/stepping.h b/Marlin/src/module/ft_motion/stepping.h index cacdd5d69a..9274cbf369 100644 --- a/Marlin/src/module/ft_motion/stepping.h +++ b/Marlin/src/module/ft_motion/stepping.h @@ -26,12 +26,11 @@ // // uint64-free equivalent of: ((uint64_t)a * b) >> 16 // -FORCE_INLINE constexpr uint32_t a_times_b_shift_16(uint32_t a, uint32_t b) { - uint32_t hi = a >> 16; - uint32_t lo = a & 0xFFFFu; +FORCE_INLINE constexpr uint32_t a_times_b_shift_16(const uint32_t a, const uint32_t b) { + const uint32_t hi = a >> 16, lo = a & 0x0000FFFF; return (hi * b) + ((lo * b) >> 16); } -#define FTM_NEVER (UINT16_MAX) // Reserved number to indicate "no ticks in this frame" (FRAME_TICKS_FP+1 would work too) +#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 in a frame static_assert(FRAME_TICKS < FTM_NEVER, "(STEPPER_TIMER_RATE / FTM_FS) must be < 2^16 (otherwise fixed-point numbers exceed uint16 vars)."); constexpr uint32_t FTM_Q_INT = 32u - __builtin_clz(FRAME_TICKS + 1); // Bits to represent the max value (duration of a frame, +1 one for FTM_NEVER). diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 37d9188863..1012cc4150 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -1827,7 +1827,7 @@ float get_move_distance(const xyze_pos_t &diff OPTARG(HAS_ROTATIONAL_AXES, bool // This is a travel move (with no extrusion) // Skip it, but keep track of the current position // (so it can be used as the start of the next non-travel move) - if (delayed_move_time != 0xFFFFFFFFUL) { + if (delayed_move_time != UINT32_MAX) { current_position = destination; NOLESS(raised_parked_position.z, destination.z); delayed_move_time = millis() + 1000UL; diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 6bee1890e3..62db79a907 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -3188,7 +3188,7 @@ void Planner::refresh_acceleration_rates() { if (TERN1(DISTINCT_E_FACTORS, i < E_AXIS || i == E_AXIS_N(active_extruder))) NOLESS(highest_rate, max_acceleration_steps_per_s2[i]); } - acceleration_long_cutoff = 4294967295UL / highest_rate; // 0xFFFFFFFFUL + acceleration_long_cutoff = UINT32_MAX / highest_rate; TERN_(HAS_LINEAR_E_JERK, recalculate_max_e_jerk()); } diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 060d51c0cc..d79a5edcc0 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -1573,7 +1573,7 @@ void Stepper::isr() { // Program timer compare for the maximum period, so it does NOT // flag an interrupt while this ISR is running - So changes from small // periods to big periods are respected and the timer does not reset to 0 - HAL_timer_set_compare(MF_TIMER_STEP, hal_timer_t(HAL_TIMER_TYPE_MAX)); + HAL_timer_set_compare(MF_TIMER_STEP, HAL_TIMER_TYPE_MAX); // Count of ticks for the next ISR hal_timer_t next_isr_ticks = 0; From ef2fbcd2b60dc39b70436a597288318c699bdf9b Mon Sep 17 00:00:00 2001 From: Naomi Rennie-Waldock Date: Sat, 6 Dec 2025 17:26:21 +0000 Subject: [PATCH 42/47] =?UTF-8?q?=F0=9F=94=A8=20Fix=20configuration.py=20U?= =?UTF-8?q?RL=20fetch=20(#28208)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/share/PlatformIO/scripts/configuration.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/buildroot/share/PlatformIO/scripts/configuration.py b/buildroot/share/PlatformIO/scripts/configuration.py index 71d4e3777c..6677cd566d 100755 --- a/buildroot/share/PlatformIO/scripts/configuration.py +++ b/buildroot/share/PlatformIO/scripts/configuration.py @@ -3,7 +3,7 @@ # configuration.py # Apply options from config.ini to the existing Configuration headers # -import re, os, shutil, configparser, datetime +import re, os, shutil, subprocess, configparser, datetime from pathlib import Path verbose = 0 @@ -149,9 +149,9 @@ def fetch_example(url): # Find a suitable fetch command if shutil.which("curl") is not None: - fetch = "curl -L -s -S -f -o" + fetch = [ "curl", "-L", "-s", "-S", "-f", "-o" ] elif shutil.which("wget") is not None: - fetch = "wget -q -O" + fetch = [ "wget", "-q", "-O" ] else: blab("Couldn't find curl or wget", -1) #blab("Couldn't find curl or wget", 0) @@ -165,7 +165,7 @@ def fetch_example(url): # 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: + if subprocess.call(fetch + [ "wgot", f"{url}/{fn}" ], stdout=subprocess.DEVNULL, stderr=subprocess.DEVNULL) == 0: shutil.move('wgot', config_path(fn)) gotfile = True blab(f"Fetched {fn}", 2) From d14b8e443512cd33edaa2d22507a7bd04d6cc3d1 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 6 Dec 2025 12:32:09 -0600 Subject: [PATCH 43/47] =?UTF-8?q?=F0=9F=94=A7=20Clean=20up=20TEMP=5FSENSOR?= =?UTF-8?q?=20conditionals,=20SKRat=20fix?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/Conditionals-1-axes.h | 54 ++++++++++++++++--- Marlin/src/inc/Conditionals-3-etc.h | 43 --------------- Marlin/src/module/temperature.cpp | 1 + Marlin/src/pins/mega/pins_MEGACONTROLLER.h | 6 +-- Marlin/src/pins/mega/pins_MEGATRONICS.h | 2 +- Marlin/src/pins/mega/pins_MEGATRONICS_2.h | 8 ++- Marlin/src/pins/mega/pins_MEGATRONICS_3.h | 8 +-- Marlin/src/pins/ramps/pins_RUMBA.h | 8 +-- Marlin/src/pins/ramps/pins_TANGO.h | 4 +- Marlin/src/pins/stm32g0/pins_BTT_SKRAT_V1_0.h | 4 +- 10 files changed, 66 insertions(+), 72 deletions(-) diff --git a/Marlin/src/inc/Conditionals-1-axes.h b/Marlin/src/inc/Conditionals-1-axes.h index 1ad256b3b8..d81aa2c746 100644 --- a/Marlin/src/inc/Conditionals-1-axes.h +++ b/Marlin/src/inc/Conditionals-1-axes.h @@ -53,14 +53,6 @@ #else #undef EXTRUDERS #define EXTRUDERS 0 - #undef TEMP_SENSOR_0 - #undef TEMP_SENSOR_1 - #undef TEMP_SENSOR_2 - #undef TEMP_SENSOR_3 - #undef TEMP_SENSOR_4 - #undef TEMP_SENSOR_5 - #undef TEMP_SENSOR_6 - #undef TEMP_SENSOR_7 #undef SINGLENOZZLE #undef SWITCHING_EXTRUDER #undef MECHANICAL_SWITCHING_EXTRUDER @@ -222,6 +214,52 @@ #undef HOTEND_OFFSET_Z #endif +// Clean up unused temperature sensors and sub-options +#define UNUSED_TEMP_SENSOR(N) (!TEMP_SENSOR_##N || N >= HOTENDS) +#if UNUSED_TEMP_SENSOR(0) + #undef TEMP_SENSOR_0 +#endif +#if UNUSED_TEMP_SENSOR(1) + #undef TEMP_SENSOR_1 +#endif +#if UNUSED_TEMP_SENSOR(2) + #undef TEMP_SENSOR_2 +#endif +#if UNUSED_TEMP_SENSOR(3) + #undef TEMP_SENSOR_3 +#endif +#if UNUSED_TEMP_SENSOR(4) + #undef TEMP_SENSOR_4 +#endif +#if UNUSED_TEMP_SENSOR(5) + #undef TEMP_SENSOR_5 +#endif +#if UNUSED_TEMP_SENSOR(6) + #undef TEMP_SENSOR_6 +#endif +#if UNUSED_TEMP_SENSOR(7) + #undef TEMP_SENSOR_7 +#endif +#if !TEMP_SENSOR_BED + #undef TEMP_SENSOR_BED +#endif +#if !TEMP_SENSOR_CHAMBER + #undef TEMP_SENSOR_CHAMBER +#endif +#if !TEMP_SENSOR_PROBE + #undef TEMP_SENSOR_PROBE +#endif +#if !TEMP_SENSOR_REDUNDANT + #undef TEMP_SENSOR_REDUNDANT +#endif +#if !TEMP_SENSOR_BOARD + #undef TEMP_SENSOR_BOARD +#endif +#if !TEMP_SENSOR_SOC + #undef TEMP_SENSOR_SOC +#endif +#undef UNUSED_TEMP_SENSOR + /** * Number of Linear Axes (e.g., XYZIJKUVW) * All the logical axes except for the tool (E) axis diff --git a/Marlin/src/inc/Conditionals-3-etc.h b/Marlin/src/inc/Conditionals-3-etc.h index 3fa80726f1..f5568b669a 100644 --- a/Marlin/src/inc/Conditionals-3-etc.h +++ b/Marlin/src/inc/Conditionals-3-etc.h @@ -40,48 +40,17 @@ // Remove irrelevant Configuration.h settings // -// Clean up unused temperature sensors and sub-options - -#define UNUSED_TEMP_SENSOR(N) (!TEMP_SENSOR_##N || N >= HOTENDS) -#if UNUSED_TEMP_SENSOR(0) - #undef TEMP_SENSOR_0 -#endif -#if UNUSED_TEMP_SENSOR(1) - #undef TEMP_SENSOR_1 -#endif -#if UNUSED_TEMP_SENSOR(2) - #undef TEMP_SENSOR_2 -#endif -#if UNUSED_TEMP_SENSOR(3) - #undef TEMP_SENSOR_3 -#endif -#if UNUSED_TEMP_SENSOR(4) - #undef TEMP_SENSOR_4 -#endif -#if UNUSED_TEMP_SENSOR(5) - #undef TEMP_SENSOR_5 -#endif -#if UNUSED_TEMP_SENSOR(6) - #undef TEMP_SENSOR_6 -#endif -#if UNUSED_TEMP_SENSOR(7) - #undef TEMP_SENSOR_7 -#endif -#undef UNUSED_TEMP_SENSOR - #if !HAS_HOTEND #undef PREHEAT_1_TEMP_HOTEND #undef PREHEAT_2_TEMP_HOTEND #endif #if !TEMP_SENSOR_BED - #undef TEMP_SENSOR_BED #undef THERMAL_PROTECTION_BED #undef MAX_BED_POWER #undef PREHEAT_1_TEMP_BED #undef PREHEAT_2_TEMP_BED #endif #if !TEMP_SENSOR_CHAMBER - #undef TEMP_SENSOR_CHAMBER #undef THERMAL_PROTECTION_CHAMBER #undef MAX_CHAMBER_POWER #undef PREHEAT_1_TEMP_CHAMBER @@ -91,18 +60,6 @@ #undef TEMP_SENSOR_COOLER #undef THERMAL_PROTECTION_COOLER #endif -#if !TEMP_SENSOR_PROBE - #undef TEMP_SENSOR_PROBE -#endif -#if !TEMP_SENSOR_REDUNDANT - #undef TEMP_SENSOR_REDUNDANT -#endif -#if !TEMP_SENSOR_BOARD - #undef TEMP_SENSOR_BOARD -#endif -#if !TEMP_SENSOR_SOC - #undef TEMP_SENSOR_SOC -#endif #if !SOFT_PWM_SCALE #undef SOFT_PWM_SCALE #endif diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 83deaa6694..819133f30d 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -348,6 +348,7 @@ PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED); #define CHECK_MAXTEMP_(N,M,S) static_assert( \ S >= 998 || M <= _MAX(TT_NAME(S)[0].celsius, TT_NAME(S)[COUNT(TT_NAME(S)) - 1].celsius) - (HOTEND_OVERSHOOT), \ "HEATER_" STRINGIFY(N) "_MAXTEMP (" STRINGIFY(M) ") is too high for thermistor_" STRINGIFY(S) ".h with HOTEND_OVERSHOOT=" STRINGIFY(HOTEND_OVERSHOOT) "."); + // This solution requires TEMP_SENSOR_* for all HOTENDS to be defined or compile fails #define CHECK_MAXTEMP(N) TERN(TEMP_SENSOR_##N##_IS_THERMISTOR, CHECK_MAXTEMP_, CODE_0)(N, HEATER_##N##_MAXTEMP, TEMP_SENSOR_##N) REPEAT(HOTENDS, CHECK_MAXTEMP) diff --git a/Marlin/src/pins/mega/pins_MEGACONTROLLER.h b/Marlin/src/pins/mega/pins_MEGACONTROLLER.h index 4ee5df8c66..d18350da47 100644 --- a/Marlin/src/pins/mega/pins_MEGACONTROLLER.h +++ b/Marlin/src/pins/mega/pins_MEGACONTROLLER.h @@ -86,13 +86,13 @@ // // Temperature Sensors // -#if TEMP_SENSOR_0 == -1 +#if TEMP_SENSOR_0_IS_AD595 #define TEMP_0_PIN 4 // Analog Input #else #define TEMP_0_PIN 0 // Analog Input #endif -#if TEMP_SENSOR_1 == -1 +#if TEMP_SENSOR_1_IS_AD595 #define TEMP_1_PIN 5 // Analog Input #else #define TEMP_1_PIN 2 // Analog Input @@ -100,7 +100,7 @@ #define TEMP_2_PIN 3 // Analog Input -#if TEMP_SENSOR_BED == -1 +#if TEMP_SENSOR_BED_IS_AD595 #define TEMP_BED_PIN 6 // Analog Input #else #define TEMP_BED_PIN 1 // Analog Input diff --git a/Marlin/src/pins/mega/pins_MEGATRONICS.h b/Marlin/src/pins/mega/pins_MEGATRONICS.h index d5616c0026..c6ffea8e1c 100644 --- a/Marlin/src/pins/mega/pins_MEGATRONICS.h +++ b/Marlin/src/pins/mega/pins_MEGATRONICS.h @@ -73,7 +73,7 @@ // // Temperature Sensors // -#if TEMP_SENSOR_0 == -1 +#if TEMP_SENSOR_0_IS_AD595 #define TEMP_0_PIN 8 // Analog Input #else #define TEMP_0_PIN 13 // Analog Input diff --git a/Marlin/src/pins/mega/pins_MEGATRONICS_2.h b/Marlin/src/pins/mega/pins_MEGATRONICS_2.h index 9f7abd3fb8..edb1295b94 100644 --- a/Marlin/src/pins/mega/pins_MEGATRONICS_2.h +++ b/Marlin/src/pins/mega/pins_MEGATRONICS_2.h @@ -77,19 +77,17 @@ // // Temperature Sensors // -#if TEMP_SENSOR_0 == -1 +#if TEMP_SENSOR_0_IS_AD595 #define TEMP_0_PIN 4 // Analog Input #else #define TEMP_0_PIN 13 // Analog Input #endif - -#if TEMP_SENSOR_1 == -1 +#if TEMP_SENSOR_1_IS_AD595 #define TEMP_1_PIN 8 // Analog Input #else #define TEMP_1_PIN 15 // Analog Input #endif - -#if TEMP_SENSOR_BED == -1 +#if TEMP_SENSOR_BED_IS_AD595 #define TEMP_BED_PIN 8 // Analog Input #else #define TEMP_BED_PIN 14 // Analog Input diff --git a/Marlin/src/pins/mega/pins_MEGATRONICS_3.h b/Marlin/src/pins/mega/pins_MEGATRONICS_3.h index 4c60ef1a5b..4e3f52f7b8 100644 --- a/Marlin/src/pins/mega/pins_MEGATRONICS_3.h +++ b/Marlin/src/pins/mega/pins_MEGATRONICS_3.h @@ -98,22 +98,22 @@ // // Temperature Sensors // -#if TEMP_SENSOR_0 == -1 +#if TEMP_SENSOR_0_IS_AD595 #define TEMP_0_PIN 11 // Analog Input #else #define TEMP_0_PIN 15 // Analog Input #endif -#if TEMP_SENSOR_1 == -1 +#if TEMP_SENSOR_1_IS_AD595 #define TEMP_1_PIN 10 // Analog Input #else #define TEMP_1_PIN 13 // Analog Input #endif -#if TEMP_SENSOR_2 == -1 +#if TEMP_SENSOR_2_IS_AD595 #define TEMP_2_PIN 9 // Analog Input #else #define TEMP_2_PIN 12 // Analog Input #endif -#if TEMP_SENSOR_BED == -1 +#if TEMP_SENSOR_BED_IS_AD595 #define TEMP_BED_PIN 8 // Analog Input #else #define TEMP_BED_PIN 14 // Analog Input diff --git a/Marlin/src/pins/ramps/pins_RUMBA.h b/Marlin/src/pins/ramps/pins_RUMBA.h index c62b68f6cc..b49487ff5f 100644 --- a/Marlin/src/pins/ramps/pins_RUMBA.h +++ b/Marlin/src/pins/ramps/pins_RUMBA.h @@ -112,7 +112,7 @@ // Temperature Sensors // #ifndef TEMP_0_PIN - #if TEMP_SENSOR_0 == -1 + #if TEMP_SENSOR_0_IS_AD595 #define TEMP_0_PIN 6 // Analog Input (connector *K1* on RUMBA thermocouple ADD ON is used) #else #define TEMP_0_PIN 15 // Analog Input (default connector for thermistor *T0* on rumba board is used) @@ -120,14 +120,14 @@ #endif #ifndef TEMP_1_PIN - #if TEMP_SENSOR_1 == -1 + #if TEMP_SENSOR_1_IS_AD595 #define TEMP_1_PIN 5 // Analog Input (connector *K2* on RUMBA thermocouple ADD ON is used) #else #define TEMP_1_PIN 14 // Analog Input (default connector for thermistor *T1* on rumba board is used) #endif #endif -#if TEMP_SENSOR_2 == -1 +#if TEMP_SENSOR_2_IS_AD595 #define TEMP_2_PIN 7 // Analog Input (connector *K3* on RUMBA thermocouple ADD ON is used <-- this can't be used when TEMP_SENSOR_BED is defined as thermocouple) #else #define TEMP_2_PIN 13 // Analog Input (default connector for thermistor *T2* on rumba board is used) @@ -140,7 +140,7 @@ //#define TEMP_CHAMBER_PIN 12 // Analog Input (default connector for thermistor *T3* on rumba board is used) #endif -#if TEMP_SENSOR_BED == -1 +#if TEMP_SENSOR_BED_IS_AD595 #define TEMP_BED_PIN 7 // Analog Input (connector *K3* on RUMBA thermocouple ADD ON is used <-- this can't be used when TEMP_SENSOR_2 is defined as thermocouple) #else #define TEMP_BED_PIN 11 // Analog Input (default connector for thermistor *THB* on rumba board is used) diff --git a/Marlin/src/pins/ramps/pins_TANGO.h b/Marlin/src/pins/ramps/pins_TANGO.h index 0f8aaca0e2..214f11e5e0 100644 --- a/Marlin/src/pins/ramps/pins_TANGO.h +++ b/Marlin/src/pins/ramps/pins_TANGO.h @@ -37,7 +37,7 @@ #endif #ifndef TEMP_0_PIN - #if TEMP_SENSOR_0 == -1 + #if TEMP_SENSOR_0_IS_AD595 #define TEMP_0_PIN 10 // Analog Input (connector *K1* on Tango thermocouple ADD ON is used) #else #define TEMP_0_PIN 15 // Analog Input (default connector for thermistor *T0* on rumba board is used) @@ -45,7 +45,7 @@ #endif #ifndef TEMP_1_PIN - #if TEMP_SENSOR_1 == -1 + #if TEMP_SENSOR_1_IS_AD595 #define TEMP_1_PIN 9 // Analog Input (connector *K2* on Tango thermocouple ADD ON is used) #else #define TEMP_1_PIN 14 // Analog Input (default connector for thermistor *T1* on rumba board is used) diff --git a/Marlin/src/pins/stm32g0/pins_BTT_SKRAT_V1_0.h b/Marlin/src/pins/stm32g0/pins_BTT_SKRAT_V1_0.h index 65bace9d50..47830d8477 100644 --- a/Marlin/src/pins/stm32g0/pins_BTT_SKRAT_V1_0.h +++ b/Marlin/src/pins/stm32g0/pins_BTT_SKRAT_V1_0.h @@ -182,10 +182,10 @@ #ifndef TEMP_BED_PIN #define TEMP_BED_PIN PB2 // TB #endif -#ifndef TEMP_SENSOR_PROBE +#ifndef TEMP_PROBE_PIN #define TEMP_PROBE_PIN PA1 // TH2 #endif -#ifndef TEMP_SENSOR_CHAMBER +#ifndef TEMP_CHAMBER_PIN #define TEMP_CHAMBER_PIN PA0 // TH3 #endif From d56fbe21fcedf8c14f359568f8f9e746938e80dd Mon Sep 17 00:00:00 2001 From: Harald Wagener Date: Sat, 6 Dec 2025 20:42:52 +0100 Subject: [PATCH 44/47] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20FTM=20without=20FTM?= =?UTF-8?q?=5FPOLYS=20build=20(#28209)?= 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 | 2 +- buildroot/tests/STM32F103RC_btt | 3 ++- 3 files changed, 5 insertions(+), 6 deletions(-) diff --git a/Marlin/src/module/ft_motion.cpp b/Marlin/src/module/ft_motion.cpp index d402439c04..a2e0b8be70 100644 --- a/Marlin/src/module/ft_motion.cpp +++ b/Marlin/src/module/ft_motion.cpp @@ -302,10 +302,8 @@ void FTMotion::init() { switch (type) { default: case TrajectoryType::TRAPEZOIDAL: currentGenerator = &trapezoidalGenerator; break; - #if ENABLED(FTM_POLYS) - case TrajectoryType::POLY5: currentGenerator = &poly5Generator; break; - case TrajectoryType::POLY6: currentGenerator = &poly6Generator; break; - #endif + case TrajectoryType::POLY5: currentGenerator = &poly5Generator; break; + case TrajectoryType::POLY6: currentGenerator = &poly6Generator; break; } } diff --git a/Marlin/src/module/ft_motion.h b/Marlin/src/module/ft_motion.h index 497c04e474..a149057547 100644 --- a/Marlin/src/module/ft_motion.h +++ b/Marlin/src/module/ft_motion.h @@ -238,7 +238,7 @@ class FTMotion { static TrajectoryType trajectoryType; static TrajectoryGenerator* currentGenerator; #else - static constexpr TrajectoryGenerator *currentGenerator = trapezoidalGenerator; + static constexpr TrajectoryGenerator *currentGenerator = &trapezoidalGenerator; #endif #if FTM_HAS_LIN_ADVANCE diff --git a/buildroot/tests/STM32F103RC_btt b/buildroot/tests/STM32F103RC_btt index 369fa80978..7a03dd64fa 100755 --- a/buildroot/tests/STM32F103RC_btt +++ b/buildroot/tests/STM32F103RC_btt @@ -17,4 +17,5 @@ opt_enable CR10_STOCKDISPLAY PINS_DEBUGGING Z_IDLE_HEIGHT EDITABLE_HOMING_CURREN 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" +opt_disable FTM_POLYS +exec_test $1 $2 "BigTreeTech SKR Mini E3 1.0 - TMC2209 HW Serial, FT_MOTION w/out FTM_POLYS" "$3" From 19d7cd1a16a2b5305dfc4791f248592a03f366d6 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 7 Dec 2025 00:37:23 +0000 Subject: [PATCH 45/47] [cron] Bump distribution date (2025-12-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 4922561f67..ac5a3a0e0d 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-06" +//#define STRING_DISTRIBUTION_DATE "2025-12-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 4b3d753f0e..2538bc840e 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-06" + #define STRING_DISTRIBUTION_DATE "2025-12-07" #endif /** From 2cee78634cc65b27f588284304e6821f0ad099c1 Mon Sep 17 00:00:00 2001 From: Miguel Risco-Castillo Date: Mon, 8 Dec 2025 20:58:13 -0500 Subject: [PATCH 46/47] =?UTF-8?q?=F0=9F=8E=A8=20e3v2=20->=20dwin=20(#28211?= =?UTF-8?q?)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/MarlinCore.cpp | 6 +++--- Marlin/src/gcode/bedlevel/abl/G29.cpp | 2 +- Marlin/src/gcode/calibrate/G28.cpp | 2 +- Marlin/src/gcode/feature/powerloss/M1000.cpp | 4 ++-- Marlin/src/gcode/stats/M75-M78.cpp | 2 +- Marlin/src/inc/Conditionals-2-LCD.h | 2 +- Marlin/src/lcd/{e3v2 => dwin}/README.md | 0 Marlin/src/lcd/{e3v2 => dwin}/common/dwin_api.cpp | 0 Marlin/src/lcd/{e3v2 => dwin}/common/dwin_api.h | 4 ++-- Marlin/src/lcd/{e3v2 => dwin}/common/dwin_color.h | 0 Marlin/src/lcd/{e3v2 => dwin}/common/dwin_font.h | 0 Marlin/src/lcd/{e3v2 => dwin}/common/dwin_set.h | 0 Marlin/src/lcd/{e3v2 => dwin}/common/encoder.cpp | 2 +- Marlin/src/lcd/{e3v2 => dwin}/common/encoder.h | 2 +- Marlin/src/lcd/{e3v2 => dwin}/common/limits.h | 2 +- Marlin/src/lcd/{e3v2 => dwin}/creality/dwin.cpp | 0 Marlin/src/lcd/{e3v2 => dwin}/creality/dwin.h | 0 Marlin/src/lcd/{e3v2 => dwin}/creality/dwin_lcd.cpp | 2 +- Marlin/src/lcd/{e3v2 => dwin}/creality/dwin_lcd.h | 0 Marlin/src/lcd/{e3v2 => dwin}/jyersui/dwin.cpp | 2 +- Marlin/src/lcd/{e3v2 => dwin}/jyersui/dwin.h | 2 +- Marlin/src/lcd/{e3v2 => dwin}/jyersui/dwin_lcd.cpp | 2 +- Marlin/src/lcd/{e3v2 => dwin}/jyersui/dwin_lcd.h | 2 +- Marlin/src/lcd/{e3v2 => dwin}/marlinui/dwin_lcd.cpp | 2 +- Marlin/src/lcd/{e3v2 => dwin}/marlinui/dwin_lcd.h | 2 +- Marlin/src/lcd/{e3v2 => dwin}/marlinui/dwin_string.cpp | 0 Marlin/src/lcd/{e3v2 => dwin}/marlinui/dwin_string.h | 0 Marlin/src/lcd/{e3v2 => dwin}/marlinui/game.cpp | 2 +- Marlin/src/lcd/{e3v2 => dwin}/marlinui/game.h | 0 .../src/lcd/{e3v2 => dwin}/marlinui/lcdprint_dwin.cpp | 2 +- Marlin/src/lcd/{e3v2 => dwin}/marlinui/lcdprint_dwin.h | 0 Marlin/src/lcd/{e3v2 => dwin}/marlinui/marlinui_dwin.h | 2 +- Marlin/src/lcd/{e3v2 => dwin}/marlinui/ui_common.cpp | 0 .../lcd/{e3v2 => dwin}/marlinui/ui_status_480x272.cpp | 0 Marlin/src/lcd/{e3v2 => dwin}/proui/base64.h | 0 Marlin/src/lcd/{e3v2 => dwin}/proui/bedlevel_tools.cpp | 0 Marlin/src/lcd/{e3v2 => dwin}/proui/bedlevel_tools.h | 0 Marlin/src/lcd/{e3v2 => dwin}/proui/dwin.cpp | 0 Marlin/src/lcd/{e3v2 => dwin}/proui/dwin.h | 0 Marlin/src/lcd/{e3v2 => dwin}/proui/dwin_defines.h | 0 Marlin/src/lcd/{e3v2 => dwin}/proui/dwin_lcd.cpp | 0 Marlin/src/lcd/{e3v2 => dwin}/proui/dwin_lcd.h | 0 Marlin/src/lcd/{e3v2 => dwin}/proui/dwin_popup.cpp | 0 Marlin/src/lcd/{e3v2 => dwin}/proui/dwin_popup.h | 0 Marlin/src/lcd/{e3v2 => dwin}/proui/dwinui.cpp | 0 Marlin/src/lcd/{e3v2 => dwin}/proui/dwinui.h | 0 Marlin/src/lcd/{e3v2 => dwin}/proui/endstop_diag.cpp | 0 Marlin/src/lcd/{e3v2 => dwin}/proui/endstop_diag.h | 0 Marlin/src/lcd/{e3v2 => dwin}/proui/gcode_preview.cpp | 0 Marlin/src/lcd/{e3v2 => dwin}/proui/gcode_preview.h | 0 Marlin/src/lcd/{e3v2 => dwin}/proui/lockscreen.cpp | 0 Marlin/src/lcd/{e3v2 => dwin}/proui/lockscreen.h | 0 Marlin/src/lcd/{e3v2 => dwin}/proui/menus.cpp | 0 Marlin/src/lcd/{e3v2 => dwin}/proui/menus.h | 0 Marlin/src/lcd/{e3v2 => dwin}/proui/meshviewer.cpp | 0 Marlin/src/lcd/{e3v2 => dwin}/proui/meshviewer.h | 0 Marlin/src/lcd/{e3v2 => dwin}/proui/plot.cpp | 0 Marlin/src/lcd/{e3v2 => dwin}/proui/plot.h | 0 Marlin/src/lcd/{e3v2 => dwin}/proui/printstats.cpp | 0 Marlin/src/lcd/{e3v2 => dwin}/proui/printstats.h | 0 Marlin/src/lcd/{e3v2 => dwin}/proui/proui_extui.cpp | 0 Marlin/src/lcd/lcdprint.h | 2 +- Marlin/src/lcd/marlinui.cpp | 4 ++-- Marlin/src/lcd/marlinui.h | 6 +++--- Marlin/src/lcd/menu/game/types.h | 2 +- Marlin/src/module/motion.h | 2 +- Marlin/src/module/settings.cpp | 6 +++--- Marlin/src/module/temperature.cpp | 2 +- Marlin/src/sd/cardreader.cpp | 2 +- ini/features.ini | 10 +++++----- platformio.ini | 2 +- 71 files changed, 43 insertions(+), 43 deletions(-) rename Marlin/src/lcd/{e3v2 => dwin}/README.md (100%) rename Marlin/src/lcd/{e3v2 => dwin}/common/dwin_api.cpp (100%) rename Marlin/src/lcd/{e3v2 => dwin}/common/dwin_api.h (99%) rename Marlin/src/lcd/{e3v2 => dwin}/common/dwin_color.h (100%) rename Marlin/src/lcd/{e3v2 => dwin}/common/dwin_font.h (100%) rename Marlin/src/lcd/{e3v2 => dwin}/common/dwin_set.h (100%) rename Marlin/src/lcd/{e3v2 => dwin}/common/encoder.cpp (99%) rename Marlin/src/lcd/{e3v2 => dwin}/common/encoder.h (98%) rename Marlin/src/lcd/{e3v2 => dwin}/common/limits.h (99%) rename Marlin/src/lcd/{e3v2 => dwin}/creality/dwin.cpp (100%) rename Marlin/src/lcd/{e3v2 => dwin}/creality/dwin.h (100%) rename Marlin/src/lcd/{e3v2 => dwin}/creality/dwin_lcd.cpp (98%) rename Marlin/src/lcd/{e3v2 => dwin}/creality/dwin_lcd.h (100%) rename Marlin/src/lcd/{e3v2 => dwin}/jyersui/dwin.cpp (99%) rename Marlin/src/lcd/{e3v2 => dwin}/jyersui/dwin.h (99%) rename Marlin/src/lcd/{e3v2 => dwin}/jyersui/dwin_lcd.cpp (98%) rename Marlin/src/lcd/{e3v2 => dwin}/jyersui/dwin_lcd.h (96%) rename Marlin/src/lcd/{e3v2 => dwin}/marlinui/dwin_lcd.cpp (98%) rename Marlin/src/lcd/{e3v2 => dwin}/marlinui/dwin_lcd.h (98%) rename Marlin/src/lcd/{e3v2 => dwin}/marlinui/dwin_string.cpp (100%) rename Marlin/src/lcd/{e3v2 => dwin}/marlinui/dwin_string.h (100%) rename Marlin/src/lcd/{e3v2 => dwin}/marlinui/game.cpp (99%) rename Marlin/src/lcd/{e3v2 => dwin}/marlinui/game.h (100%) rename Marlin/src/lcd/{e3v2 => dwin}/marlinui/lcdprint_dwin.cpp (99%) rename Marlin/src/lcd/{e3v2 => dwin}/marlinui/lcdprint_dwin.h (100%) rename Marlin/src/lcd/{e3v2 => dwin}/marlinui/marlinui_dwin.h (99%) rename Marlin/src/lcd/{e3v2 => dwin}/marlinui/ui_common.cpp (100%) rename Marlin/src/lcd/{e3v2 => dwin}/marlinui/ui_status_480x272.cpp (100%) rename Marlin/src/lcd/{e3v2 => dwin}/proui/base64.h (100%) rename Marlin/src/lcd/{e3v2 => dwin}/proui/bedlevel_tools.cpp (100%) rename Marlin/src/lcd/{e3v2 => dwin}/proui/bedlevel_tools.h (100%) rename Marlin/src/lcd/{e3v2 => dwin}/proui/dwin.cpp (100%) rename Marlin/src/lcd/{e3v2 => dwin}/proui/dwin.h (100%) rename Marlin/src/lcd/{e3v2 => dwin}/proui/dwin_defines.h (100%) rename Marlin/src/lcd/{e3v2 => dwin}/proui/dwin_lcd.cpp (100%) rename Marlin/src/lcd/{e3v2 => dwin}/proui/dwin_lcd.h (100%) rename Marlin/src/lcd/{e3v2 => dwin}/proui/dwin_popup.cpp (100%) rename Marlin/src/lcd/{e3v2 => dwin}/proui/dwin_popup.h (100%) rename Marlin/src/lcd/{e3v2 => dwin}/proui/dwinui.cpp (100%) rename Marlin/src/lcd/{e3v2 => dwin}/proui/dwinui.h (100%) rename Marlin/src/lcd/{e3v2 => dwin}/proui/endstop_diag.cpp (100%) rename Marlin/src/lcd/{e3v2 => dwin}/proui/endstop_diag.h (100%) rename Marlin/src/lcd/{e3v2 => dwin}/proui/gcode_preview.cpp (100%) rename Marlin/src/lcd/{e3v2 => dwin}/proui/gcode_preview.h (100%) rename Marlin/src/lcd/{e3v2 => dwin}/proui/lockscreen.cpp (100%) rename Marlin/src/lcd/{e3v2 => dwin}/proui/lockscreen.h (100%) rename Marlin/src/lcd/{e3v2 => dwin}/proui/menus.cpp (100%) rename Marlin/src/lcd/{e3v2 => dwin}/proui/menus.h (100%) rename Marlin/src/lcd/{e3v2 => dwin}/proui/meshviewer.cpp (100%) rename Marlin/src/lcd/{e3v2 => dwin}/proui/meshviewer.h (100%) rename Marlin/src/lcd/{e3v2 => dwin}/proui/plot.cpp (100%) rename Marlin/src/lcd/{e3v2 => dwin}/proui/plot.h (100%) rename Marlin/src/lcd/{e3v2 => dwin}/proui/printstats.cpp (100%) rename Marlin/src/lcd/{e3v2 => dwin}/proui/printstats.h (100%) rename Marlin/src/lcd/{e3v2 => dwin}/proui/proui_extui.cpp (100%) diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 6610e90ab7..6d672e3b8c 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -74,11 +74,11 @@ #endif #if HAS_DWIN_E3V2 - #include "lcd/e3v2/common/encoder.h" + #include "lcd/dwin/common/encoder.h" #if ENABLED(DWIN_CREALITY_LCD) - #include "lcd/e3v2/creality/dwin.h" + #include "lcd/dwin/creality/dwin.h" #elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) - #include "lcd/e3v2/jyersui/dwin.h" + #include "lcd/dwin/jyersui/dwin.h" #elif ENABLED(SOVOL_SV06_RTS) #include "lcd/sovol_rts/sovol_rts.h" #endif diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index 058d4ea4ab..800d51dac6 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -51,7 +51,7 @@ #if ENABLED(EXTENSIBLE_UI) #include "../../../lcd/extui/ui_api.h" #elif ENABLED(DWIN_CREALITY_LCD) - #include "../../../lcd/e3v2/creality/dwin.h" + #include "../../../lcd/dwin/creality/dwin.h" #elif ENABLED(SOVOL_SV06_RTS) #include "../../../lcd/sovol_rts/sovol_rts.h" #endif diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index 4d3d7841e7..4a0ecffc4b 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -61,7 +61,7 @@ #if ENABLED(EXTENSIBLE_UI) #include "../../lcd/extui/ui_api.h" #elif ENABLED(DWIN_CREALITY_LCD) - #include "../../lcd/e3v2/creality/dwin.h" + #include "../../lcd/dwin/creality/dwin.h" #elif ENABLED(SOVOL_SV06_RTS) #include "../../lcd/sovol_rts/sovol_rts.h" #endif diff --git a/Marlin/src/gcode/feature/powerloss/M1000.cpp b/Marlin/src/gcode/feature/powerloss/M1000.cpp index c85817cd3e..15597eac59 100644 --- a/Marlin/src/gcode/feature/powerloss/M1000.cpp +++ b/Marlin/src/gcode/feature/powerloss/M1000.cpp @@ -36,9 +36,9 @@ #if ENABLED(EXTENSIBLE_UI) #include "../../../lcd/extui/ui_api.h" #elif ENABLED(DWIN_CREALITY_LCD) - #include "../../../lcd/e3v2/creality/dwin.h" + #include "../../../lcd/dwin/creality/dwin.h" #elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) - #include "../../../lcd/e3v2/jyersui/dwin.h" // Temporary fix until it can be better implemented + #include "../../../lcd/dwin/jyersui/dwin.h" // Temporary fix until it can be better implemented #endif #define DEBUG_OUT ENABLED(DEBUG_POWER_LOSS_RECOVERY) diff --git a/Marlin/src/gcode/stats/M75-M78.cpp b/Marlin/src/gcode/stats/M75-M78.cpp index 8c7378c977..b539bf30dc 100644 --- a/Marlin/src/gcode/stats/M75-M78.cpp +++ b/Marlin/src/gcode/stats/M75-M78.cpp @@ -30,7 +30,7 @@ #include "../../MarlinCore.h" // for startOrResumeJob #if ENABLED(DWIN_LCD_PROUI) - #include "../../lcd/e3v2/proui/dwin.h" + #include "../../lcd/dwin/proui/dwin.h" #endif /** diff --git a/Marlin/src/inc/Conditionals-2-LCD.h b/Marlin/src/inc/Conditionals-2-LCD.h index 49d8121f0c..72bad45c89 100644 --- a/Marlin/src/inc/Conditionals-2-LCD.h +++ b/Marlin/src/inc/Conditionals-2-LCD.h @@ -570,7 +570,7 @@ #define EXTENSIBLE_UI #endif -// E3V2 extras +// DWIN extras #if ANY(HAS_DWIN_E3V2, IS_DWIN_MARLINUI, SOVOL_SV06_RTS) #define SERIAL_CATCHALL 0 #define HAS_LCD_BRIGHTNESS 1 diff --git a/Marlin/src/lcd/e3v2/README.md b/Marlin/src/lcd/dwin/README.md similarity index 100% rename from Marlin/src/lcd/e3v2/README.md rename to Marlin/src/lcd/dwin/README.md diff --git a/Marlin/src/lcd/e3v2/common/dwin_api.cpp b/Marlin/src/lcd/dwin/common/dwin_api.cpp similarity index 100% rename from Marlin/src/lcd/e3v2/common/dwin_api.cpp rename to Marlin/src/lcd/dwin/common/dwin_api.cpp diff --git a/Marlin/src/lcd/e3v2/common/dwin_api.h b/Marlin/src/lcd/dwin/common/dwin_api.h similarity index 99% rename from Marlin/src/lcd/e3v2/common/dwin_api.h rename to Marlin/src/lcd/dwin/common/dwin_api.h index bf50a78e2f..15c7ba3c94 100644 --- a/Marlin/src/lcd/e3v2/common/dwin_api.h +++ b/Marlin/src/lcd/dwin/common/dwin_api.h @@ -24,9 +24,9 @@ #include "../../../inc/MarlinConfig.h" // -// e3v2/common/dwin_api.h +// dwin/common/dwin_api.h // -// Included by: e3v2/*/dwin_lcd.h +// Included by: dwin/*/dwin_lcd.h // #if ENABLED(DWIN_MARLINUI_LANDSCAPE) diff --git a/Marlin/src/lcd/e3v2/common/dwin_color.h b/Marlin/src/lcd/dwin/common/dwin_color.h similarity index 100% rename from Marlin/src/lcd/e3v2/common/dwin_color.h rename to Marlin/src/lcd/dwin/common/dwin_color.h diff --git a/Marlin/src/lcd/e3v2/common/dwin_font.h b/Marlin/src/lcd/dwin/common/dwin_font.h similarity index 100% rename from Marlin/src/lcd/e3v2/common/dwin_font.h rename to Marlin/src/lcd/dwin/common/dwin_font.h diff --git a/Marlin/src/lcd/e3v2/common/dwin_set.h b/Marlin/src/lcd/dwin/common/dwin_set.h similarity index 100% rename from Marlin/src/lcd/e3v2/common/dwin_set.h rename to Marlin/src/lcd/dwin/common/dwin_set.h diff --git a/Marlin/src/lcd/e3v2/common/encoder.cpp b/Marlin/src/lcd/dwin/common/encoder.cpp similarity index 99% rename from Marlin/src/lcd/e3v2/common/encoder.cpp rename to Marlin/src/lcd/dwin/common/encoder.cpp index 2f050e92fd..8eea288d12 100644 --- a/Marlin/src/lcd/e3v2/common/encoder.cpp +++ b/Marlin/src/lcd/dwin/common/encoder.cpp @@ -21,7 +21,7 @@ */ /***************************************************************************** - * @file lcd/e3v2/common/encoder.cpp + * @file lcd/dwin/common/encoder.cpp * @brief Rotary encoder functions *****************************************************************************/ diff --git a/Marlin/src/lcd/e3v2/common/encoder.h b/Marlin/src/lcd/dwin/common/encoder.h similarity index 98% rename from Marlin/src/lcd/e3v2/common/encoder.h rename to Marlin/src/lcd/dwin/common/encoder.h index 428193ca65..8a8f2fcaa3 100644 --- a/Marlin/src/lcd/e3v2/common/encoder.h +++ b/Marlin/src/lcd/dwin/common/encoder.h @@ -22,7 +22,7 @@ #pragma once /***************************************************************************** - * @file lcd/e3v2/common/encoder.h + * @file lcd/dwin/common/encoder.h * @brief Rotary encoder functions ****************************************************************************/ diff --git a/Marlin/src/lcd/e3v2/common/limits.h b/Marlin/src/lcd/dwin/common/limits.h similarity index 99% rename from Marlin/src/lcd/e3v2/common/limits.h rename to Marlin/src/lcd/dwin/common/limits.h index c773240b28..1e2a77980c 100644 --- a/Marlin/src/lcd/e3v2/common/limits.h +++ b/Marlin/src/lcd/dwin/common/limits.h @@ -22,7 +22,7 @@ #pragma once /***************************************************************************** - * @file lcd/e3v2/common/limits.h + * @file lcd/dwin/common/limits.h * @brief Limits for UI values ****************************************************************************/ diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/dwin/creality/dwin.cpp similarity index 100% rename from Marlin/src/lcd/e3v2/creality/dwin.cpp rename to Marlin/src/lcd/dwin/creality/dwin.cpp diff --git a/Marlin/src/lcd/e3v2/creality/dwin.h b/Marlin/src/lcd/dwin/creality/dwin.h similarity index 100% rename from Marlin/src/lcd/e3v2/creality/dwin.h rename to Marlin/src/lcd/dwin/creality/dwin.h diff --git a/Marlin/src/lcd/e3v2/creality/dwin_lcd.cpp b/Marlin/src/lcd/dwin/creality/dwin_lcd.cpp similarity index 98% rename from Marlin/src/lcd/e3v2/creality/dwin_lcd.cpp rename to Marlin/src/lcd/dwin/creality/dwin_lcd.cpp index 649e1b4771..60c49e8d96 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin_lcd.cpp +++ b/Marlin/src/lcd/dwin/creality/dwin_lcd.cpp @@ -21,7 +21,7 @@ */ /******************************************************************************** - * @file lcd/e3v2/creality/dwin_lcd.cpp + * @file lcd/dwin/creality/dwin_lcd.cpp * @author LEO / Creality3D * @date 2019/07/18 * @version 2.0.1 diff --git a/Marlin/src/lcd/e3v2/creality/dwin_lcd.h b/Marlin/src/lcd/dwin/creality/dwin_lcd.h similarity index 100% rename from Marlin/src/lcd/e3v2/creality/dwin_lcd.h rename to Marlin/src/lcd/dwin/creality/dwin_lcd.h diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/dwin/jyersui/dwin.cpp similarity index 99% rename from Marlin/src/lcd/e3v2/jyersui/dwin.cpp rename to Marlin/src/lcd/dwin/jyersui/dwin.cpp index 2cede088ec..1e8cdb1a55 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/dwin/jyersui/dwin.cpp @@ -21,7 +21,7 @@ */ /** - * lcd/e3v2/jyersui/dwin.cpp + * lcd/dwin/jyersui/dwin.cpp */ #include "../../../inc/MarlinConfigPre.h" diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.h b/Marlin/src/lcd/dwin/jyersui/dwin.h similarity index 99% rename from Marlin/src/lcd/e3v2/jyersui/dwin.h rename to Marlin/src/lcd/dwin/jyersui/dwin.h index 890cc79999..22a56b190c 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.h +++ b/Marlin/src/lcd/dwin/jyersui/dwin.h @@ -22,7 +22,7 @@ #pragma once /** - * lcd/e3v2/jyersui/dwin.h + * lcd/dwin/jyersui/dwin.h */ #include "dwin_lcd.h" diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.cpp b/Marlin/src/lcd/dwin/jyersui/dwin_lcd.cpp similarity index 98% rename from Marlin/src/lcd/e3v2/jyersui/dwin_lcd.cpp rename to Marlin/src/lcd/dwin/jyersui/dwin_lcd.cpp index 96518b8c21..717e17868d 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.cpp +++ b/Marlin/src/lcd/dwin/jyersui/dwin_lcd.cpp @@ -21,7 +21,7 @@ */ /******************************************************************************** - * @file lcd/e3v2/jyersui/dwin_lcd.cpp + * @file lcd/dwin/jyersui/dwin_lcd.cpp * @brief DWIN screen control functions ********************************************************************************/ diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h b/Marlin/src/lcd/dwin/jyersui/dwin_lcd.h similarity index 96% rename from Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h rename to Marlin/src/lcd/dwin/jyersui/dwin_lcd.h index a9335a4f23..124062535a 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin_lcd.h +++ b/Marlin/src/lcd/dwin/jyersui/dwin_lcd.h @@ -22,7 +22,7 @@ #pragma once /******************************************************************************** - * @file lcd/e3v2/jyersui/dwin_lcd.h + * @file lcd/dwin/jyersui/dwin_lcd.h * @brief DWIN screen control functions ********************************************************************************/ diff --git a/Marlin/src/lcd/e3v2/marlinui/dwin_lcd.cpp b/Marlin/src/lcd/dwin/marlinui/dwin_lcd.cpp similarity index 98% rename from Marlin/src/lcd/e3v2/marlinui/dwin_lcd.cpp rename to Marlin/src/lcd/dwin/marlinui/dwin_lcd.cpp index 13c6de5480..49d660d843 100644 --- a/Marlin/src/lcd/e3v2/marlinui/dwin_lcd.cpp +++ b/Marlin/src/lcd/dwin/marlinui/dwin_lcd.cpp @@ -21,7 +21,7 @@ */ /******************************************************************************** - * @file lcd/e3v2/marlinui/dwin_lcd.cpp + * @file lcd/dwin/marlinui/dwin_lcd.cpp * @brief DWIN screen control functions ********************************************************************************/ diff --git a/Marlin/src/lcd/e3v2/marlinui/dwin_lcd.h b/Marlin/src/lcd/dwin/marlinui/dwin_lcd.h similarity index 98% rename from Marlin/src/lcd/e3v2/marlinui/dwin_lcd.h rename to Marlin/src/lcd/dwin/marlinui/dwin_lcd.h index ef81a7df77..3b308a7020 100644 --- a/Marlin/src/lcd/e3v2/marlinui/dwin_lcd.h +++ b/Marlin/src/lcd/dwin/marlinui/dwin_lcd.h @@ -22,7 +22,7 @@ #pragma once /******************************************************************************** - * @file lcd/e3v2/marlinui/dwin_lcd.h + * @file lcd/dwin/marlinui/dwin_lcd.h * @brief DWIN screen control functions ********************************************************************************/ diff --git a/Marlin/src/lcd/e3v2/marlinui/dwin_string.cpp b/Marlin/src/lcd/dwin/marlinui/dwin_string.cpp similarity index 100% rename from Marlin/src/lcd/e3v2/marlinui/dwin_string.cpp rename to Marlin/src/lcd/dwin/marlinui/dwin_string.cpp diff --git a/Marlin/src/lcd/e3v2/marlinui/dwin_string.h b/Marlin/src/lcd/dwin/marlinui/dwin_string.h similarity index 100% rename from Marlin/src/lcd/e3v2/marlinui/dwin_string.h rename to Marlin/src/lcd/dwin/marlinui/dwin_string.h diff --git a/Marlin/src/lcd/e3v2/marlinui/game.cpp b/Marlin/src/lcd/dwin/marlinui/game.cpp similarity index 99% rename from Marlin/src/lcd/e3v2/marlinui/game.cpp rename to Marlin/src/lcd/dwin/marlinui/game.cpp index eb15bd8108..b77c72664f 100644 --- a/Marlin/src/lcd/e3v2/marlinui/game.cpp +++ b/Marlin/src/lcd/dwin/marlinui/game.cpp @@ -26,7 +26,7 @@ // Enable performance counters (draw call count, frame timing) for debugging //#define GAME_PERFORMANCE_COUNTERS -#include "../../menu/game/types.h" // includes e3v2/marlinui/game.h +#include "../../menu/game/types.h" // includes dwin/marlinui/game.h #include "../../lcdprint.h" #include "lcdprint_dwin.h" #include "marlinui_dwin.h" diff --git a/Marlin/src/lcd/e3v2/marlinui/game.h b/Marlin/src/lcd/dwin/marlinui/game.h similarity index 100% rename from Marlin/src/lcd/e3v2/marlinui/game.h rename to Marlin/src/lcd/dwin/marlinui/game.h diff --git a/Marlin/src/lcd/e3v2/marlinui/lcdprint_dwin.cpp b/Marlin/src/lcd/dwin/marlinui/lcdprint_dwin.cpp similarity index 99% rename from Marlin/src/lcd/e3v2/marlinui/lcdprint_dwin.cpp rename to Marlin/src/lcd/dwin/marlinui/lcdprint_dwin.cpp index d13ec2e779..a1c7ba2094 100644 --- a/Marlin/src/lcd/e3v2/marlinui/lcdprint_dwin.cpp +++ b/Marlin/src/lcd/dwin/marlinui/lcdprint_dwin.cpp @@ -21,7 +21,7 @@ */ /** - * lcd/e3v2/marlinui/lcdprint_dwin.cpp + * lcd/dwin/marlinui/lcdprint_dwin.cpp * * Due to DWIN hardware limitations simplified characters are used */ diff --git a/Marlin/src/lcd/e3v2/marlinui/lcdprint_dwin.h b/Marlin/src/lcd/dwin/marlinui/lcdprint_dwin.h similarity index 100% rename from Marlin/src/lcd/e3v2/marlinui/lcdprint_dwin.h rename to Marlin/src/lcd/dwin/marlinui/lcdprint_dwin.h diff --git a/Marlin/src/lcd/e3v2/marlinui/marlinui_dwin.h b/Marlin/src/lcd/dwin/marlinui/marlinui_dwin.h similarity index 99% rename from Marlin/src/lcd/e3v2/marlinui/marlinui_dwin.h rename to Marlin/src/lcd/dwin/marlinui/marlinui_dwin.h index b8913914dd..eb25ecd362 100644 --- a/Marlin/src/lcd/e3v2/marlinui/marlinui_dwin.h +++ b/Marlin/src/lcd/dwin/marlinui/marlinui_dwin.h @@ -22,7 +22,7 @@ #pragma once /** - * lcd/e3v2/marlinui/lcdprint_dwin.h + * lcd/dwin/marlinui/lcdprint_dwin.h */ #include "../../../inc/MarlinConfigPre.h" diff --git a/Marlin/src/lcd/e3v2/marlinui/ui_common.cpp b/Marlin/src/lcd/dwin/marlinui/ui_common.cpp similarity index 100% rename from Marlin/src/lcd/e3v2/marlinui/ui_common.cpp rename to Marlin/src/lcd/dwin/marlinui/ui_common.cpp diff --git a/Marlin/src/lcd/e3v2/marlinui/ui_status_480x272.cpp b/Marlin/src/lcd/dwin/marlinui/ui_status_480x272.cpp similarity index 100% rename from Marlin/src/lcd/e3v2/marlinui/ui_status_480x272.cpp rename to Marlin/src/lcd/dwin/marlinui/ui_status_480x272.cpp diff --git a/Marlin/src/lcd/e3v2/proui/base64.h b/Marlin/src/lcd/dwin/proui/base64.h similarity index 100% rename from Marlin/src/lcd/e3v2/proui/base64.h rename to Marlin/src/lcd/dwin/proui/base64.h diff --git a/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp b/Marlin/src/lcd/dwin/proui/bedlevel_tools.cpp similarity index 100% rename from Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp rename to Marlin/src/lcd/dwin/proui/bedlevel_tools.cpp diff --git a/Marlin/src/lcd/e3v2/proui/bedlevel_tools.h b/Marlin/src/lcd/dwin/proui/bedlevel_tools.h similarity index 100% rename from Marlin/src/lcd/e3v2/proui/bedlevel_tools.h rename to Marlin/src/lcd/dwin/proui/bedlevel_tools.h diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/dwin/proui/dwin.cpp similarity index 100% rename from Marlin/src/lcd/e3v2/proui/dwin.cpp rename to Marlin/src/lcd/dwin/proui/dwin.cpp diff --git a/Marlin/src/lcd/e3v2/proui/dwin.h b/Marlin/src/lcd/dwin/proui/dwin.h similarity index 100% rename from Marlin/src/lcd/e3v2/proui/dwin.h rename to Marlin/src/lcd/dwin/proui/dwin.h diff --git a/Marlin/src/lcd/e3v2/proui/dwin_defines.h b/Marlin/src/lcd/dwin/proui/dwin_defines.h similarity index 100% rename from Marlin/src/lcd/e3v2/proui/dwin_defines.h rename to Marlin/src/lcd/dwin/proui/dwin_defines.h diff --git a/Marlin/src/lcd/e3v2/proui/dwin_lcd.cpp b/Marlin/src/lcd/dwin/proui/dwin_lcd.cpp similarity index 100% rename from Marlin/src/lcd/e3v2/proui/dwin_lcd.cpp rename to Marlin/src/lcd/dwin/proui/dwin_lcd.cpp diff --git a/Marlin/src/lcd/e3v2/proui/dwin_lcd.h b/Marlin/src/lcd/dwin/proui/dwin_lcd.h similarity index 100% rename from Marlin/src/lcd/e3v2/proui/dwin_lcd.h rename to Marlin/src/lcd/dwin/proui/dwin_lcd.h diff --git a/Marlin/src/lcd/e3v2/proui/dwin_popup.cpp b/Marlin/src/lcd/dwin/proui/dwin_popup.cpp similarity index 100% rename from Marlin/src/lcd/e3v2/proui/dwin_popup.cpp rename to Marlin/src/lcd/dwin/proui/dwin_popup.cpp diff --git a/Marlin/src/lcd/e3v2/proui/dwin_popup.h b/Marlin/src/lcd/dwin/proui/dwin_popup.h similarity index 100% rename from Marlin/src/lcd/e3v2/proui/dwin_popup.h rename to Marlin/src/lcd/dwin/proui/dwin_popup.h diff --git a/Marlin/src/lcd/e3v2/proui/dwinui.cpp b/Marlin/src/lcd/dwin/proui/dwinui.cpp similarity index 100% rename from Marlin/src/lcd/e3v2/proui/dwinui.cpp rename to Marlin/src/lcd/dwin/proui/dwinui.cpp diff --git a/Marlin/src/lcd/e3v2/proui/dwinui.h b/Marlin/src/lcd/dwin/proui/dwinui.h similarity index 100% rename from Marlin/src/lcd/e3v2/proui/dwinui.h rename to Marlin/src/lcd/dwin/proui/dwinui.h diff --git a/Marlin/src/lcd/e3v2/proui/endstop_diag.cpp b/Marlin/src/lcd/dwin/proui/endstop_diag.cpp similarity index 100% rename from Marlin/src/lcd/e3v2/proui/endstop_diag.cpp rename to Marlin/src/lcd/dwin/proui/endstop_diag.cpp diff --git a/Marlin/src/lcd/e3v2/proui/endstop_diag.h b/Marlin/src/lcd/dwin/proui/endstop_diag.h similarity index 100% rename from Marlin/src/lcd/e3v2/proui/endstop_diag.h rename to Marlin/src/lcd/dwin/proui/endstop_diag.h diff --git a/Marlin/src/lcd/e3v2/proui/gcode_preview.cpp b/Marlin/src/lcd/dwin/proui/gcode_preview.cpp similarity index 100% rename from Marlin/src/lcd/e3v2/proui/gcode_preview.cpp rename to Marlin/src/lcd/dwin/proui/gcode_preview.cpp diff --git a/Marlin/src/lcd/e3v2/proui/gcode_preview.h b/Marlin/src/lcd/dwin/proui/gcode_preview.h similarity index 100% rename from Marlin/src/lcd/e3v2/proui/gcode_preview.h rename to Marlin/src/lcd/dwin/proui/gcode_preview.h diff --git a/Marlin/src/lcd/e3v2/proui/lockscreen.cpp b/Marlin/src/lcd/dwin/proui/lockscreen.cpp similarity index 100% rename from Marlin/src/lcd/e3v2/proui/lockscreen.cpp rename to Marlin/src/lcd/dwin/proui/lockscreen.cpp diff --git a/Marlin/src/lcd/e3v2/proui/lockscreen.h b/Marlin/src/lcd/dwin/proui/lockscreen.h similarity index 100% rename from Marlin/src/lcd/e3v2/proui/lockscreen.h rename to Marlin/src/lcd/dwin/proui/lockscreen.h diff --git a/Marlin/src/lcd/e3v2/proui/menus.cpp b/Marlin/src/lcd/dwin/proui/menus.cpp similarity index 100% rename from Marlin/src/lcd/e3v2/proui/menus.cpp rename to Marlin/src/lcd/dwin/proui/menus.cpp diff --git a/Marlin/src/lcd/e3v2/proui/menus.h b/Marlin/src/lcd/dwin/proui/menus.h similarity index 100% rename from Marlin/src/lcd/e3v2/proui/menus.h rename to Marlin/src/lcd/dwin/proui/menus.h diff --git a/Marlin/src/lcd/e3v2/proui/meshviewer.cpp b/Marlin/src/lcd/dwin/proui/meshviewer.cpp similarity index 100% rename from Marlin/src/lcd/e3v2/proui/meshviewer.cpp rename to Marlin/src/lcd/dwin/proui/meshviewer.cpp diff --git a/Marlin/src/lcd/e3v2/proui/meshviewer.h b/Marlin/src/lcd/dwin/proui/meshviewer.h similarity index 100% rename from Marlin/src/lcd/e3v2/proui/meshviewer.h rename to Marlin/src/lcd/dwin/proui/meshviewer.h diff --git a/Marlin/src/lcd/e3v2/proui/plot.cpp b/Marlin/src/lcd/dwin/proui/plot.cpp similarity index 100% rename from Marlin/src/lcd/e3v2/proui/plot.cpp rename to Marlin/src/lcd/dwin/proui/plot.cpp diff --git a/Marlin/src/lcd/e3v2/proui/plot.h b/Marlin/src/lcd/dwin/proui/plot.h similarity index 100% rename from Marlin/src/lcd/e3v2/proui/plot.h rename to Marlin/src/lcd/dwin/proui/plot.h diff --git a/Marlin/src/lcd/e3v2/proui/printstats.cpp b/Marlin/src/lcd/dwin/proui/printstats.cpp similarity index 100% rename from Marlin/src/lcd/e3v2/proui/printstats.cpp rename to Marlin/src/lcd/dwin/proui/printstats.cpp diff --git a/Marlin/src/lcd/e3v2/proui/printstats.h b/Marlin/src/lcd/dwin/proui/printstats.h similarity index 100% rename from Marlin/src/lcd/e3v2/proui/printstats.h rename to Marlin/src/lcd/dwin/proui/printstats.h diff --git a/Marlin/src/lcd/e3v2/proui/proui_extui.cpp b/Marlin/src/lcd/dwin/proui/proui_extui.cpp similarity index 100% rename from Marlin/src/lcd/e3v2/proui/proui_extui.cpp rename to Marlin/src/lcd/dwin/proui/proui_extui.cpp diff --git a/Marlin/src/lcd/lcdprint.h b/Marlin/src/lcd/lcdprint.h index ef50fb823e..50f1074655 100644 --- a/Marlin/src/lcd/lcdprint.h +++ b/Marlin/src/lcd/lcdprint.h @@ -36,7 +36,7 @@ #if IS_DWIN_MARLINUI - #include "e3v2/marlinui/marlinui_dwin.h" + #include "dwin/marlinui/marlinui_dwin.h" // The DWIN lcd_moveto function uses row / column, not pixels #define LCD_COL_X(col) (col) diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index b9f7749c97..b22023a056 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -46,9 +46,9 @@ MarlinUI ui; #endif #if ENABLED(DWIN_CREALITY_LCD) - #include "e3v2/creality/dwin.h" + #include "dwin/creality/dwin.h" #elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) - #include "e3v2/jyersui/dwin.h" + #include "dwin/jyersui/dwin.h" #elif ENABLED(SOVOL_SV06_RTS) #include "sovol_rts/sovol_rts.h" #endif diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index 94a333629a..a3a3ae28f0 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -48,13 +48,13 @@ #endif #if ENABLED(DWIN_CREALITY_LCD) - #include "e3v2/creality/dwin.h" + #include "dwin/creality/dwin.h" #elif ENABLED(DWIN_LCD_PROUI) - #include "e3v2/proui/dwin.h" + #include "dwin/proui/dwin.h" #endif #if ALL(HAS_STATUS_MESSAGE, IS_DWIN_MARLINUI) - #include "e3v2/marlinui/marlinui_dwin.h" // for LCD_WIDTH + #include "dwin/marlinui/marlinui_dwin.h" // for LCD_WIDTH #endif typedef bool (*statusResetFunc_t)(); diff --git a/Marlin/src/lcd/menu/game/types.h b/Marlin/src/lcd/menu/game/types.h index a12d134d38..c19c60dd69 100644 --- a/Marlin/src/lcd/menu/game/types.h +++ b/Marlin/src/lcd/menu/game/types.h @@ -27,7 +27,7 @@ #if HAS_MARLINUI_U8GLIB #include "../../dogm/game.h" #elif IS_DWIN_MARLINUI - #include "../../e3v2/marlinui/game.h" + #include "../../dwin/marlinui/game.h" #endif typedef struct { int8_t x, y; } pos_t; diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index fbce0166a9..8050e66448 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -31,7 +31,7 @@ #include "../inc/MarlinConfig.h" #if ALL(DWIN_LCD_PROUI, INDIVIDUAL_AXIS_HOMING_SUBMENU, MESH_BED_LEVELING) - #include "../lcd/e3v2/proui/dwin.h" // for Z_POST_CLEARANCE + #include "../lcd/dwin/proui/dwin.h" // for Z_POST_CLEARANCE #endif #if IS_SCARA diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index e7ce0204c7..e48b215b77 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -79,14 +79,14 @@ #endif #if ENABLED(DWIN_LCD_PROUI) - #include "../lcd/e3v2/proui/dwin.h" - #include "../lcd/e3v2/proui/bedlevel_tools.h" + #include "../lcd/dwin/proui/dwin.h" + #include "../lcd/dwin/proui/bedlevel_tools.h" #endif #if ENABLED(EXTENSIBLE_UI) #include "../lcd/extui/ui_api.h" #elif ENABLED(DWIN_CREALITY_LCD_JYERSUI) - #include "../lcd/e3v2/jyersui/dwin.h" + #include "../lcd/dwin/jyersui/dwin.h" #endif #if ENABLED(HOST_PROMPT_SUPPORT) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 819133f30d..f0ca49ef66 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -51,7 +51,7 @@ #endif #if ENABLED(DWIN_CREALITY_LCD) - #include "../lcd/e3v2/creality/dwin.h" + #include "../lcd/dwin/creality/dwin.h" #elif ENABLED(SOVOL_SV06_RTS) #include "../lcd/sovol_rts/sovol_rts.h" #endif diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 1fb12f44a2..98b44e5d14 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -36,7 +36,7 @@ #include "../lcd/marlinui.h" #if ENABLED(DWIN_CREALITY_LCD) - #include "../lcd/e3v2/creality/dwin.h" + #include "../lcd/dwin/creality/dwin.h" #elif ENABLED(SOVOL_SV06_RTS) #include "../lcd/sovol_rts/sovol_rts.h" #endif diff --git a/ini/features.ini b/ini/features.ini index d9b0928237..03a9bdbba8 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -47,11 +47,11 @@ HAS_(FSMC|SPI|LTDC)_TFT = build_src_filter=+ I2C_EEPROM = build_src_filter=+ SOFT_I2C_EEPROM|U8G_USES_SW_I2C = SlowSoftI2CMaster, SlowSoftWire=https://github.com/felias-fogg/SlowSoftWire/archive/f34d777f39.zip SPI_EEPROM = build_src_filter=+ -HAS_DWIN_E3V2|IS_DWIN_MARLINUI = build_src_filter=+ -DWIN_CREALITY_LCD = build_src_filter=+ -DWIN_LCD_PROUI = build_src_filter=+ -DWIN_CREALITY_LCD_JYERSUI = build_src_filter=+ -IS_DWIN_MARLINUI = build_src_filter=+ +HAS_DWIN_E3V2|IS_DWIN_MARLINUI = build_src_filter=+ +DWIN_CREALITY_LCD = build_src_filter=+ +DWIN_LCD_PROUI = build_src_filter=+ +DWIN_CREALITY_LCD_JYERSUI = build_src_filter=+ +IS_DWIN_MARLINUI = build_src_filter=+ SOVOL_SV06_RTS = build_src_filter=+ HAS_GRAPHICAL_TFT = build_src_filter=+ - - HAS_UI_320X.+ = build_src_filter=+ diff --git a/platformio.ini b/platformio.ini index df5418cde4..995c29ca17 100644 --- a/platformio.ini +++ b/platformio.ini @@ -58,7 +58,7 @@ lib_deps = default_src_filter = + - - ; LCDs and Controllers - - - - - - - - - - - + - - - - - - ; Marlin HAL - From 0e5a4cacf8262e503fdc6c2347b7cd0aef9f0f86 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 8 Dec 2025 21:04:01 -0600 Subject: [PATCH 47/47] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Remov?= =?UTF-8?q?e=20unused=20servo=20fields?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/TEENSY31_32/Servo.h | 2 -- Marlin/src/HAL/TEENSY35_36/Servo.h | 2 -- Marlin/src/HAL/TEENSY40_41/Servo.h | 2 -- 3 files changed, 6 deletions(-) diff --git a/Marlin/src/HAL/TEENSY31_32/Servo.h b/Marlin/src/HAL/TEENSY31_32/Servo.h index 82b601d956..2da74fd25d 100644 --- a/Marlin/src/HAL/TEENSY31_32/Servo.h +++ b/Marlin/src/HAL/TEENSY31_32/Servo.h @@ -31,7 +31,5 @@ class libServo : public Servo { void move(const int value); private: typedef Servo super; - uint16_t min_ticks; - uint16_t max_ticks; uint8_t servoIndex; // index into the channel data for this servo }; diff --git a/Marlin/src/HAL/TEENSY35_36/Servo.h b/Marlin/src/HAL/TEENSY35_36/Servo.h index 719011f102..c37567a813 100644 --- a/Marlin/src/HAL/TEENSY35_36/Servo.h +++ b/Marlin/src/HAL/TEENSY35_36/Servo.h @@ -35,7 +35,5 @@ class libServo : public Servo { void move(const int value); private: typedef Servo super; - uint16_t min_ticks; - uint16_t max_ticks; uint8_t servoIndex; // Index into the channel data for this servo }; diff --git a/Marlin/src/HAL/TEENSY40_41/Servo.h b/Marlin/src/HAL/TEENSY40_41/Servo.h index 699fd700c9..fceb9465ea 100644 --- a/Marlin/src/HAL/TEENSY40_41/Servo.h +++ b/Marlin/src/HAL/TEENSY40_41/Servo.h @@ -37,7 +37,5 @@ class libServo : public PWMServo { private: typedef PWMServo super; uint8_t servoPin; - uint16_t min_ticks; - uint16_t max_ticks; uint8_t servoIndex; // Index into the channel data for this servo };