diff --git a/.gitignore b/.gitignore old mode 100755 new mode 100644 diff --git a/Makefile b/Makefile index 97441dc856..68c522e5b6 100644 --- a/Makefile +++ b/Makefile @@ -7,7 +7,7 @@ UNIT_TEST_CONFIG ?= default # Find a Python 3 interpreter ifeq ($(OS),Windows_NT) # Windows: use `where` – fall back through the three common names - PYTHON := $(shell where python 2>nul || where python3 2>nul || where py 2>nul) + PYTHON := $(shell which python 2>nul || which python3 2>nul || which py 2>nul) # Windows: Use cmd tools to find pins files PINS_RAW := $(shell cmd //c "dir /s /b Marlin\src\pins\*.h 2>nul | findstr /r ".*Marlin\\\\src\\\\pins\\\\.*\\\\pins_.*\.h"") PINS := $(subst \,/,$(PINS_RAW)) @@ -66,6 +66,9 @@ marlin: ./buildroot/bin/mftest -a .PHONY: marlin +clean: + rm -rf .pio/build* + tests-single-ci: export GIT_RESET_HARD=true $(MAKE) tests-single-local TEST_TARGET=$(TEST_TARGET) PLATFORMIO_BUILD_FLAGS=-DGITHUB_ACTION diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 122a7a458d..f1feb94688 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1212,7 +1212,7 @@ #define FTM_BATCH_SIZE 100 // Custom Batch size for trajectory generation needed by Ulendo FBS #endif - #define FTM_FS 1000 // (Hz) Frequency for trajectory generation. (Reciprocal of FTM_TS) + #define FTM_FS 1000 // (Hz) Frequency for trajectory generation #if DISABLED(COREXY) #define FTM_STEPPER_FS 20000 // (Hz) Frequency for stepper I/O update diff --git a/Marlin/Version.h b/Marlin/Version.h index 87d1def5b0..650b942c08 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2025-10-19" +//#define STRING_DISTRIBUTION_DATE "2025-10-29" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/config.ini b/Marlin/config.ini index d6d2395e39..fd2b81062a 100644 --- a/Marlin/config.ini +++ b/Marlin/config.ini @@ -86,13 +86,14 @@ heater_0_maxtemp = 275 pidtemp = on pid_k1 = 0.95 pid_max = 255 -pid_functional_range = 10 +pid_functional_range = 20 default_kp = 22.20 default_ki = 1.08 default_kd = 114.00 temp_sensor_bed = 1 +bed_check_interval = 5000 bed_mintemp = 5 bed_maxtemp = 150 @@ -163,18 +164,28 @@ min_steps_per_segment = 6 default_minsegmenttime = 20000 [config:basic] +hotend_overshoot = 15 bed_overshoot = 10 +max_bed_power = 255 + busy_while_heating = on +host_keepalive_feature = on default_keepalive_interval = 2 +printjob_timer_autostart = on + +jd_handle_small_segments = on +validate_homing_endstops = on +editable_steps_per_unit = on + eeprom_boot_silent = on eeprom_chitchat = on + endstoppullups = on -extrude_maxlength = 200 + +prevent_cold_extrusion = on extrude_mintemp = 170 -host_keepalive_feature = on -hotend_overshoot = 15 -jd_handle_small_segments = on -max_bed_power = 255 +prevent_lengthy_extrude = on +extrude_maxlength = 200 min_software_endstops = on max_software_endstops = on @@ -195,21 +206,19 @@ preheat_2_temp_hotend = 240 preheat_2_temp_bed = 110 preheat_2_fan_speed = 0 -prevent_cold_extrusion = on -prevent_lengthy_extrude = on -printjob_timer_autostart = on - temp_bed_hysteresis = 3 temp_bed_residency_time = 10 temp_bed_window = 1 temp_residency_time = 10 temp_window = 1 -validate_homing_endstops = on - -editable_steps_per_unit = on [config:advanced] arc_support = on +min_arc_segment_mm = 0.1 +max_arc_segment_mm = 1.0 +min_circle_segments = 72 +n_arc_correction = 25 + auto_report_temperatures = on autotemp = on @@ -223,22 +232,23 @@ disable_idle_x = on disable_idle_y = on disable_idle_z = on disable_idle_e = on + e0_auto_fan_pin = -1 + faster_gcode_parser = on debug_flags_gcode = on + homing_bump_mm = { 5, 5, 2 } -max_arc_segment_mm = 1.0 -min_arc_segment_mm = 0.1 -min_circle_segments = 72 -n_arc_correction = 25 -serial_overrun_protection = on + slowdown = on slowdown_divisor = 2 -tx_buffer_size = 0 +multistepping_limit = 16 -bed_check_interval = 5000 -watch_bed_temp_increase = 2 -watch_bed_temp_period = 60 +serial_overrun_protection = on +tx_buffer_size = 0 watch_temp_increase = 2 watch_temp_period = 40 + +watch_bed_temp_increase = 2 +watch_bed_temp_period = 60 diff --git a/Marlin/src/HAL/AVR/fastio.cpp b/Marlin/src/HAL/AVR/fastio.cpp index 7d46afadcb..98fd636ebf 100644 --- a/Marlin/src/HAL/AVR/fastio.cpp +++ b/Marlin/src/HAL/AVR/fastio.cpp @@ -254,7 +254,7 @@ uint16_t set_pwm_frequency_hz(const float hz, const float dca, const float dcb, else { prescaler = 1; SET_CS(5, PRESCALER_1); } count /= float(prescaler); - const float pwm_top = round(count); // Get the rounded count + const float pwm_top = roundf(count); // Get the rounded count ICR5 = (uint16_t)pwm_top - 1; // Subtract 1 for TOP OCR5A = pwm_top * ABS(dca); // Update and scale DCs @@ -280,7 +280,7 @@ uint16_t set_pwm_frequency_hz(const float hz, const float dca, const float dcb, SET_CS(5, PRESCALER_64); // 16MHz / 64 = 250kHz OCR5A = OCR5B = OCR5C = 0; } - return round(count); + return roundf(count); } #endif diff --git a/Marlin/src/HAL/AVR/inc/SanityCheck.h b/Marlin/src/HAL/AVR/inc/SanityCheck.h index 85ee683685..08fe21d4f8 100644 --- a/Marlin/src/HAL/AVR/inc/SanityCheck.h +++ b/Marlin/src/HAL/AVR/inc/SanityCheck.h @@ -95,7 +95,7 @@ /** * The Trinamic library includes SoftwareSerial.h, leading to a compile error. */ -#if ALL(HAS_TRINAMIC_CONFIG, ENDSTOP_INTERRUPTS_FEATURE) +#if ALL(HAS_TMC_SW_SERIAL, ENDSTOP_INTERRUPTS_FEATURE) #error "TMCStepper includes SoftwareSerial.h which is incompatible with ENDSTOP_INTERRUPTS_FEATURE. Disable ENDSTOP_INTERRUPTS_FEATURE to continue." #endif diff --git a/Marlin/src/HAL/AVR/registers.h b/Marlin/src/HAL/AVR/registers.h index 64c0955c3e..0eac4888cd 100644 --- a/Marlin/src/HAL/AVR/registers.h +++ b/Marlin/src/HAL/AVR/registers.h @@ -93,15 +93,15 @@ namespace AVRHelpers { typedef T type; }; template - struct voltype { + struct voltype { typedef uint8_t type; }; template - struct voltype { + struct voltype { typedef uint16_t type; }; template - struct voltype { + struct voltype { typedef uint32_t type; }; @@ -2007,7 +2007,7 @@ inline void _ATmega_resetperipherals() { #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM05__) _EEAR._EEAR = 0; - dwrite(_EEDR, (uint8_t)0u); + dwrite(_EEDR, (uint8_t)0U); #endif #if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__) diff --git a/Marlin/src/HAL/AVR/timers.h b/Marlin/src/HAL/AVR/timers.h index 94b17f3102..0e1d7f2ba3 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 0xFFFF +#define HAL_TIMER_TYPE_MAX 0xFFFFU // ------------------------ // Defines diff --git a/Marlin/src/HAL/DUE/timers.h b/Marlin/src/HAL/DUE/timers.h index db5d83a06f..9316552ff5 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 0xFFFFFFFF +#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFUL #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/HAL.h b/Marlin/src/HAL/ESP32/HAL.h index baa03d8a76..36b8ea53fc 100644 --- a/Marlin/src/HAL/ESP32/HAL.h +++ b/Marlin/src/HAL/ESP32/HAL.h @@ -64,10 +64,10 @@ #define CRITICAL_SECTION_END() portEXIT_CRITICAL(&hal.spinlock) #define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment -#define PWM_FREQUENCY 1000u // Default PWM frequency when set_pwm_duty() is called without set_pwm_frequency() -#define PWM_RESOLUTION 10u // Default PWM bit resolution -#define CHANNEL_MAX_NUM 15u // max PWM channel # to allocate (7 to only use low speed, 15 to use low & high) -#define MAX_PWM_IOPIN 33u // hardware pwm pins < 34 +#define PWM_FREQUENCY 1000U // Default PWM frequency when set_pwm_duty() is called without set_pwm_frequency() +#define PWM_RESOLUTION 10U // Default PWM bit resolution +#define CHANNEL_MAX_NUM 15U // max PWM channel # to allocate (7 to only use low speed, 15 to use low & high) +#define MAX_PWM_IOPIN 33U // hardware pwm pins < 34 #ifndef MAX_EXPANDER_BITS #define MAX_EXPANDER_BITS 32 // I2S expander bit width (max 32) #endif diff --git a/Marlin/src/HAL/ESP32/Servo.cpp b/Marlin/src/HAL/ESP32/Servo.cpp index ca3950d07f..3a2c11832d 100644 --- a/Marlin/src/HAL/ESP32/Servo.cpp +++ b/Marlin/src/HAL/ESP32/Servo.cpp @@ -35,7 +35,7 @@ Servo::Servo() {} int8_t Servo::attach(const int inPin) { if (inPin > 0) pin = inPin; - channel = get_pwm_channel(pin, 50u, 16u); + channel = get_pwm_channel(pin, 50U, 16U); return channel; // -1 if no PWM avail. } diff --git a/Marlin/src/HAL/ESP32/timers.h b/Marlin/src/HAL/ESP32/timers.h index 3f336fbfc9..03c343af98 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 0xFFFFFFFFFFFFFFFFULL +#define HAL_TIMER_TYPE_MAX 0xFFFF'FFFF'FFFF'FFFFULL #ifndef MF_TIMER_STEP #define MF_TIMER_STEP 0 // Timer Index for Stepper @@ -52,12 +52,12 @@ typedef uint64_t hal_timer_t; #if ENABLED(I2S_STEPPER_STREAM) #define STEPPER_TIMER_PRESCALE 1 - #define STEPPER_TIMER_RATE 250000 // 250khz, 4µs pulses of i2s word clock + #define STEPPER_TIMER_RATE 250'000 // 250khz, 4µs pulses of i2s word clock #else #define STEPPER_TIMER_PRESCALE 40 #define STEPPER_TIMER_RATE ((HAL_TIMER_RATE) / (STEPPER_TIMER_PRESCALE)) // frequency of stepper timer, 2MHz #endif -#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs +#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 diff --git a/Marlin/src/HAL/GD32_MFL/temp_soc.h b/Marlin/src/HAL/GD32_MFL/temp_soc.h index 5f1be64e43..bd78fba5b9 100644 --- a/Marlin/src/HAL/GD32_MFL/temp_soc.h +++ b/Marlin/src/HAL/GD32_MFL/temp_soc.h @@ -26,4 +26,4 @@ #define TS_TYPICAL_SLOPE 4.5 // TODO: Implement voltage scaling (calibrated Vrefint) and ADC resolution scaling (when applicable) -#define TEMP_SOC_SENSOR(RAW) ((TS_TYPICAL_V - (RAW) / float(OVERSAMPLENR) / float(HAL_ADC_RANGE) * (float(ADC_VREF_MV) / 1000.0f)) / ((TS_TYPICAL_SLOPE) / 1000.0f) + TS_TYPICAL_TEMP) +#define TEMP_SOC_SENSOR(RAW) ((TS_TYPICAL_V - (RAW) / float(OVERSAMPLENR) / float(HAL_ADC_RANGE) * (float(ADC_VREF_MV) * 0.001f)) / ((TS_TYPICAL_SLOPE) * 0.001f) + TS_TYPICAL_TEMP) diff --git a/Marlin/src/HAL/HC32/timers.h b/Marlin/src/HAL/HC32/timers.h index e5ab3f21f5..d03a5f9630 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 0xFFFF +#define HAL_TIMER_TYPE_MAX 0xFFFFU // // Timer instances diff --git a/Marlin/src/HAL/LINUX/timers.h b/Marlin/src/HAL/LINUX/timers.h index 2b29edce0b..d75519ed3e 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 0xFFFFFFFF +#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFUL #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 bae01703ed..8c0a39158e 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 0xFFFFFFFF +#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFUL #define HAL_TIMER_RATE ((F_CPU) / 4) // frequency of timers peripherals diff --git a/Marlin/src/HAL/NATIVE_SIM/timers.h b/Marlin/src/HAL/NATIVE_SIM/timers.h index d46e8e7b94..43aecf427b 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 0xFFFFFFFFFFFFFFFF +#define HAL_TIMER_TYPE_MAX 0xFFFF'FFFF'FFFF'FFFFULL #define HAL_TIMER_RATE ((SystemCoreClock) / 4) // frequency of timers peripherals @@ -52,11 +52,11 @@ typedef uint64_t hal_timer_t; #endif #define SYSTICK_TIMER_FREQUENCY 1000 -#define TEMP_TIMER_RATE 1000000 -#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency +#define TEMP_TIMER_RATE 1'000'000 +#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt 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_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1'000'000) // 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 diff --git a/Marlin/src/HAL/RP2040/timers.h b/Marlin/src/HAL/RP2040/timers.h index 512c6ba465..4d11804361 100644 --- a/Marlin/src/HAL/RP2040/timers.h +++ b/Marlin/src/HAL/RP2040/timers.h @@ -41,9 +41,9 @@ #define _HAL_TIMER_ISR(T) __HAL_TIMER_ISR(T) typedef uint64_t hal_timer_t; -#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFFFFFFFFF +#define HAL_TIMER_TYPE_MAX 0xFFFF'FFFF'FFFF'FFFFULL -#define HAL_TIMER_RATE (1000000ull) // fixed value as we use a microsecond timesource +#define HAL_TIMER_RATE (1'000'000ULL) // fixed value as we use a microsecond timesource #ifndef MF_TIMER_STEP #define MF_TIMER_STEP 0 // Timer Index for Stepper #endif diff --git a/Marlin/src/HAL/SAMD21/eeprom/eeprom_flash.cpp b/Marlin/src/HAL/SAMD21/eeprom/eeprom_flash.cpp index 1c190495de..0b5323cda4 100644 --- a/Marlin/src/HAL/SAMD21/eeprom/eeprom_flash.cpp +++ b/Marlin/src/HAL/SAMD21/eeprom/eeprom_flash.cpp @@ -83,7 +83,7 @@ bool PersistentStore::access_start() { NVMCTRL->CTRLA.reg = NVMCTRL_CTRLA_CMDEX_KEY | NVMCTRL_CTRLA_CMD_PBC; while (NVMCTRL->INTFLAG.bit.READY == 0) { } - PAGE_SIZE = pow(2,3 + NVMCTRL->PARAM.bit.PSZ); + PAGE_SIZE = POW(2, 3 + NVMCTRL->PARAM.bit.PSZ); ROW_SIZE= PAGE_SIZE * 4; /*NVMCTRL->SEECFG.reg = NVMCTRL_SEECFG_WMODE_BUFFERED; // Buffered mode and segment reallocation active if (NVMCTRL->SEESTAT.bit.RLOCK) diff --git a/Marlin/src/HAL/SAMD21/timers.h b/Marlin/src/HAL/SAMD21/timers.h index 303ccbdc50..a4faabb8e8 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 0xFFFFFFFF +#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFUL #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 86c3241892..59817453aa 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 0xFFFFFFFF +#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFUL #define HAL_TIMER_RATE F_CPU // frequency of timers peripherals diff --git a/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp b/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp index faf7d2b048..70caef6778 100644 --- a/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp +++ b/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp @@ -182,7 +182,7 @@ void TFT_FSMC::abort() { } void TFT_FSMC::transmitDMA(uint32_t memoryIncrease, uint16_t *data, uint16_t count) { - if (DMAtx.Init.PeriphInc != memoryIncrease) { + if (!__IS_DMA_CONFIGURED(&DMAtx) || DMAtx.Init.PeriphInc != memoryIncrease) { DMAtx.Init.PeriphInc = memoryIncrease; HAL_DMA_Init(&DMAtx); } @@ -191,7 +191,7 @@ void TFT_FSMC::transmitDMA(uint32_t memoryIncrease, uint16_t *data, uint16_t cou } void TFT_FSMC::transmit(uint32_t memoryIncrease, uint16_t *data, uint16_t count) { - if (DMAtx.Init.PeriphInc != memoryIncrease) { + if (!__IS_DMA_CONFIGURED(&DMAtx) || DMAtx.Init.PeriphInc != memoryIncrease) { DMAtx.Init.PeriphInc = memoryIncrease; HAL_DMA_Init(&DMAtx); } diff --git a/Marlin/src/HAL/STM32F1/timers.h b/Marlin/src/HAL/STM32F1/timers.h index 89a609c2c3..456278db2f 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 0xFFFF +#define HAL_TIMER_TYPE_MAX 0xFFFFU #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 3bbc2421e0..aeb8f2388a 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 0xFFFFFFFF +#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFUL #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 3536b62265..3a836ba44e 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 0xFFFFFFFF +#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFUL #define FTM0_TIMER_PRESCALE 8 #define FTM1_TIMER_PRESCALE 4 diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.cpp b/Marlin/src/HAL/TEENSY40_41/HAL.cpp index 1f27a283f7..3a1f06095b 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.cpp +++ b/Marlin/src/HAL/TEENSY40_41/HAL.cpp @@ -98,7 +98,7 @@ void MarlinHAL::clear_reset_source() { #define WDT_TIMEOUT TERN(WATCHDOG_DURATION_8S, 8, 4) // 4 or 8 second timeout - constexpr uint8_t timeoutval = (WDT_TIMEOUT - 0.5f) / 0.5f; + constexpr uint8_t timeoutval = (WDT_TIMEOUT - 0.5f) * 2.0f; void MarlinHAL::watchdog_init() { CCM_CCGR3 |= CCM_CCGR3_WDOG1(3); // enable WDOG1 clocks diff --git a/Marlin/src/HAL/TEENSY40_41/timers.h b/Marlin/src/HAL/TEENSY40_41/timers.h index fc160ab8b8..277a7f318d 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 0xFFFFFFFE +#define HAL_TIMER_TYPE_MAX 0xFFFFFFFEUL #define GPT_TIMER_RATE (F_CPU / 4) // 150MHz (Can't use F_BUS_ACTUAL because it's extern volatile) diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 1b95b2ba52..7cc9760e49 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -513,10 +513,11 @@ #define BOARD_BTT_OCTOPUS_PRO_V1_1 6008 // BigTreeTech Octopus Pro v1.1 (STM32H723ZE) #define BOARD_BTT_MANTA_M8P_V2_0 6009 // BigTreeTech Manta M8P V2.0 (STM32H723ZE) #define BOARD_BTT_KRAKEN_V1_0 6010 // BigTreeTech Kraken v1.0 (STM32H723ZG) -#define BOARD_TEENSY41 6011 // Teensy 4.1 -#define BOARD_T41U5XBB 6012 // T41U5XBB Teensy 4.1 breakout board -#define BOARD_FLY_D8_PRO 6013 // FLY_D8_PRO (STM32H723VG) -#define BOARD_FLY_SUPER8_PRO 6014 // FLY SUPER8 PRO (STM32H723ZG) +#define BOARD_TEENSY40 6011 // Teensy 4.0 +#define BOARD_TEENSY41 6012 // Teensy 4.1 +#define BOARD_T41U5XBB 6013 // T41U5XBB Teensy 4.1 breakout board +#define BOARD_FLY_D8_PRO 6014 // FLY_D8_PRO (STM32H723VG) +#define BOARD_FLY_SUPER8_PRO 6015 // FLY SUPER8 PRO (STM32H723ZG) // // Espressif ESP32 WiFi diff --git a/Marlin/src/core/serial_base.h b/Marlin/src/core/serial_base.h index a8700f3d23..07bed55b35 100644 --- a/Marlin/src/core/serial_base.h +++ b/Marlin/src/core/serial_base.h @@ -228,7 +228,7 @@ struct SerialBase { // Handle negative numbers if (number < 0.0) { write('-'); - number = -number; + number *= -1; } // Round correctly so that print(1.999, 2) prints as "2.00" diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h index 99a4e31a5d..fab32dea9b 100644 --- a/Marlin/src/core/types.h +++ b/Marlin/src/core/types.h @@ -547,13 +547,18 @@ struct XYval { FI constexpr T large() const { return _MAX(x, y); } // Explicit copy and copies with conversion - FI constexpr XYval copy() const { return *this; } - FI constexpr XYval ABS() const { return { T(_ABS(x)), T(_ABS(y)) }; } - FI constexpr XYval asInt() const { return { int16_t(x), int16_t(y) }; } - FI constexpr XYval asLong() const { return { int32_t(x), int32_t(y) }; } - FI constexpr XYval ROUNDL() const { return { int32_t(LROUND(x)), int32_t(LROUND(y)) }; } - FI constexpr XYval asFloat() const { return { static_cast(x), static_cast(y) }; } - FI constexpr XYval reciprocal() const { return { _RECIP(x), _RECIP(y) }; } + FI constexpr XYval copy() const { return *this; } + FI constexpr XYval ABS() const { return { T(_ABS(x)), T(_ABS(y)) }; } + FI constexpr XYval ROUNDL() const { return { int32_t(LROUND(x)), int32_t(LROUND(y)) }; } + FI constexpr XYval reciprocal() const { return { _RECIP(x), _RECIP(y) }; } + + // Conversion to other types + FI constexpr XYval asInt16() const { return { int16_t(x), int16_t(y) }; } + FI constexpr XYval asInt32() const { return { int32_t(x), int32_t(y) }; } + FI constexpr XYval asUInt32() const { return { uint32_t(x), uint32_t(y) }; } + FI constexpr XYval asInt64() const { return { int64_t(x), int64_t(y) }; } + FI constexpr XYval asUInt64() const { return { uint64_t(x), uint64_t(y) }; } + FI constexpr XYval asFloat() const { return { static_cast(x), static_cast(y) }; } // Marlin workspace shifting is done with G92 and M206 FI XYval asLogical() const { XYval o = asFloat(); toLogical(o); return o; } @@ -625,6 +630,11 @@ struct XYval { FI bool operator!=(const XYval &rs) const { return !operator==(rs); } FI bool operator!=(const XYZval &rs) const { return !operator==(rs); } FI bool operator!=(const XYZEval &rs) const { return !operator==(rs); } + + // Exact comparison to a single value + FI bool operator==(const T &p) const { return x == p && y == p; } + FI bool operator!=(const T &p) const { return !operator==(p); } + }; // @@ -701,12 +711,17 @@ struct XYZval { // Explicit copy and copies with conversion FI constexpr XYZval copy() const { XYZval o = *this; return o; } FI constexpr XYZval ABS() const { return NUM_AXIS_ARRAY(T(_ABS(x)), T(_ABS(y)), T(_ABS(z)), T(_ABS(i)), T(_ABS(j)), T(_ABS(k)), T(_ABS(u)), T(_ABS(v)), T(_ABS(w))); } - FI constexpr XYZval asInt() const { return NUM_AXIS_ARRAY(int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k), int16_t(u), int16_t(v), int16_t(w)); } - FI constexpr XYZval asLong() const { return NUM_AXIS_ARRAY(int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k), int32_t(u), int32_t(v), int32_t(w)); } FI constexpr XYZval ROUNDL() const { return NUM_AXIS_ARRAY(int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(i)), int32_t(LROUND(j)), int32_t(LROUND(k)), int32_t(LROUND(u)), int32_t(LROUND(v)), int32_t(LROUND(w))); } - FI constexpr XYZval asFloat() const { return NUM_AXIS_ARRAY(static_cast(x), static_cast(y), static_cast(z), static_cast(i), static_cast(j), static_cast(k), static_cast(u), static_cast(v), static_cast(w)); } FI constexpr XYZval reciprocal() const { return NUM_AXIS_ARRAY(_RECIP(x), _RECIP(y), _RECIP(z), _RECIP(i), _RECIP(j), _RECIP(k), _RECIP(u), _RECIP(v), _RECIP(w)); } + // Conversion to other types + FI constexpr XYZval asInt16() const { return NUM_AXIS_ARRAY(int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k), int16_t(u), int16_t(v), int16_t(w)); } + FI constexpr XYZval asInt32() const { return NUM_AXIS_ARRAY(int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k), int32_t(u), int32_t(v), int32_t(w)); } + FI constexpr XYZval asUInt32() const { return NUM_AXIS_ARRAY(uint32_t(x), uint32_t(y), uint32_t(z), uint32_t(i), uint32_t(j), uint32_t(k), uint32_t(u), uint32_t(v), uint32_t(w)); } + FI constexpr XYZval asInt64() const { return NUM_AXIS_ARRAY(int64_t(x), int64_t(y), int64_t(z), int64_t(i), int64_t(j), int64_t(k), int64_t(u), int64_t(v), int64_t(w)); } + FI constexpr XYZval asUInt64() const { return NUM_AXIS_ARRAY(uint64_t(x), uint64_t(y), uint64_t(z), uint64_t(i), uint64_t(j), uint64_t(k), uint64_t(u), uint64_t(v), uint64_t(w)); } + FI constexpr XYZval asFloat() const { return NUM_AXIS_ARRAY(static_cast(x), static_cast(y), static_cast(z), static_cast(i), static_cast(j), static_cast(k), static_cast(u), static_cast(v), static_cast(w)); } + // Marlin workspace shifting is done with G92 and M206 FI XYZval asLogical() const { XYZval o = asFloat(); toLogical(o); return o; } FI XYZval asNative() const { XYZval o = asFloat(); toNative(o); return o; } @@ -772,8 +787,13 @@ struct XYZval { 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; } // Exact comparisons. For floats a "NEAR" operation may be better. - FI bool operator==(const XYZEval &rs) const { return true NUM_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k, && u == rs.u, && v == rs.v, && w == rs.w); } + FI bool operator==(const XYZEval &rs) const { return ENABLED(HAS_X_AXIS) NUM_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k, && u == rs.u, && v == rs.v, && w == rs.w); } FI bool operator!=(const XYZEval &rs) const { return !operator==(rs); } + + // Exact comparison to a single value + FI bool operator==(const T &p) const { return ENABLED(HAS_X_AXIS) NUM_AXIS_GANG(&& x == p, && y == p, && z == p, && i == p, && j == p, && k == p, && u == p, && v == p, && w == p); } + FI bool operator!=(const T &p) const { return !operator==(p); } + }; // @@ -849,13 +869,18 @@ struct XYZEval { FI constexpr T large() const { return _MAX(LOGICAL_AXIS_LIST(e, x, y, z, i, j, k, u, v, w)); } // Explicit copy and copies with conversion - FI constexpr XYZEval copy() const { XYZEval v = *this; return v; } - FI constexpr XYZEval ABS() const { return LOGICAL_AXIS_ARRAY(T(_ABS(e)), T(_ABS(x)), T(_ABS(y)), T(_ABS(z)), T(_ABS(i)), T(_ABS(j)), T(_ABS(k)), T(_ABS(u)), T(_ABS(v)), T(_ABS(w))); } - FI constexpr XYZEval asInt() const { return LOGICAL_AXIS_ARRAY(int16_t(e), int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k), int16_t(u), int16_t(v), int16_t(w)); } - FI constexpr XYZEval asLong() const { return LOGICAL_AXIS_ARRAY(int32_t(e), int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k), int32_t(u), int32_t(v), int32_t(w)); } - FI constexpr XYZEval ROUNDL() const { return LOGICAL_AXIS_ARRAY(int32_t(LROUND(e)), int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(i)), int32_t(LROUND(j)), int32_t(LROUND(k)), int32_t(LROUND(u)), int32_t(LROUND(v)), int32_t(LROUND(w))); } - FI constexpr XYZEval asFloat() const { return LOGICAL_AXIS_ARRAY(static_cast(e), static_cast(x), static_cast(y), static_cast(z), static_cast(i), static_cast(j), static_cast(k), static_cast(u), static_cast(v), static_cast(w)); } - FI constexpr XYZEval reciprocal() const { return LOGICAL_AXIS_ARRAY(_RECIP(e), _RECIP(x), _RECIP(y), _RECIP(z), _RECIP(i), _RECIP(j), _RECIP(k), _RECIP(u), _RECIP(v), _RECIP(w)); } + FI constexpr XYZEval copy() const { XYZEval v = *this; return v; } + FI constexpr XYZEval ABS() const { return LOGICAL_AXIS_ARRAY(T(_ABS(e)), T(_ABS(x)), T(_ABS(y)), T(_ABS(z)), T(_ABS(i)), T(_ABS(j)), T(_ABS(k)), T(_ABS(u)), T(_ABS(v)), T(_ABS(w))); } + FI constexpr XYZEval ROUNDL() const { return LOGICAL_AXIS_ARRAY(int32_t(LROUND(e)), int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(i)), int32_t(LROUND(j)), int32_t(LROUND(k)), int32_t(LROUND(u)), int32_t(LROUND(v)), int32_t(LROUND(w))); } + FI constexpr XYZEval reciprocal() const { return LOGICAL_AXIS_ARRAY(_RECIP(e), _RECIP(x), _RECIP(y), _RECIP(z), _RECIP(i), _RECIP(j), _RECIP(k), _RECIP(u), _RECIP(v), _RECIP(w)); } + + // Conversion to other types + FI constexpr XYZEval asInt16() const { return LOGICAL_AXIS_ARRAY(int16_t(e), int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k), int16_t(u), int16_t(v), int16_t(w)); } + FI constexpr XYZEval asInt32() const { return LOGICAL_AXIS_ARRAY(int32_t(e), int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k), int32_t(u), int32_t(v), int32_t(w)); } + FI constexpr XYZEval asUInt32() const { return LOGICAL_AXIS_ARRAY(uint32_t(e), uint32_t(x), uint32_t(y), uint32_t(z), uint32_t(i), uint32_t(j), uint32_t(k), uint32_t(u), uint32_t(v), uint32_t(w)); } + FI constexpr XYZEval asInt64() const { return LOGICAL_AXIS_ARRAY(int64_t(e), int64_t(x), int64_t(y), int64_t(z), int64_t(i), int64_t(j), int64_t(k), int64_t(u), int64_t(v), int64_t(w)); } + FI constexpr XYZEval asUInt64() const { return LOGICAL_AXIS_ARRAY(uint64_t(e), uint64_t(x), uint64_t(y), uint64_t(z), uint64_t(i), uint64_t(j), uint64_t(k), uint64_t(u), uint64_t(v), uint64_t(w)); } + FI constexpr XYZEval asFloat() const { return LOGICAL_AXIS_ARRAY(static_cast(e), static_cast(x), static_cast(y), static_cast(z), static_cast(i), static_cast(j), static_cast(k), static_cast(u), static_cast(v), static_cast(w)); } // Marlin workspace shifting is done with G92 and M206 FI XYZEval asLogical() const { XYZEval o = asFloat(); toLogical(o); return o; } @@ -889,7 +914,10 @@ struct XYZEval { FI constexpr XYZEval operator- (const XYZEval &rs) const { return LOGICAL_AXIS_ARRAY(T(e - rs.e), T(x - rs.x), T(y - rs.y), T(z - rs.z), T(i - rs.i), T(j - rs.j), T(k - rs.k), T(u - rs.u), T(v - rs.v), T(w - rs.w)); } FI constexpr XYZEval operator* (const XYZEval &rs) const { return LOGICAL_AXIS_ARRAY(T(e * rs.e), T(x * rs.x), T(y * rs.y), T(z * rs.z), T(i * rs.i), T(j * rs.j), T(k * rs.k), T(u * rs.u), T(v * rs.v), T(w * rs.w)); } FI constexpr XYZEval operator/ (const XYZEval &rs) const { return LOGICAL_AXIS_ARRAY(T(e / rs.e), T(x / rs.x), T(y / rs.y), T(z / rs.z), T(i / rs.i), T(j / rs.j), T(k / rs.k), T(u / rs.u), T(v / rs.v), T(w / rs.w)); } + FI constexpr XYZEval operator+ (const uint32_t &p) const { return LOGICAL_AXIS_ARRAY(T(e + p), T(x + p), T(y + p), T(z + p), T(i + p), T(j + p), T(k + p), T(u + p), T(v + p), T(w + p)); } FI constexpr XYZEval operator* (const float &p) const { return LOGICAL_AXIS_ARRAY(T(e * p), T(x * p), T(y * p), T(z * p), T(i * p), T(j * p), T(k * p), T(u * p), T(v * p), T(w * p)); } + FI constexpr XYZEval operator* (const uint32_t &p) const { return LOGICAL_AXIS_ARRAY(T(e * p), T(x * p), T(y * p), T(z * p), T(i * p), T(j * p), T(k * p), T(u * p), T(v * p), T(w * p)); } + FI constexpr XYZEval operator& (const int64_t &p) const { return LOGICAL_AXIS_ARRAY(T(e & p), T(x & p), T(y & p), T(z & p), T(i & p), T(j & p), T(k & p), T(u & p), T(v & p), T(w & p)); } FI constexpr XYZEval operator* (const int &p) const { return LOGICAL_AXIS_ARRAY(e * p, x * p, y * p, z * p, i * p, j * p, k * p, u * p, v * p, w * p); } FI constexpr XYZEval operator/ (const float &p) const { return LOGICAL_AXIS_ARRAY(T(e / p), T(x / p), T(y / p), T(z / p), T(i / p), T(j / p), T(k / p), T(u / p), T(v / p), T(w / p)); } FI constexpr XYZEval operator/ (const int &p) const { return LOGICAL_AXIS_ARRAY(e / p, x / p, y / p, z / p, i / p, j / p, k / p, u / p, v / p, w / p); } @@ -920,14 +948,22 @@ struct XYZEval { FI XYZEval& operator<<=(const int &p) { LOGICAL_AXIS_CODE(_LSE(e), _LSE(x), _LSE(y), _LSE(z), _LSE(i), _LSE(j), _LSE(k), _LSE(u), _LSE(v), _LSE(w)); return *this; } // Exact comparisons. For floats a "NEAR" operation may be better. - FI bool operator==(const XYZval &rs) const { return true NUM_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k, && u == rs.u, && v == rs.v, && w == rs.w); } - FI bool operator==(const XYZEval &rs) const { return true LOGICAL_AXIS_GANG(&& e == rs.e, && x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k, && u == rs.u, && v == rs.v, && w == rs.w); } + FI bool operator==(const XYZval &rs) const { return ENABLED(HAS_X_AXIS) NUM_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k, && u == rs.u, && v == rs.v, && w == rs.w); } + FI bool operator==(const XYZEval &rs) const { return ANY(HAS_X_AXIS, HAS_EXTRUDERS) LOGICAL_AXIS_GANG(&& e == rs.e, && x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k, && u == rs.u, && v == rs.v, && w == rs.w); } FI bool operator!=(const XYZval &rs) const { return !operator==(rs); } FI bool operator!=(const XYZEval &rs) const { return !operator==(rs); } + + // Exact comparison to a single value + FI bool operator==(const T &p) const { return ENABLED(HAS_X_AXIS) LOGICAL_AXIS_GANG(&& e == p, && x == p, && y == p, && z == p, && i == p, && j == p, && k == p, && u == p, && v == p, && w == p); } + FI bool operator!=(const T &p) const { return !operator==(p); } + }; #include // for memset +// +// Axis indexed arrays of type T (x[SIZE], y[SIZE], etc.) +// template struct XYZarray { typedef T el[SIZE]; @@ -1027,6 +1063,9 @@ struct XYZEarray { FI XYZEval operator[](const int n) const { return XYZval(LOGICAL_AXIS_ARRAY(e[n], x[n], y[n], z[n], i[n], j[n], k[n], u[n], v[n], w[n])); } }; +// +// Axes mapped to bits in a mask of minimum size, bits_t(NUM_AXIS_HEADS) +// class AxisBits { public: typedef bits_t(NUM_AXIS_HEADS) el; diff --git a/Marlin/src/feature/bedlevel/bdl/bdl.cpp b/Marlin/src/feature/bedlevel/bdl/bdl.cpp index 7e9d583cc1..ea4bcc0607 100644 --- a/Marlin/src/feature/bedlevel/bdl/bdl.cpp +++ b/Marlin/src/feature/bedlevel/bdl/bdl.cpp @@ -101,7 +101,7 @@ bool BDS_Leveling::check(const uint16_t data, const bool raw_data/*=false*/, con } float BDS_Leveling::interpret(const uint16_t data) { - return (data & 0x3FF) / 100.0f; + return (data & 0x3FF) * 0.01f; } float BDS_Leveling::read() { diff --git a/Marlin/src/feature/dac/stepper_dac.cpp b/Marlin/src/feature/dac/stepper_dac.cpp index f5664bc598..cd73eb17e2 100644 --- a/Marlin/src/feature/dac/stepper_dac.cpp +++ b/Marlin/src/feature/dac/stepper_dac.cpp @@ -68,7 +68,7 @@ void StepperDAC::set_current_value(const uint8_t channel, uint16_t val) { } void StepperDAC::set_current_percent(const uint8_t channel, float val) { - set_current_value(channel, _MIN(val, 100.0f) * (DAC_STEPPER_MAX) / 100.0f); + set_current_value(channel, _MIN(val, 100.0f) * (DAC_STEPPER_MAX) * 0.01f); } static float dac_perc(int8_t n) { return mcp4728.getDrvPct(dac_order[n]); } diff --git a/Marlin/src/feature/filwidth.h b/Marlin/src/feature/filwidth.h index d9e2a00025..a16240936a 100644 --- a/Marlin/src/feature/filwidth.h +++ b/Marlin/src/feature/filwidth.h @@ -67,7 +67,7 @@ public: } // Convert raw measurement to mm - static float raw_to_mm(const uint16_t v) { return v * (float(ADC_VREF_MV) / 1000.0f) * RECIPROCAL(float(MAX_RAW_THERMISTOR_VALUE)); } + static float raw_to_mm(const uint16_t v) { return v * (float(ADC_VREF_MV) * 0.001f) * RECIPROCAL(float(MAX_RAW_THERMISTOR_VALUE)); } static float raw_to_mm() { return raw_to_mm(raw); } // A scaled reading is ready diff --git a/Marlin/src/feature/mmu3/mmu3.cpp b/Marlin/src/feature/mmu3/mmu3.cpp index 9097c8ae48..c39ed4a249 100644 --- a/Marlin/src/feature/mmu3/mmu3.cpp +++ b/Marlin/src/feature/mmu3/mmu3.cpp @@ -867,7 +867,7 @@ namespace MMU3 { nozzle_timer.start(); LogEchoEvent(F("Cooling Timeout started")); } - else if (nozzle_timer.duration() > (PAUSE_PARK_NOZZLE_TIMEOUT * 1000ul)) { // mins->msec. + else if (nozzle_timer.duration() > (PAUSE_PARK_NOZZLE_TIMEOUT * 1000UL)) { // mins->msec. mmu_print_saved &= ~(SavedState::CooldownPending); mmu_print_saved |= SavedState::Cooldown; thermal_setTargetHotend(0); diff --git a/Marlin/src/feature/mmu3/mmu3_protocol_logic.cpp b/Marlin/src/feature/mmu3/mmu3_protocol_logic.cpp index cf74e669b8..4323925b6b 100644 --- a/Marlin/src/feature/mmu3/mmu3_protocol_logic.cpp +++ b/Marlin/src/feature/mmu3/mmu3_protocol_logic.cpp @@ -707,7 +707,7 @@ namespace MMU3 { } bool ProtocolLogic::Elapsed(uint32_t timeout) const { - return _millis() >= (lastUARTActivityMs + timeout); + return ELAPSED(_millis(), lastUARTActivityMs + timeout); } void ProtocolLogic::RecordUARTActivity() { @@ -716,7 +716,7 @@ namespace MMU3 { void ProtocolLogic::RecordReceivedByte(uint8_t c) { lastReceivedBytes[lrb] = c; - lrb = (lrb + 1) % lastReceivedBytes.size(); + lrb = (lrb + 1) % COUNT(lastReceivedBytes); } constexpr char NibbleToChar(uint8_t c) { @@ -728,13 +728,13 @@ namespace MMU3 { } void ProtocolLogic::FormatLastReceivedBytes(char *dst) { - for (uint8_t i = 0; i < lastReceivedBytes.size(); ++i) { - uint8_t b = lastReceivedBytes[(lrb - i - 1) % lastReceivedBytes.size()]; + for (uint8_t i = 0; i < COUNT(lastReceivedBytes); ++i) { + uint8_t b = lastReceivedBytes[(COUNT(lastReceivedBytes) - 1 + (lrb - i)) % COUNT(lastReceivedBytes)]; dst[i * 3] = NibbleToChar(b >> 4); dst[i * 3 + 1] = NibbleToChar(b & 0xf); dst[i * 3 + 2] = ' '; } - dst[(lastReceivedBytes.size() - 1) * 3 + 2] = 0; // terminate properly + dst[(COUNT(lastReceivedBytes) - 1) * 3 + 2] = 0; // terminate properly } void ProtocolLogic::FormatLastResponseMsgAndClearLRB(char *dst) { @@ -777,18 +777,18 @@ namespace MMU3 { } void ProtocolLogic::LogError(const char *reason_P) { - char lrb[lastReceivedBytes.size() * 3]; - FormatLastReceivedBytes(lrb); + char _lrb[COUNT(lastReceivedBytes) * 3]; + FormatLastReceivedBytes(_lrb); MMU2_ERROR_MSGRPGM(reason_P); SERIAL_ECHOPGM(", last bytes: "); - SERIAL_ECHOLN(lrb); + SERIAL_ECHOLN(_lrb); } void ProtocolLogic::LogResponse() { - char lrb[lastReceivedBytes.size()]; - FormatLastResponseMsgAndClearLRB(lrb); - MMU2_ECHO_MSGLN(lrb); + char _lrb[COUNT(lastReceivedBytes)]; + FormatLastResponseMsgAndClearLRB(_lrb); + MMU2_ECHO_MSGLN(_lrb); } StepStatus ProtocolLogic::SuppressShortDropOuts(const char *msg_P, StepStatus ss) { diff --git a/Marlin/src/feature/mmu3/mmu3_protocol_logic.h b/Marlin/src/feature/mmu3/mmu3_protocol_logic.h index 2fef77c276..30f9c5d0d5 100644 --- a/Marlin/src/feature/mmu3/mmu3_protocol_logic.h +++ b/Marlin/src/feature/mmu3/mmu3_protocol_logic.h @@ -36,24 +36,8 @@ #include "mmu_hw/buttons.h" #include "mmu_hw/registers.h" #include "mmu3_protocol.h" - - // #include std array is not available on AVR ... we need to "fake" it - namespace std { - template - class array { - T data[N]; - public: - array() = default; - inline constexpr T *begin() const { return data; } - inline constexpr T *end() const { return data + N; } - static constexpr uint8_t size() { return N; } - inline T &operator[](uint8_t i) { return data[i]; } - }; - } // std - #else // !__AVR__ - #include #include "mmu_hw/error_codes.h" #include "mmu_hw/progress_codes.h" @@ -351,8 +335,7 @@ namespace MMU3 { Protocol protocol; //!< protocol codec - std::array lastReceivedBytes; //!< remembers the last few bytes of incoming communication for diagnostic purposes - uint8_t lrb; + uint8_t lrb, lastReceivedBytes[16]; //!< keep the last few bytes of incoming communication for diagnostic purposes ErrorCode errorCode; //!< last received error code from the MMU ProgressCode progressCode; //!< last received progress code from the MMU diff --git a/Marlin/src/feature/probe_temp_comp.cpp b/Marlin/src/feature/probe_temp_comp.cpp index 413beda161..7dfa28f4b9 100644 --- a/Marlin/src/feature/probe_temp_comp.cpp +++ b/Marlin/src/feature/probe_temp_comp.cpp @@ -212,7 +212,7 @@ void ProbeTempComp::compensate_measurement(const TempSensorID tsi, const celsius } // convert offset to mm and apply it - meas_z -= offset / 1000.0f; + meas_z -= offset * 0.001f; } bool ProbeTempComp::linear_regression(const TempSensorID tsi, float &k, float &d) { diff --git a/Marlin/src/feature/spindle_laser.h b/Marlin/src/feature/spindle_laser.h index 8702bd289a..8305c1fec4 100644 --- a/Marlin/src/feature/spindle_laser.h +++ b/Marlin/src/feature/spindle_laser.h @@ -60,7 +60,7 @@ public: // Convert configured power range to a percentage static constexpr cutter_cpower_t power_floor = TERN(CUTTER_POWER_RELATIVE, SPEED_POWER_MIN, 0); static constexpr uint8_t cpwr_to_pct(const cutter_cpower_t cpwr) { - return cpwr ? round(100.0f * (cpwr - power_floor) / (SPEED_POWER_MAX - power_floor)) : 0; + return cpwr ? LROUND(100.0f * (cpwr - power_floor) / (SPEED_POWER_MAX - power_floor)) : 0; } // Convert config defines from RPM to %, angle or PWM when in Spindle mode @@ -164,7 +164,7 @@ public: */ static cutter_power_t power_to_range(const cutter_power_t pwr, const uint8_t pwrUnit=_CUTTER_POWER(CUTTER_POWER_UNIT)) { static constexpr float - min_pct = TERN(CUTTER_POWER_RELATIVE, 0, TERN(SPINDLE_FEATURE, round(100.0f * (SPEED_POWER_MIN) / (SPEED_POWER_MAX)), SPEED_POWER_MIN)), + min_pct = TERN(CUTTER_POWER_RELATIVE, 0, TERN(SPINDLE_FEATURE, roundf(100.0f * (SPEED_POWER_MIN) / (SPEED_POWER_MAX)), SPEED_POWER_MIN)), max_pct = TERN(SPINDLE_FEATURE, 100, SPEED_POWER_MAX); if (pwr <= 0) return 0; cutter_power_t upwr; diff --git a/Marlin/src/feature/tmc_util.cpp b/Marlin/src/feature/tmc_util.cpp index 06ee4c9e93..b1fc69f88a 100644 --- a/Marlin/src/feature/tmc_util.cpp +++ b/Marlin/src/feature/tmc_util.cpp @@ -973,14 +973,14 @@ TMC_REPORT("[mm/s]\t", TMC_TPWMTHRS_MMS); TMC_REPORT("OT prewarn", TMC_DEBUG_OTPW); #if ENABLED(MONITOR_DRIVER_STATUS) - TMC_REPORT("triggered\n OTP\t", TMC_OTPW_TRIGGERED); + TMC_REPORT("OTPW trig.\t", TMC_OTPW_TRIGGERED); #endif #if HAS_TMC220x - TMC_REPORT("pwm scale sum", TMC_PWM_SCALE_SUM); - TMC_REPORT("pwm scale auto", TMC_PWM_SCALE_AUTO); - TMC_REPORT("pwm offset auto", TMC_PWM_OFS_AUTO); - TMC_REPORT("pwm grad auto", TMC_PWM_GRAD_AUTO); + TMC_REPORT("pwm scale sum", TMC_PWM_SCALE_SUM); + TMC_REPORT("pwm scale auto", TMC_PWM_SCALE_AUTO); + TMC_REPORT("pwm offset auto", TMC_PWM_OFS_AUTO); + TMC_REPORT("pwm grad auto", TMC_PWM_GRAD_AUTO); #endif TMC_REPORT("off time", TMC_TOFF); diff --git a/Marlin/src/gcode/calibrate/G33.cpp b/Marlin/src/gcode/calibrate/G33.cpp index 11c3cdca78..1eabb30ffa 100644 --- a/Marlin/src/gcode/calibrate/G33.cpp +++ b/Marlin/src/gcode/calibrate/G33.cpp @@ -154,7 +154,7 @@ static float std_dev_points(float z_pt[NPP + 1], const bool _0p_cal, const bool S2 += sq(z_pt[rad]); N++; } - return LROUND(SQRT(S2 / N) * 1000.0f) / 1000.0f + 0.00001f; + return LROUND(SQRT(S2 / N) * 1000.0f) * 0.001f + 0.00001f; } } return 0.00001f; @@ -315,7 +315,7 @@ static void calc_kinematics_diff_probe_points(float z_pt[NPP + 1], const float d static float auto_tune_h(const float dcr) { const float r_quot = dcr / delta_radius; - return RECIPROCAL(r_quot / (2.0f / 3.0f)); // (2/3)/CR + return RECIPROCAL(r_quot * (3.0f / 2.0f)); // (2/3)/CR } static float auto_tune_r(const float dcr) { @@ -490,7 +490,7 @@ void GcodeSuite::G33() { float z_at_pt[NPP + 1] = { 0.0f }; - test_precision = zero_std_dev_old != 999.0f ? (zero_std_dev + zero_std_dev_old) / 2.0f : zero_std_dev; + test_precision = zero_std_dev_old != 999.0f ? (zero_std_dev + zero_std_dev_old) * 0.5f : zero_std_dev; iterations++; // Probe the points @@ -527,7 +527,7 @@ void GcodeSuite::G33() { * - Definition of the matrix scaling parameters * - Matrices for 4 and 7 point calibration */ - #define ZP(N,I) ((N) * z_at_pt[I] / 4.0f) // 4.0 = divider to normalize to integers + #define ZP(N,I) ((N) * z_at_pt[I] * 0.25f) // 4.0 = divider to normalize to integers #define Z12(I) ZP(12, I) #define Z4(I) ZP(4, I) #define Z2(I) ZP(2, I) diff --git a/Marlin/src/gcode/calibrate/G34_M422.cpp b/Marlin/src/gcode/calibrate/G34_M422.cpp index aba828d6dd..6c367ad882 100644 --- a/Marlin/src/gcode/calibrate/G34_M422.cpp +++ b/Marlin/src/gcode/calibrate/G34_M422.cpp @@ -236,10 +236,8 @@ void GcodeSuite::G34() { Z_TWEEN_SAFE_CLEARANCE // z_clearance ); - if (DEBUGGING(LEVELING)) { - DEBUG_ECHOLNPGM_P(PSTR("Probing X"), ppos.x, SP_Y_STR, ppos.y); - DEBUG_ECHOLNPGM("Height = ", z_probed_height); - } + if (DEBUGGING(LEVELING)) + DEBUG_ECHOLN(F("Probing X"), ppos.x, FPSTR(SP_Y_STR), ppos.y, F(" Height = "), z_probed_height); if (isnan(z_probed_height)) { SERIAL_ECHOLNPGM(STR_ERR_PROBING_FAILED); @@ -392,7 +390,7 @@ void GcodeSuite::G34() { // Decreasing accuracy was detected so move was inverted. // Will match reversed Z steppers on dual steppers. Triple will need more work to map. if (adjustment_reverse) { - z_align_move = -z_align_move; + z_align_move *= -1; if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("> Z", zstepper + 1, " correction reversed to ", z_align_move); } #endif diff --git a/Marlin/src/gcode/feature/advance/M900.cpp b/Marlin/src/gcode/feature/advance/M900.cpp index 7b92cad9d2..ac6a5246aa 100644 --- a/Marlin/src/gcode/feature/advance/M900.cpp +++ b/Marlin/src/gcode/feature/advance/M900.cpp @@ -41,6 +41,9 @@ * With ADVANCE_K_EXTRA: * S<0/1> Activate slot 0 or 1. * L Set secondary advance K factor (Slot 1). + * + * With SMOOTH_LIN_ADVANCE: + * U Set a tau value for LA smoothing */ void GcodeSuite::M900() { diff --git a/Marlin/src/gcode/feature/trinamic/M122.cpp b/Marlin/src/gcode/feature/trinamic/M122.cpp index b3ad144f14..fe87e485bc 100644 --- a/Marlin/src/gcode/feature/trinamic/M122.cpp +++ b/Marlin/src/gcode/feature/trinamic/M122.cpp @@ -28,11 +28,18 @@ #include "../../../feature/tmc_util.h" #include "../../../module/stepper/indirection.h" // for restore_stepper_drivers +#if AXIS_COLLISION('I') + #warning "M122 parameter 'I' collision with axis name." +#endif +#if AXIS_COLLISION('V') + #warning "M122 parameter 'V' collision with axis name." +#endif + /** * M122: Debug TMC drivers * - * I - Flag to re-initialize stepper drivers with current settings. - * X, Y, Z, E - Flags to only report the specified axes. + * I - Flag to re-initialize stepper drivers with current settings. + * X, Y, Z ... E - Flags to only report the specified axes. * * With TMC_DEBUG: * V - Report raw register data. Refer to the datasheet to decipher the report. @@ -45,20 +52,24 @@ void GcodeSuite::M122() { bool print_all = true; LOOP_LOGICAL_AXES(i) if (parser.seen_test(AXIS_CHAR(i))) { print_axis[i] = true; print_all = false; } - if (print_all) LOOP_LOGICAL_AXES(i) print_axis[i] = true; if (parser.boolval('I')) restore_stepper_drivers(); #if ENABLED(TMC_DEBUG) #if ENABLED(MONITOR_DRIVER_STATUS) - const bool sflag = parser.seen('S'), sval = sflag && parser.value_bool(); - if (sflag && !sval) // "S0" + if (parser.seenval('S') && !parser.value_bool()) { // "S0" tmc_set_report_interval(0); - else if (parser.seenval('P')) // "P" + return; + } + else if (parser.seenval('P')) { // "P" tmc_set_report_interval(_MAX(uint16_t(250), parser.value_ushort())); - else if (sval) // "S" or "S1" + return; + } + else if (parser.boolval('S')) { // "S" or "S1" tmc_set_report_interval(MONITOR_DRIVER_STATUS_INTERVAL_MS); + return; + } #endif if (parser.seen_test('V')) diff --git a/Marlin/src/inc/Conditionals-5-post.h b/Marlin/src/inc/Conditionals-5-post.h index 3d248f7b29..6e5fa8de6c 100644 --- a/Marlin/src/inc/Conditionals-5-post.h +++ b/Marlin/src/inc/Conditionals-5-post.h @@ -1867,6 +1867,8 @@ #endif #if ANY_AXIS_HAS(SW_SERIAL) #define HAS_TMC_SW_SERIAL 1 +#elif HAS_TRINAMIC_CONFIG + #define HAS_TMC_WITHOUT_SW_SERIAL 1 #endif #ifndef SERIAL_FLOAT_PRECISION #define SERIAL_FLOAT_PRECISION 2 @@ -3063,13 +3065,17 @@ #define HAS_MOTOR_CURRENT_PWM 1 #endif +#if PINS_EXIST(MS1, MS2) + #define HAS_SHARED_MICROSTEPPING_PINS 1 +#endif + #if ANY(HAS_Z_MS_PINS, HAS_Z2_MS_PINS, HAS_Z3_MS_PINS, HAS_Z4_MS_PINS) #define HAS_SOME_Z_MS_PINS 1 #endif #if ANY(HAS_E0_MS_PINS, HAS_E1_MS_PINS, HAS_E2_MS_PINS, HAS_E3_MS_PINS, HAS_E4_MS_PINS, HAS_E5_MS_PINS, HAS_E6_MS_PINS, HAS_E7_MS_PINS) #define HAS_SOME_E_MS_PINS 1 #endif -#if ANY(HAS_X_MS_PINS, HAS_X2_MS_PINS, HAS_Y_MS_PINS, HAS_Y2_MS_PINS, HAS_SOME_Z_MS_PINS, HAS_I_MS_PINS, HAS_J_MS_PINS, HAS_K_MS_PINS, HAS_U_MS_PINS, HAS_V_MS_PINS, HAS_W_MS_PINS, HAS_SOME_E_MS_PINS) +#if ANY(HAS_X_MS_PINS, HAS_X2_MS_PINS, HAS_Y_MS_PINS, HAS_Y2_MS_PINS, HAS_SOME_Z_MS_PINS, HAS_I_MS_PINS, HAS_J_MS_PINS, HAS_K_MS_PINS, HAS_U_MS_PINS, HAS_V_MS_PINS, HAS_W_MS_PINS, HAS_SOME_E_MS_PINS, HAS_SHARED_MICROSTEPPING_PINS) #define HAS_MICROSTEPS 1 #else #undef MICROSTEP_MODES diff --git a/Marlin/src/inc/MarlinConfig.h b/Marlin/src/inc/MarlinConfig.h index f962a5ff5c..70f34944c9 100644 --- a/Marlin/src/inc/MarlinConfig.h +++ b/Marlin/src/inc/MarlinConfig.h @@ -21,9 +21,22 @@ */ #pragma once -// -// Prefix header for all Marlin sources -// +/** + * MarlinConfig.h + * + * Prefix header for all Marlin sources. Includes the following: + * + * Conditionals-6-type.h + * MarlinConfigPre-6-type.h + * Conditionals-5-post.h + * MarlinConfigPre.h + * ... (see the file) ... + * HAL.h + * pins.h + * HAL/timers.h + * HAL/spi_pins.h + * types.h + */ #include "Conditionals-6-type.h" diff --git a/Marlin/src/inc/MarlinConfigPre.h b/Marlin/src/inc/MarlinConfigPre.h index 6abd9e1ea6..e89471f578 100644 --- a/Marlin/src/inc/MarlinConfigPre.h +++ b/Marlin/src/inc/MarlinConfigPre.h @@ -21,9 +21,28 @@ */ #pragma once -// -// Prefix header to acquire configurations -// +/** + * MarlinConfigPre.h + * + * Prefix header to acquire Configurations. Includes the following: + * + * Conditionals-1-axes.h + * MarlinConfigPre-1-axes.h + * Config.h + * macros.h + * boards.h + * Configuration.h (if not Config.h) + * HAL/platforms.h + * Version.h + * Conditionals-2-LCD.h + * Conditionals-3-etc.h + * Conditionals-4-adv.h + * MarlinConfigPre-4-adv.h + * Conditionals-3-etc.h (as above) + * drivers.h + * Configuration_adv.h (if not Config.h) + */ + #include "Conditionals-1-axes.h" #include "Conditionals-2-LCD.h" #include "Conditionals-3-etc.h" diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index ceddf20b7b..b78ad2d55a 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -40,6 +40,9 @@ #error "Marlin requires C++11 support (gcc >= 4.7, Arduino IDE >= 1.6.8). Please upgrade your toolchain." #endif +// Emit the GCC version +//static_assert(false, "GCC version: " STRINGIFY(__GNUC__) "." STRINGIFY(__GNUC_MINOR__) "." STRINGIFY(__GNUC_PATCHLEVEL__)); + // Strings for sanity check messages #define _NUM_AXES_STR NUM_AXIS_GANG("X ", "Y ", "Z ", "I ", "J ", "K ", "U ", "V ", "W ") #define _LOGICAL_AXES_STR LOGICAL_AXIS_GANG("E ", "X ", "Y ", "Z ", "I ", "J ", "K ", "U ", "V ", "W ") @@ -4531,6 +4534,17 @@ static_assert(WITHIN(MULTISTEPPING_LIMIT, 1, 128) && IS_POWER_OF_2(MULTISTEPPING #error "CONFIGURABLE_MACHINE_NAME requires GCODE_QUOTED_STRINGS." #endif +/** + * Shared Microstepping Pins Sanity Check + */ +#if HAS_SHARED_MICROSTEPPING_PINS + static constexpr uint8_t _microstep_modes[] = MICROSTEP_MODES, mm0 = _microstep_modes[0]; + static_assert( + _microstep_modes[1] == mm0 && _microstep_modes[2] == mm0 && _microstep_modes[3] == mm0 && _microstep_modes[4] == mm0 && _microstep_modes[5] == mm0, + "When using shared microstepping pins (MS1_PIN and MS2_PIN), all MICROSTEP_MODES values must be identical." + ); +#endif + // Misc. Cleanup #undef _TEST_PWM #undef _NUM_AXES_STR diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 9021441f79..445ea6994f 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2025-10-19" + #define STRING_DISTRIBUTION_DATE "2025-10-29" #endif /** diff --git a/Marlin/src/inc/Warnings.cpp b/Marlin/src/inc/Warnings.cpp index dddada62ec..38711e4fca 100644 --- a/Marlin/src/inc/Warnings.cpp +++ b/Marlin/src/inc/Warnings.cpp @@ -932,6 +932,12 @@ #if ENABLED(FTM_HOME_AND_PROBE) && DELAY_BEFORE_PROBING <= 25 #warning "A longer DELAY_BEFORE_PROBING is recommended when using a probe with FT_MOTION." #endif + #if ENABLED(NONLINEAR_EXTRUSION) + #warning "NONLINEAR_EXTRUSION does not (currently) operate when FT_MOTION is the active motion system." + #endif + #if ENABLED(LIN_ADVANCE) + #warning "Be aware that FT_MOTION K factor (M493 K) is a separate setting from LIN_ADVANCE K factor (M900 K)." + #endif #endif /** diff --git a/Marlin/src/lcd/dogm/u8g/u8g_dev_ssd1306_sh1106_128x64_SWSPI.cpp b/Marlin/src/lcd/dogm/u8g/u8g_dev_ssd1306_sh1106_128x64_SWSPI.cpp index fae4b78aec..e55a450406 100644 --- a/Marlin/src/lcd/dogm/u8g/u8g_dev_ssd1306_sh1106_128x64_SWSPI.cpp +++ b/Marlin/src/lcd/dogm/u8g/u8g_dev_ssd1306_sh1106_128x64_SWSPI.cpp @@ -87,7 +87,7 @@ static const uint8_t u8g_dev_ssd13xx_HAL_sleep_on[] PROGMEM = { U8G_ESC_ADR(0), // Instruction mode U8G_ESC_CS(1), // Enable chip - SH1106_ON(0) // Display off + SH1106_ON(0), // Display off U8G_ESC_CS(0), // Disable chip U8G_ESC_END // End of sequence }; diff --git a/Marlin/src/lcd/e3v2/common/dwin_api.cpp b/Marlin/src/lcd/e3v2/common/dwin_api.cpp index 132e8bbb76..619b9283a0 100644 --- a/Marlin/src/lcd/e3v2/common/dwin_api.cpp +++ b/Marlin/src/lcd/e3v2/common/dwin_api.cpp @@ -408,7 +408,7 @@ void dwinDrawFloatValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t // value: positive unscaled float value void dwinDrawFloatValue(uint8_t bShow, bool zeroFill, uint8_t zeroMode, uint8_t size, uint16_t color, uint16_t bColor, uint8_t iNum, uint8_t fNum, uint16_t x, uint16_t y, float value) { - const int32_t val = round(value * POW(10, fNum)); + const int32_t val = LROUND(value * POW(10, fNum)); dwinDrawFloatValue(bShow, zeroFill, zeroMode, size, color, bColor, iNum, fNum, x, y, val); } diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index 30a179fb9c..06e3321288 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -96,7 +96,7 @@ // Minimum unit (0.1) : multiple (10) #define UNITFDIGITS 1 -#define MINUNITMULT pow(10, UNITFDIGITS) +#define MINUNITMULT POW(10, UNITFDIGITS) #define DWIN_VAR_UPDATE_INTERVAL 1024 #define DWIN_SCROLL_UPDATE_INTERVAL SEC_TO_MS(2) @@ -1388,7 +1388,7 @@ void hmiMoveDone(const AxisEnum axis) { LIMIT(hmiValues.offset_value, _OFFSET_ZMIN * 100, _OFFSET_ZMAX * 100); last_zoffset = dwin_zoffset; - dwin_zoffset = hmiValues.offset_value / 100.0f; + dwin_zoffset = hmiValues.offset_value * 0.01f; #if ANY(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) if (BABYSTEP_ALLOWED()) babystep.add_mm(Z_AXIS, dwin_zoffset - last_zoffset); #endif diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp index 4fbefa3c8b..2870524dea 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -378,8 +378,8 @@ private: dwinDrawRectangle(1, // RGB565 colors: http://www.barth-dev.de/online/rgb565-color-picker/ isnan(bedlevel.z_values[x][y]) ? COLOR_GREY : ( // gray if undefined (bedlevel.z_values[x][y] < 0 ? - (uint16_t)round(0x1F * -bedlevel.z_values[x][y] / (!viewer_asymmetric_range ? rmax : v_min)) << 11 : // red if mesh point value is negative - (uint16_t)round(0x3F * bedlevel.z_values[x][y] / (!viewer_asymmetric_range ? rmax : v_max)) << 5) | // green if mesh point value is positive + (uint16_t)LROUND(0x1F * -bedlevel.z_values[x][y] / (!viewer_asymmetric_range ? rmax : v_min)) << 11 : // red if mesh point value is negative + (uint16_t)LROUND(0x3F * bedlevel.z_values[x][y] / (!viewer_asymmetric_range ? rmax : v_max)) << 5) | // green if mesh point value is positive _MIN(0x1F, (((uint8_t)abs(bedlevel.z_values[x][y]) / 10) * 4))), // + blue stepping for every mm start_x_px, start_y_px, end_x_px, end_y_px ); @@ -1523,7 +1523,7 @@ void JyersDWIN::menuItemHandler(const uint8_t menu, const uint8_t item, bool dra if (use_probe) { #if HAS_BED_PROBE gcode.process_subcommands_now( - TS(F("G0F4000\nG0Z10\nG0X"), p_float_t((X_MAX_POS) / 2.0f - probe.offset.x, 3), 'Y', p_float_t((Y_MAX_POS) / 2.0f - probe.offset.y, 3)) + TS(F("G0F4000\nG0Z10\nG0X"), p_float_t((X_MAX_POS) * 0.5f - probe.offset.x, 3), 'Y', p_float_t((Y_MAX_POS) * 0.5f - probe.offset.y, 3)) ); planner.synchronize(); popupHandler(Popup_ManualProbing); @@ -5112,7 +5112,7 @@ void JyersDWIN::loadSettings(const char * const buff) { memcpy(&eeprom_settings, buff, _MIN(sizeof(eeprom_settings), eeprom_data_size)); TERN_(AUTO_BED_LEVELING_UBL, mesh_conf.tilt_grid = eeprom_settings.tilt_grid_size + 1); if (eeprom_settings.corner_pos == 0) eeprom_settings.corner_pos = 325; - corner_pos = eeprom_settings.corner_pos / 10.0f; + corner_pos = eeprom_settings.corner_pos * 0.1f; redrawScreen(); #if ENABLED(POWER_LOSS_RECOVERY) static bool init = true; @@ -5139,7 +5139,7 @@ void JyersDWIN::resetSettings() { eeprom_settings.coordinates_text = 0; eeprom_settings.coordinates_split_line = 0; TERN_(AUTO_BED_LEVELING_UBL, mesh_conf.tilt_grid = eeprom_settings.tilt_grid_size + 1); - corner_pos = eeprom_settings.corner_pos / 10.0f; + corner_pos = eeprom_settings.corner_pos * 0.1f; TERN_(SOUND_MENU_ITEM, ui.sound_on = ENABLED(SOUND_ON_DEFAULT)); redrawScreen(); } diff --git a/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp b/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp index b85caaf6cc..7c6ee0491a 100644 --- a/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp +++ b/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp @@ -226,10 +226,10 @@ bool BedLevelTools::meshValidate() { const auto start_y_px = padding_y_top + ((GRID_MAX_POINTS_Y) - y - 1) * cell_height_px; const auto end_y_px = start_y_px + cell_height_px - 1 - gridline_width; const float z = bedlevel.z_values[x][y]; - const uint16_t color = isnan(z) ? COLOR_GREY : ( // Gray if undefined - (z < 0 ? uint16_t(round(0x1F * -z / rmax)) << 11 // Red for negative mesh point - : uint16_t(round(0x3F * z / rmax)) << 5) // Green for positive mesh point - | _MIN(0x1F, (uint8_t(abs(z) * 0.4))) // + Blue stepping for every mm + const uint16_t color = isnan(z) ? COLOR_GREY : ( // Gray if undefined + (z < 0 ? uint16_t(LROUND(0x1F * -z / rmax)) << 11 // Red for negative mesh point + : uint16_t(LROUND(0x3F * z / rmax)) << 5) // Green for positive mesh point + | _MIN(0x1F, (uint8_t(abs(z) * 0.4))) // + Blue stepping for every mm ); dwinDrawRectangle(1, color, start_x_px, start_y_px, end_x_px, end_y_px); diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 4ae26a3c77..d6718305c2 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -2169,13 +2169,13 @@ void autoHome() { queue.inject_P(G28_STR); } void applyZOffset() { TERN_(EEPROM_SETTINGS, settings.save()); } void liveZOffset() { #if ANY(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) - const float step_zoffset = round((menuData.value / 100.0f) * planner.settings.axis_steps_per_mm[Z_AXIS]) - babystep.accum; + const float step_zoffset = roundf((menuData.value * 0.01f) * planner.settings.axis_steps_per_mm[Z_AXIS]) - babystep.accum; if (BABYSTEP_ALLOWED()) babystep.add_steps(Z_AXIS, step_zoffset); #endif } void setZOffset() { #if ANY(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) - babystep.accum = round(planner.settings.axis_steps_per_mm[Z_AXIS] * BABY_Z_VAR); + babystep.accum = LROUND(planner.settings.axis_steps_per_mm[Z_AXIS] * BABY_Z_VAR); #endif setPFloatOnClick(PROBE_OFFSET_ZMIN, PROBE_OFFSET_ZMAX, 2, applyZOffset, liveZOffset); } diff --git a/Marlin/src/lcd/e3v2/proui/menus.cpp b/Marlin/src/lcd/e3v2/proui/menus.cpp index 0451944645..a3d159ff8a 100644 --- a/Marlin/src/lcd/e3v2/proui/menus.cpp +++ b/Marlin/src/lcd/e3v2/proui/menus.cpp @@ -213,7 +213,7 @@ void setValueOnClick(uint8_t process, const int32_t lo, const int32_t hi, const // liveUpdate: live update function when the encoder changes // apply: update function when the encoder is pressed void setValueOnClick(uint8_t process, const float lo, const float hi, uint8_t dp, const float val, void (*apply)()/*=nullptr*/, void (*liveUpdate)()/*=nullptr*/) { - const int32_t value = round(val * POW(10, dp)); + const int32_t value = LROUND(val * POW(10, dp)); setOnClick(process, lo * POW(10, dp), hi * POW(10, dp), dp, value, apply, liveUpdate); DrawItemEdit(true); } diff --git a/Marlin/src/lcd/e3v2/proui/meshviewer.cpp b/Marlin/src/lcd/e3v2/proui/meshviewer.cpp index e167af5665..54904ad8b9 100644 --- a/Marlin/src/lcd/e3v2/proui/meshviewer.cpp +++ b/Marlin/src/lcd/e3v2/proui/meshviewer.cpp @@ -75,7 +75,7 @@ void MeshViewer::drawMeshGrid(const uint8_t csizex, const uint8_t csizey) { void MeshViewer::drawMeshPoint(const uint8_t x, const uint8_t y, const float z) { const uint8_t fs = DWINUI::fontWidth(meshfont); - const int16_t v = isnan(z) ? 0 : round(z * 100); + const int16_t v = isnan(z) ? int16_t(0) : int16_t(LROUND(z * 100)); NOLESS(max, z); NOMORE(min, z); const uint16_t color = DWINUI::rainbowInt(v, zmin, zmax); diff --git a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp index 79353a4e23..84b27eec51 100644 --- a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp @@ -542,7 +542,7 @@ void DGUSScreenHandler::handleSettings(DGUS_VP_Variable &var, void *val_ptr) { #if HAS_BED_PROBE void DGUSScreenHandler::handleProbeOffsetZChanged(DGUS_VP_Variable &var, void *val_ptr) { - const float offset = float(int16_t(BE16_P(val_ptr))) / 100.0f; + const float offset = float(int16_t(BE16_P(val_ptr))) * 0.01f; ExtUI::setZOffset_mm(offset); skipVP = var.VP; // don't overwrite value the next update time as the display might autoincrement in parallel return; diff --git a/Marlin/src/lcd/extui/dgus/DGUSScreenHandlerBase.h b/Marlin/src/lcd/extui/dgus/DGUSScreenHandlerBase.h index ceaeb7cd7f..017b38430d 100644 --- a/Marlin/src/lcd/extui/dgus/DGUSScreenHandlerBase.h +++ b/Marlin/src/lcd/extui/dgus/DGUSScreenHandlerBase.h @@ -199,7 +199,7 @@ public: if (var.memadr) { float f = *(float *)var.memadr; f *= cpow(10, decimals); - dgus.writeVariable(var.VP, (long)f); + dgus.writeVariable(var.VP, LROUND(f)); } } @@ -212,7 +212,7 @@ public: float f = *(float *)var.memadr; DEBUG_ECHOLNPGM(" >> ", p_float_t(f, 6)); f *= cpow(10, decimals); - dgus.writeVariable(var.VP, (int16_t)f); + dgus.writeVariable(var.VP, (int16_t)LROUND(f)); } } diff --git a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp index be0e60a8df..f4c7db544b 100644 --- a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp @@ -205,7 +205,7 @@ void DGUSScreenHandler::handleManualMove(DGUS_VP_Variable &var, void *val_ptr) { const uint16_t backup_speed = MMS_TO_MMM(feedrate_mm_s); char sign[] = "\0"; int16_t value = movevalue / 100; - if (movevalue < 0) { value = -value; sign[0] = '-'; } + if (movevalue < 0) { value *= -1; sign[0] = '-'; } int16_t fraction = ABS(movevalue) % 100; snprintf_P(buf, 32, PSTR("G0 %c%s%d.%02d F%d"), axiscode, sign, value, fraction, speed); queue.enqueue_one_now(buf); diff --git a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp index 297c71f8a9..a62d3a2ffc 100644 --- a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp @@ -207,7 +207,7 @@ void DGUSScreenHandler::handleManualMove(DGUS_VP_Variable &var, void *val_ptr) { const uint16_t backup_speed = MMS_TO_MMM(feedrate_mm_s); char sign[] = "\0"; int16_t value = movevalue / 100; - if (movevalue < 0) { value = -value; sign[0] = '-'; } + if (movevalue < 0) { value *= -1; sign[0] = '-'; } int16_t fraction = ABS(movevalue) % 100; snprintf_P(buf, 32, PSTR("G0 %c%s%d.%02d F%d"), axiscode, sign, value, fraction, speed); queue.enqueue_one_now(buf); diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp index 2a9ba87d68..2965d75da3 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp @@ -382,7 +382,7 @@ void DGUSScreenHandlerMKS::zOffsetSelect(DGUS_VP_Variable &var, void *val_ptr) { void DGUSScreenHandlerMKS::getOffsetValue(DGUS_VP_Variable &var, void *val_ptr) { #if HAS_BED_PROBE - const float offset = BE32_P(val_ptr) / 100.0f; + const float offset = BE32_P(val_ptr) * 0.01f; switch (var.VP) { default: break; case VP_OFFSET_X: probe.offset.x = offset; break; @@ -778,7 +778,7 @@ void DGUSScreenHandler::handleManualMove(DGUS_VP_Variable &var, void *val_ptr) { char buf[32]; // G1 X9999.99 F12345 char sign[] = "\0"; int16_t value = movevalue / 100; - if (movevalue < 0) { value = -value; sign[0] = '-'; } + if (movevalue < 0) { value *= -1; sign[0] = '-'; } const int16_t fraction = ABS(movevalue) % 100; snprintf_P(buf, 32, PSTR("G0 %c%s%d.%02d F%d"), axiscode, sign, value, fraction, speed); queue.enqueue_one_now(buf); diff --git a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp index 0afc8a25ad..ac73c8cf65 100644 --- a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp @@ -207,7 +207,7 @@ void DGUSScreenHandler::handleManualMove(DGUS_VP_Variable &var, void *val_ptr) { const uint16_t backup_speed = MMS_TO_MMM(feedrate_mm_s); char sign[] = "\0"; int16_t value = movevalue / 100; - if (movevalue < 0) { value = -value; sign[0] = '-'; } + if (movevalue < 0) { value *= -1; sign[0] = '-'; } int16_t fraction = ABS(movevalue) % 100; snprintf_P(buf, 32, PSTR("G0 %c%s%d.%02d F%d"), axiscode, sign, value, fraction, speed); queue.enqueue_one_now(buf); diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp index e195654caa..6b2caadba0 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp @@ -676,11 +676,11 @@ void DGUSRxHandler::moveStep(DGUS_VP &vp, void *data_ptr) { switch (direction) { default: return; - case DGUS_Data::MoveDirection::XM: offset = -offset; + case DGUS_Data::MoveDirection::XM: offset *= -1; case DGUS_Data::MoveDirection::XP: axis = ExtUI::X; break; - case DGUS_Data::MoveDirection::YM: offset = -offset; + case DGUS_Data::MoveDirection::YM: offset *= -1; case DGUS_Data::MoveDirection::YP: axis = ExtUI::Y; break; - case DGUS_Data::MoveDirection::ZM: offset = -offset; + case DGUS_Data::MoveDirection::ZM: offset *= -1; case DGUS_Data::MoveDirection::ZP: axis = ExtUI::Z; break; } diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.cpp index 1212f715c0..a2327d025f 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSTxHandler.cpp @@ -183,7 +183,7 @@ void DGUSTxHandler::zPosition(DGUS_VP &vp) { const float position = ExtUI::isAxisPositionKnown(ExtUI::Z) ? planner.get_axis_position_mm(Z_AXIS) : 0; - const int32_t data = dgus.toFixedPoint(int32_t(position * 50.0f) / 50.0f); // Round to 0.02 + const int32_t data = dgus.toFixedPoint(int32_t(position * 50.0f) * 0.02f); // Round to 0.02 dgus.write((uint16_t)vp.addr, dgus.swapBytes(data)); } diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index 5f69d4424a..75caf8a85c 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -850,7 +850,7 @@ namespace ExtUI { { backlash.set_distance_mm((AxisEnum)axis, constrain(value,0,5)); } float getBacklashCorrection_percent() { return backlash.get_correction() * 100.0f; } - void setBacklashCorrection_percent(const float value) { backlash.set_correction(constrain(value, 0, 100) / 100.0f); } + void setBacklashCorrection_percent(const float value) { backlash.set_correction(constrain(value, 0, 100) * 0.01f); } #ifdef BACKLASH_SMOOTHING_MM float getBacklashSmoothing_mm() { return backlash.get_smoothing_mm(); } diff --git a/Marlin/src/lcd/menu/game/brickout.cpp b/Marlin/src/lcd/menu/game/brickout.cpp index 061e4e89c8..7b596a156f 100644 --- a/Marlin/src/lcd/menu/game/brickout.cpp +++ b/Marlin/src/lcd/menu/game/brickout.cpp @@ -53,7 +53,7 @@ void reset_ball() { bdat.ballv = FTOF(1.3f); bdat.ballh = -FTOF(1.25f); uint8_t bx = bdat.paddle_x + (PADDLE_W) / 2 + ball_dist; - if (bx >= GAME_WIDTH - 10) { bx -= ball_dist * 2; bdat.ballh = -bdat.ballh; } + if (bx >= GAME_WIDTH - 10) { bx -= ball_dist * 2; bdat.ballh *= -1; } bdat.ballx = BTOF(bx); bdat.hit_dir = -1; } @@ -71,10 +71,10 @@ void BrickoutGame::game_screen() { // Provisionally update the ball position const fixed_t newx = bdat.ballx + bdat.ballh, newy = bdat.bally + bdat.ballv; // current next position if (!WITHIN(newx, 0, BTOF(GAME_WIDTH - 1))) { // out in x? - bdat.ballh = -bdat.ballh; _BUZZ(5, 220); // bounce x + bdat.ballh *= -1; _BUZZ(5, 220); // bounce x } if (newy < 0) { // out in y? - bdat.ballv = -bdat.ballv; _BUZZ(5, 280); // bounce v + bdat.ballv *= -1; _BUZZ(5, 280); // bounce v bdat.hit_dir = 1; } // Did the ball go below the bottom? @@ -96,8 +96,8 @@ void BrickoutGame::game_screen() { // If bricks are gone, go to reset state if (!--bdat.brick_count) game_state = 2; // Bounce the ball cleverly - if ((bdat.ballv < 0) == (bdat.hit_dir < 0)) { bdat.ballv = -bdat.ballv; bdat.ballh += fixed_t(random(-16, 16)); _BUZZ(5, 880); } - else { bdat.ballh = -bdat.ballh; bdat.ballv += fixed_t(random(-16, 16)); _BUZZ(5, 640); } + if ((bdat.ballv < 0) == (bdat.hit_dir < 0)) { bdat.ballv *= -1; bdat.ballh += fixed_t(random(-16, 16)); _BUZZ(5, 880); } + else { bdat.ballh *= -1; bdat.ballv += fixed_t(random(-16, 16)); _BUZZ(5, 640); } } } // Is the ball moving down and in paddle range? @@ -107,13 +107,13 @@ void BrickoutGame::game_screen() { if (WITHIN(diff, 0, PADDLE_W - 1)) { // Reverse Y direction - bdat.ballv = -bdat.ballv; _BUZZ(3, 880); + bdat.ballv *= -1; _BUZZ(3, 880); bdat.hit_dir = -1; // Near edges affects X velocity const bool is_left_edge = (diff <= 1); if (is_left_edge || diff >= PADDLE_W-1 - 1) { - if ((bdat.ballh > 0) == is_left_edge) bdat.ballh = -bdat.ballh; + if ((bdat.ballh > 0) == is_left_edge) bdat.ballh *= -1; } else if (diff <= 3) { bdat.ballh += fixed_t(random(-64, 0)); diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index f869436c7d..9e956711cf 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -465,10 +465,7 @@ void menu_move() { BACK_ITEM(MSG_MOTION); bool show_state = c.active; - EDIT_ITEM(bool, MSG_FIXED_TIME_MOTION, &show_state, []{ - FLIP(ftMotion.cfg.active); - ftMotion.update_shaping_params(); - }); + EDIT_ITEM(bool, MSG_FIXED_TIME_MOTION, &show_state, []{ (void)ftMotion.toggle(); }); // Show only when FT Motion is active (or optionally always show) if (c.active || ENABLED(FT_MOTION_NO_MENU_TOGGLE)) { diff --git a/Marlin/src/lcd/sovol_rts/sovol_rts.cpp b/Marlin/src/lcd/sovol_rts/sovol_rts.cpp index 3c09838684..c982a2cc32 100644 --- a/Marlin/src/lcd/sovol_rts/sovol_rts.cpp +++ b/Marlin/src/lcd/sovol_rts/sovol_rts.cpp @@ -838,7 +838,7 @@ void RTS::handleData() { #endif case Heater0LoadEnterKey: - filament_load_0 = float(recdat.data[0]) / 10.0f; + filament_load_0 = float(recdat.data[0]) * 0.1f; break; case AxisPageSelectKey: // Mobile shaft interface @@ -948,7 +948,7 @@ void RTS::handleData() { #if HAS_X_AXIS case XaxismoveKey: { waitway = 4; - current_position.x = float(recdat.data[0] >= 32768 ? recdat.data[0] - 65536 : recdat.data[0]) / 10.0f; + current_position.x = float(recdat.data[0] >= 32768 ? recdat.data[0] - 65536 : recdat.data[0]) * 0.1f; LIMIT(current_position.x, X_MIN_POS, X_MAX_POS); RTS_line_to_current(X_AXIS); sendData(current_position.x * 10.0f, AXIS_X_COORD_VP); @@ -960,7 +960,7 @@ void RTS::handleData() { #if HAS_Y_AXIS case YaxismoveKey: { waitway = 4; - current_position.y = float(recdat.data[0]) / 10.0f; + current_position.y = float(recdat.data[0]) * 0.1f; LIMIT(current_position.y, Y_MIN_POS, Y_MAX_POS); RTS_line_to_current(Y_AXIS); sendData(current_position.y * 10.0f, AXIS_Y_COORD_VP); @@ -972,7 +972,7 @@ void RTS::handleData() { #if HAS_Z_AXIS case ZaxismoveKey: { waitway = 4; - current_position.z = float(recdat.data[0]) / 10.0f; + current_position.z = float(recdat.data[0]) * 0.1f; LIMIT(current_position.z, Z_MIN_POS, Z_MAX_POS); RTS_line_to_current(Z_AXIS); sendData(current_position.z * 10.0f, AXIS_Z_COORD_VP); @@ -1229,7 +1229,7 @@ void RTS::handleData() { case 1: { // PID #if ENABLED(PIDTEMP) const float hot_p = thermalManager.temp_hotend[0].pid.p() * 100.0f, - hot_i = (thermalManager.temp_hotend[0].pid.i() / 8.0f * 10000.0f) + 0.00001f, + hot_i = (thermalManager.temp_hotend[0].pid.i() * 0.125f * 10000.0f) + 0.00001f, hot_d = thermalManager.temp_hotend[0].pid.d() * 8.0f; sendData(hot_p, Nozzle_P_VP); sendData(hot_i, Nozzle_I_VP); @@ -1238,7 +1238,7 @@ void RTS::handleData() { #if ENABLED(PIDTEMPBED) const float bed_p = thermalManager.temp_bed.pid.p() * 100.0f, - bed_i = (thermalManager.temp_bed.pid.i() / 8.0f * 10000.0f) + 0.0001f, + bed_i = (thermalManager.temp_bed.pid.i() * 0.125f * 10000.0f) + 0.0001f, bed_d = thermalManager.temp_bed.pid.d() * 0.8f; sendData(bed_p, Hot_Bed_P_VP); @@ -1306,51 +1306,51 @@ void RTS::handleData() { break; #if ENABLED(PIDTEMP) - case Nozzle_P: SET_HOTEND_PID(Kp, 0, float(recdat.data[0]) / 100.0f); thermalManager.updatePID(); break; - case Nozzle_I: SET_HOTEND_PID(Ki, 0, float(recdat.data[0]) * 8.0f / 10000.0f); thermalManager.updatePID(); break; - case Nozzle_D: SET_HOTEND_PID(Kd, 0, float(recdat.data[0]) / 8.0f); thermalManager.updatePID(); break; + case Nozzle_P: SET_HOTEND_PID(Kp, 0, float(recdat.data[0]) * 0.01f); thermalManager.updatePID(); break; + case Nozzle_I: SET_HOTEND_PID(Ki, 0, float(recdat.data[0]) * 8.0f * 0.0001f); thermalManager.updatePID(); break; + case Nozzle_D: SET_HOTEND_PID(Kd, 0, float(recdat.data[0]) * 0.125f); thermalManager.updatePID(); break; #endif #if ENABLED(PIDTEMPBED) - case Hot_Bed_P: thermalManager.temp_bed.pid.set_Kp(float(recdat.data[0]) / 100.0f); break; - case Hot_Bed_I: thermalManager.temp_bed.pid.set_Ki(float(recdat.data[0]) * 8.0f / 10000.0f); break; - case Hot_Bed_D: thermalManager.temp_bed.pid.set_Kd(float(recdat.data[0]) / 0.8f); break; + case Hot_Bed_P: thermalManager.temp_bed.pid.set_Kp(float(recdat.data[0]) * 0.01f); break; + case Hot_Bed_I: thermalManager.temp_bed.pid.set_Ki(float(recdat.data[0]) * 8.0f * 0.0001f); break; + case Hot_Bed_D: thermalManager.temp_bed.pid.set_Kd(float(recdat.data[0]) * 1.25); break; #endif #if HAS_X_AXIS case Vmax_X: planner.settings.max_feedrate_mm_s[X_AXIS] = recdat.data[0]; break; case Amax_X: planner.settings.max_acceleration_mm_per_s2[X_AXIS] = recdat.data[0]; break; - case Steps_X: planner.settings.axis_steps_per_mm[X_AXIS] = float(recdat.data[0]) / 10.0f; break; + case Steps_X: planner.settings.axis_steps_per_mm[X_AXIS] = float(recdat.data[0]) * 0.1f; break; #if ENABLED(CLASSIC_JERK) - case Jerk_X: planner.max_jerk.x = float(recdat.data[0]) / 10.0f; break; + case Jerk_X: planner.max_jerk.x = float(recdat.data[0]) * 0.1f; break; #endif #endif #if HAS_Y_AXIS case Vmax_Y: planner.settings.max_feedrate_mm_s[Y_AXIS] = recdat.data[0]; break; case Amax_Y: planner.settings.max_acceleration_mm_per_s2[Y_AXIS] = recdat.data[0]; break; - case Steps_Y: planner.settings.axis_steps_per_mm[Y_AXIS] = float(recdat.data[0]) / 10.0f; break; + case Steps_Y: planner.settings.axis_steps_per_mm[Y_AXIS] = float(recdat.data[0]) * 0.1f; break; #if ENABLED(CLASSIC_JERK) - case Jerk_Y: planner.max_jerk.y = float(recdat.data[0]) / 10.0f; break; + case Jerk_Y: planner.max_jerk.y = float(recdat.data[0]) * 0.1f; break; #endif #endif #if HAS_Z_AXIS case Vmax_Z: planner.settings.max_feedrate_mm_s[Z_AXIS] = recdat.data[0]; break; case Amax_Z: planner.settings.max_acceleration_mm_per_s2[Z_AXIS] = recdat.data[0]; break; - case Steps_Z: planner.settings.axis_steps_per_mm[Z_AXIS] = float(recdat.data[0]) / 10.0f; break; + case Steps_Z: planner.settings.axis_steps_per_mm[Z_AXIS] = float(recdat.data[0]) * 0.1f; break; #if ENABLED(CLASSIC_JERK) - case Jerk_Z: planner.max_jerk.z = float(recdat.data[0]) / 10.0f; break; + case Jerk_Z: planner.max_jerk.z = float(recdat.data[0]) * 0.1f; break; #endif #endif #if HAS_HOTEND case Vmax_E: planner.settings.max_feedrate_mm_s[E_AXIS] = recdat.data[0]; break; case Amax_E: planner.settings.max_acceleration_mm_per_s2[E_AXIS] = recdat.data[0]; break; - case Steps_E: planner.settings.axis_steps_per_mm[E_AXIS] = float(recdat.data[0]) / 10.0f; break; + case Steps_E: planner.settings.axis_steps_per_mm[E_AXIS] = float(recdat.data[0]) * 0.1f; break; #if ENABLED(CLASSIC_JERK) - case Jerk_E: planner.max_jerk.e = float(recdat.data[0]) / 10.0f; break; + case Jerk_E: planner.max_jerk.e = float(recdat.data[0]) * 0.1f; break; #endif case A_Retract: planner.settings.retract_acceleration = recdat.data[0]; break; #if ENABLED(LIN_ADVANCE) - case Advance_K: planner.set_advance_k(float(recdat.data[0]) / 100.0f); break; + case Advance_K: planner.set_advance_k(float(recdat.data[0]) * 0.01f); break; #endif #endif case Accel: planner.settings.acceleration = recdat.data[0]; break; @@ -1384,7 +1384,7 @@ void RTS::handleData() { case ZOffsetKey: last_zoffset = zprobe_zoffset; - zprobe_zoffset = float(recdat.data[0] >= 32767 ? recdat.data[0] - 65537 : recdat.data[0]) / 100.0f + 0.0001f; + zprobe_zoffset = float(recdat.data[0] >= 32767 ? recdat.data[0] - 65537 : recdat.data[0]) * 0.01f + 0.0001f; if (WITHIN(zprobe_zoffset, PROBE_OFFSET_ZMIN, PROBE_OFFSET_ZMAX)) babystep.add_mm(Z_AXIS, zprobe_zoffset - last_zoffset); probe.offset.z = zprobe_zoffset; diff --git a/Marlin/src/libs/numtostr.cpp b/Marlin/src/libs/numtostr.cpp index ec097f203f..43ecf018d7 100644 --- a/Marlin/src/libs/numtostr.cpp +++ b/Marlin/src/libs/numtostr.cpp @@ -41,7 +41,7 @@ template constexpr char MINUSOR(T &n, const char alt) { return (n >= 0) ? alt : (n = -n) ? '-' : '-'; } constexpr long INTFLOAT(const float V, const int N) { - return long((V * 10.0f * pow(10.0f, N) + (V < 0.0f ? -5.0f : 5.0f)) / 10.0f); + return long((V * 10.0f * pow(10.0f, N) + (V < 0.0f ? -5.0f : 5.0f)) * 0.1f); } constexpr long UINTFLOAT(const float V, const int N) { return INTFLOAT(V < 0.0f ? -V : V, N); diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index b0ad431476..a12e432003 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -309,11 +309,6 @@ void Endstops::enable(const bool onoff) { resync(); } -// Disable / Enable endstops based on ENSTOPS_ONLY_FOR_HOMING and global enable -void Endstops::not_homing() { - enabled = enabled_globally; -} - #if ENABLED(VALIDATE_HOMING_ENDSTOPS) // If the last move failed to trigger an endstop, call kill void Endstops::validate_homing_move() { diff --git a/Marlin/src/module/endstops.h b/Marlin/src/module/endstops.h index 40975632ff..ab124c3536 100644 --- a/Marlin/src/module/endstops.h +++ b/Marlin/src/module/endstops.h @@ -246,7 +246,7 @@ class Endstops { static void enable(const bool onoff=true); // Disable / Enable endstops based on ENSTOPS_ONLY_FOR_HOMING and global enable - static void not_homing(); + static void not_homing() { enabled = enabled_globally; } #if ENABLED(VALIDATE_HOMING_ENDSTOPS) // If the last move failed to trigger an endstop, call kill diff --git a/Marlin/src/module/ft_motion.cpp b/Marlin/src/module/ft_motion.cpp index 5b2db32626..cd0c162668 100644 --- a/Marlin/src/module/ft_motion.cpp +++ b/Marlin/src/module/ft_motion.cpp @@ -20,6 +20,13 @@ * */ +/** + * ft_motion.cpp - Singleton to execute Fixed Time Motion planning + * + * Fixed-Time Motion concept contributed by Ulendo with integration and + * overhaul optimizations by @thinkyhead, @narno2202, @dbuezas. + */ + #include "../inc/MarlinConfig.h" #if ENABLED(FT_MOTION) @@ -302,7 +309,7 @@ void FTMotion::loop() { case ftMotionShaper_2HEI: { max_i = 3U; const float vtolx2 = sq(vtol); - const float X = pow(vtolx2 * (sqrt(1.0f - vtolx2) + 1.0f), 1.0f / 3.0f); + const float X = POW(vtolx2 * (sqrt(1.0f - vtolx2) + 1.0f), 1.0f / 3.0f); Ai[0] = (3.0f * sq(X) + 2.0f * X + 3.0f * vtolx2) / (16.0f * X); Ai[1] = (0.5f - Ai[0]) * K; Ai[2] = Ai[1] * K; @@ -348,28 +355,28 @@ void FTMotion::loop() { const float df = sqrt ( 1.f - sq(zeta) ); switch (shaper) { case ftMotionShaper_ZV: - Ni[1] = round((0.5f / f / df) * (FTM_FS)); + Ni[1] = LROUND((0.5f / f / df) * (FTM_FS)); break; case ftMotionShaper_ZVD: case ftMotionShaper_EI: - Ni[1] = round((0.5f / f / df) * (FTM_FS)); + Ni[1] = LROUND((0.5f / f / df) * (FTM_FS)); Ni[2] = Ni[1] + Ni[1]; break; case ftMotionShaper_ZVDD: case ftMotionShaper_2HEI: - Ni[1] = round((0.5f / f / df) * (FTM_FS)); + Ni[1] = LROUND((0.5f / f / df) * (FTM_FS)); Ni[2] = Ni[1] + Ni[1]; Ni[3] = Ni[2] + Ni[1]; break; case ftMotionShaper_ZVDDD: case ftMotionShaper_3HEI: - Ni[1] = round((0.5f / f / df) * (FTM_FS)); + Ni[1] = LROUND((0.5f / f / df) * (FTM_FS)); Ni[2] = Ni[1] + Ni[1]; Ni[3] = Ni[2] + Ni[1]; Ni[4] = Ni[3] + Ni[1]; break; case ftMotionShaper_MZV: - Ni[1] = round((0.375f / f / df) * (FTM_FS)); + Ni[1] = LROUND((0.375f / f / df) * (FTM_FS)); Ni[2] = Ni[1] + Ni[1]; break; case ftMotionShaper_NONE: @@ -383,7 +390,7 @@ void FTMotion::loop() { float centroid = 0.0f; for (uint8_t i = 1; i <= max_i; ++i) centroid -= Ai[i] * Ni[i]; - Ni[0] = round(centroid); + Ni[0] = LROUND(centroid); // The resulting echo index can be negative, this is ok because it will be offset // by the max delay of all axes before it is used. diff --git a/Marlin/src/module/ft_motion.h b/Marlin/src/module/ft_motion.h index 11f85aea53..dfe10282e1 100644 --- a/Marlin/src/module/ft_motion.h +++ b/Marlin/src/module/ft_motion.h @@ -41,6 +41,9 @@ #endif #endif +/** + * FTConfig - The active configured state of FT Motion + */ typedef struct FTConfig { bool active = ENABLED(FTM_IS_DEFAULT_MOTION); // Active (else standard motion) bool axis_sync_enabled = true; // Axis synchronization enabled @@ -77,6 +80,9 @@ typedef struct FTConfig { float poly6_acceleration_overshoot; // Overshoot factor for Poly6 (1.25 to 2.0) } ft_config_t; +/** + * FTMotion - Singleton class encapsulating Fixed Time Motion + */ class FTMotion { public: @@ -145,7 +151,7 @@ class FTMotion { #if HAS_FTM_SHAPING // Refresh gains and indices used by shaping functions. - static void update_shaping_params(void); + static void update_shaping_params(); #endif #if ENABLED(FTM_SMOOTHING) @@ -157,6 +163,13 @@ class FTMotion { static void reset(); // Reset all states of the fixed time conversion to defaults. + static bool toggle() { + stepper.ftMotion_syncPosition(); + FLIP(cfg.active); + update_shaping_params(); + return cfg.active; + } + // Trajectory generator selection static void setTrajectoryType(const TrajectoryType type); static TrajectoryType getTrajectoryType() { return trajectoryType; } @@ -269,8 +282,12 @@ class FTMotion { }; // class FTMotion -extern FTMotion ftMotion; +extern FTMotion ftMotion; // Use ftMotion.thing, not FTMotion::thing. +/** + * Optional behavior to turn FT Motion off for homing/probing. + * Applies when FTM_HOME_AND_PROBE is disabled. + */ typedef struct FTMotionDisableInScope { #if DISABLED(FTM_HOME_AND_PROBE) bool isactive; diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index d7967f6aaf..1282e605eb 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -190,7 +190,7 @@ xyz_pos_t cartes; xyz_pos_t workspace_offset{0}; #endif -#if HAS_ABL_NOT_UBL +#if ABL_USES_GRID feedRate_t xy_probe_feedrate_mm_s = MMM_TO_MMS(XY_PROBE_FEEDRATE); #endif diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index 39da94a46e..e74562728d 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -62,7 +62,9 @@ extern xyz_pos_t cartes; extern abce_pos_t delta; #endif -#if HAS_ABL_NOT_UBL +// Determine XY_PROBE_FEEDRATE_MM_S - The feedrate used between Probe Points +#if ABL_USES_GRID + // ABL LINEAR and BILINEAR use 'G29 S' value, or MMM_TO_MMS(XY_PROBE_FEEDRATE) extern feedRate_t xy_probe_feedrate_mm_s; #define XY_PROBE_FEEDRATE_MM_S xy_probe_feedrate_mm_s #elif defined(XY_PROBE_FEEDRATE) diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index e48a55ae48..99df08205d 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -2415,9 +2415,10 @@ bool Planner::_populate_block( * Check the appropriate K value for Standard or Fixed-Time Motion. */ if (esteps && dm.e) { - const bool ftm_active = TERN0(FTM_HAS_LIN_ADVANCE, ftMotion.cfg.active); + const bool ftm_active = TERN0(FTM_HAS_LIN_ADVANCE, ftMotion.cfg.active), + ftm_la_active = TERN0(FTM_HAS_LIN_ADVANCE, ftm_active && ftMotion.cfg.linearAdvEna); const float advK = ftm_active - ? TERN0(FTM_HAS_LIN_ADVANCE, ftMotion.cfg.linearAdvK) + ? (ftm_la_active ? TERN0(FTM_HAS_LIN_ADVANCE, ftMotion.cfg.linearAdvK) : 0) : TERN0(HAS_ROUGH_LIN_ADVANCE, extruder_advance_K[E_INDEX_N(extruder)]); if (advK) { float e_D_ratio = (target_float.e - position_float.e) / @@ -2437,7 +2438,7 @@ bool Planner::_populate_block( const uint32_t max_accel_steps_per_s2 = (MAX_E_JERK(extruder) / (advK * e_D_ratio)) * steps_per_mm; if (accel > max_accel_steps_per_s2) { accel = max_accel_steps_per_s2; - if (TERN0(LA_DEBUG, DEBUGGING(INFO))) SERIAL_ECHOLNPGM("Acceleration limited."); + if (TERN0(LA_DEBUG, DEBUGGING(INFO))) SERIAL_ECHOLNPGM("Acceleration limited to max_accel_steps_per_s2 (", max_accel_steps_per_s2, ")"); } } } @@ -3065,11 +3066,11 @@ bool Planner::buffer_line(const xyze_pos_t &cart, const feedRate_t fr_mm_s feedRate_t calculated_feedrate = fr_mm_s; const xyz_pos_t diff = delta - position_float; if (!NEAR_ZERO(diff.b)) { - if (delta.a <= POLAR_FAST_RADIUS ) + if (delta.a <= POLAR_FAST_RADIUS) calculated_feedrate = settings.max_feedrate_mm_s[Y_AXIS]; else { // Normalized vector of movement - const float diffBLength = ABS((2.0f * M_PI * diff.a) * (diff.b / 360.0f)), + const float diffBLength = ABS((2.0f * M_PI * diff.a) * (diff.b * 0.002777777778)), // ÷ 360 diffTheta = DEGREES(ATAN2(diff.a, diffBLength)), normalizedTheta = 1.0f - (ABS(diffTheta > 90.0f ? 180.0f - diffTheta : diffTheta) / 90.0f); diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 0ad68352ee..b6fdc2fc6f 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -209,12 +209,12 @@ typedef struct PlannerBlock { volatile block_flags_t flag; // Block flags - bool is_sync_pos() { return flag.sync_position; } - bool is_sync_fan() { return TERN0(LASER_SYNCHRONOUS_M106_M107, flag.sync_fans); } - bool is_sync_pwr() { return TERN0(LASER_POWER_SYNC, flag.sync_laser_pwr); } - bool is_sync() { return is_sync_pos() || is_sync_fan() || is_sync_pwr(); } - bool is_page() { return TERN0(DIRECT_STEPPING, flag.page); } - bool is_move() { return !(is_sync() || is_page()); } + bool is_sync_pos() const { return flag.sync_position; } + bool is_sync_fan() const { return TERN0(LASER_SYNCHRONOUS_M106_M107, flag.sync_fans); } + bool is_sync_pwr() const { return TERN0(LASER_POWER_SYNC, flag.sync_laser_pwr); } + bool is_sync() const { return is_sync_pos() || is_sync_fan() || is_sync_pwr(); } + bool is_page() const { return TERN0(DIRECT_STEPPING, flag.page); } + bool is_move() const { return !(is_sync() || is_page()); } // Fields used by the motion planner to manage acceleration float nominal_speed, // The nominal speed for this block in (mm/sec) diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index e72a2d14ac..63f69d13c2 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -2518,7 +2518,7 @@ void MarlinSettings::postprocess() { #if HAS_TRINAMIC_CONFIG - #define SET_CURR(Q) stepper##Q.rms_current(currents.Q ? currents.Q : Q##_CURRENT) + #define SET_CURR(Q) stepper##Q.rms_current(currents.Q ?: Q##_CURRENT) if (!validating) { TERN_(X_IS_TRINAMIC, SET_CURR(X)); TERN_(Y_IS_TRINAMIC, SET_CURR(Y)); diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 8bf839c39c..3025cb83bd 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -21,33 +21,25 @@ */ /** - * stepper.cpp - A singleton object to execute motion plans using stepper motors - * Marlin Firmware + * stepper.cpp - Singleton to execute motion plans using stepper motors * - * Derived from Grbl - * Copyright (c) 2009-2011 Simen Svale Skogsrud + * Marlin uses the Bresenham algorithm. For a detailed explanation of theory and + * method see https://www.cs.helsinki.fi/group/goa/mallinnus/lines/bresenh.html * - * Grbl 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. - * - * Grbl 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 Grbl. If not, see . - */ - -/** * Timer calculations informed by the 'RepRap cartesian firmware' by Zack Smith * and Philipp Tiefenbacher. + * + * Jerk controlled movements planner added Apr 2018 by Eduardo José Tagle. + * Equations based on Synthethos TinyG2 sources, but the fixed-point + * implementation is new, as we are running the ISR with a variable period. + * Also implemented the Bézier velocity curve evaluation in ARM assembler, + * to avoid impacting ISR speed. + * + * Fixed-Time Motion concept contributed by Ulendo with integration and + * overhaul optimizations by @thinkyhead, @narno2202, @dbuezas. */ -/** - * __________________________ +/** __________________________ * /| |\ _________________ ^ * / | | \ /| |\ | * / | | \ / | | \ s @@ -70,19 +62,6 @@ * - Reset the trapezoid generator. */ -/** - * Marlin uses the Bresenham algorithm. For a detailed explanation of theory and - * method see https://www.cs.helsinki.fi/group/goa/mallinnus/lines/bresenh.html - */ - -/** - * Jerk controlled movements planner added Apr 2018 by Eduardo José Tagle. - * Equations based on Synthethos TinyG2 sources, but the fixed-point - * implementation is new, as we are running the ISR with a variable period. - * Also implemented the Bézier velocity curve evaluation in ARM assembler, - * to avoid impacting ISR speed. - */ - #include "stepper.h" Stepper stepper; // Singleton @@ -2459,6 +2438,7 @@ hal_timer_t Stepper::block_phase_isr() { acceleration_time += interval; deceleration_time = 0; // Reset since we're doing acceleration first. + // Apply Nonlinear Extrusion, if enabled calc_nonlinear_e(acc_step_rate << oversampling_factor); #if HAS_ROUGH_LIN_ADVANCE @@ -2523,6 +2503,7 @@ hal_timer_t Stepper::block_phase_isr() { interval = calc_multistep_timer_interval(step_rate << oversampling_factor); deceleration_time += interval; + // Apply Nonlinear Extrusion, if enabled calc_nonlinear_e(step_rate << oversampling_factor); #if HAS_ROUGH_LIN_ADVANCE @@ -2534,7 +2515,7 @@ hal_timer_t Stepper::block_phase_isr() { if (forward_e != motor_direction(E_AXIS)) { last_direction_bits.toggle(E_AXIS); - count_direction.e = -count_direction.e; + count_direction.e *= -1; DIR_WAIT_BEFORE(); @@ -2576,6 +2557,7 @@ hal_timer_t Stepper::block_phase_isr() { TERN_(SMOOTH_LIN_ADVANCE, curr_step_rate = current_block->nominal_rate;) deceleration_time = ticks_nominal / 2; + // Apply Nonlinear Extrusion, if enabled calc_nonlinear_e(current_block->nominal_rate << oversampling_factor); #if HAS_ROUGH_LIN_ADVANCE @@ -2717,7 +2699,7 @@ hal_timer_t Stepper::block_phase_isr() { TERN_(HAS_ROUGH_LIN_ADVANCE, la_delta_error = delta_error); // Calculate Bresenham dividends and divisors - advance_dividend = (current_block->steps << 1).asLong(); + advance_dividend = (current_block->steps << 1).asInt32(); advance_divisor = step_event_count << 1; #if ENABLED(INPUT_SHAPING_X) @@ -2847,6 +2829,7 @@ hal_timer_t Stepper::block_phase_isr() { // Initialize ac/deceleration time as if half the time passed. acceleration_time = deceleration_time = interval / 2; + // Apply Nonlinear Extrusion, if enabled calc_nonlinear_e(current_block->initial_rate << oversampling_factor); #if ENABLED(LIN_ADVANCE) @@ -2893,7 +2876,7 @@ hal_timer_t Stepper::block_phase_isr() { la_interval = calc_timer_interval(uint32_t(ABS(step_rate))); if (forward_e != motor_direction(E_AXIS)) { last_direction_bits.toggle(E_AXIS); - count_direction.e = -count_direction.e; + count_direction.e *= -1; DIR_WAIT_BEFORE(); E_APPLY_DIR(forward_e, false); TERN_(FT_MOTION, last_set_direction = last_direction_bits); @@ -3590,8 +3573,7 @@ void Stepper::report_positions() { if (last_set_direction != last_direction_bits) { // Apply directions (generally applying to the entire linear move) - #define _FTM_APPLY_DIR(A) if (last_direction_bits.A != last_set_direction.A) \ - SET_STEP_DIR(A); + #define _FTM_APPLY_DIR(A) if (last_direction_bits.A != last_set_direction.A) SET_STEP_DIR(A); LOGICAL_AXIS_MAP(_FTM_APPLY_DIR); last_set_direction = last_direction_bits; diff --git a/Marlin/src/module/stepper/control.cpp b/Marlin/src/module/stepper/control.cpp index 4d4b6b351f..ec7ec878c4 100644 --- a/Marlin/src/module/stepper/control.cpp +++ b/Marlin/src/module/stepper/control.cpp @@ -361,252 +361,268 @@ #endif #endif + #if HAS_SHARED_MICROSTEPPING_PINS + SET_OUTPUT(MS1_PIN); SET_OUTPUT(MS2_PIN); + #endif + static const uint8_t microstep_modes[] = MICROSTEP_MODES; - for (uint16_t i = 0; i < COUNT(microstep_modes); i++) - microstep_mode(i, microstep_modes[i]); + #if HAS_SHARED_MICROSTEPPING_PINS + // When using shared microstepping pins, set microstepping once for all drivers + microstep_mode(0, microstep_modes[0]); + #else + for (uint16_t i = 0; i < COUNT(microstep_modes); i++) + microstep_mode(i, microstep_modes[i]); + #endif } void Stepper::microstep_ms(const uint8_t driver, const int8_t ms1, const int8_t ms2, const int8_t ms3) { - if (ms1 >= 0) switch (driver) { - #if HAS_X_MS_PINS || HAS_X2_MS_PINS - case X_AXIS: - #if HAS_X_MS_PINS - WRITE(X_MS1_PIN, ms1); - #endif - #if HAS_X2_MS_PINS - WRITE(X2_MS1_PIN, ms1); - #endif - break; - #endif - #if HAS_Y_MS_PINS || HAS_Y2_MS_PINS - case Y_AXIS: - #if HAS_Y_MS_PINS - WRITE(Y_MS1_PIN, ms1); - #endif - #if HAS_Y2_MS_PINS - WRITE(Y2_MS1_PIN, ms1); - #endif - break; - #endif - #if HAS_SOME_Z_MS_PINS - case Z_AXIS: - #if HAS_Z_MS_PINS - WRITE(Z_MS1_PIN, ms1); - #endif - #if HAS_Z2_MS_PINS - WRITE(Z2_MS1_PIN, ms1); - #endif - #if HAS_Z3_MS_PINS - WRITE(Z3_MS1_PIN, ms1); - #endif - #if HAS_Z4_MS_PINS - WRITE(Z4_MS1_PIN, ms1); - #endif - break; - #endif - #if HAS_I_MS_PINS - case I_AXIS: WRITE(I_MS1_PIN, ms1); break; - #endif - #if HAS_J_MS_PINS - case J_AXIS: WRITE(J_MS1_PIN, ms1); break; - #endif - #if HAS_K_MS_PINS - case K_AXIS: WRITE(K_MS1_PIN, ms1); break; - #endif - #if HAS_U_MS_PINS - case U_AXIS: WRITE(U_MS1_PIN, ms1); break; - #endif - #if HAS_V_MS_PINS - case V_AXIS: WRITE(V_MS1_PIN, ms1); break; - #endif - #if HAS_W_MS_PINS - case W_AXIS: WRITE(W_MS1_PIN, ms1); break; - #endif - #if HAS_E0_MS_PINS - case E_AXIS: WRITE(E0_MS1_PIN, ms1); break; - #endif - #if HAS_E1_MS_PINS - case (E_AXIS + 1): WRITE(E1_MS1_PIN, ms1); break; - #endif - #if HAS_E2_MS_PINS - case (E_AXIS + 2): WRITE(E2_MS1_PIN, ms1); break; - #endif - #if HAS_E3_MS_PINS - case (E_AXIS + 3): WRITE(E3_MS1_PIN, ms1); break; - #endif - #if HAS_E4_MS_PINS - case (E_AXIS + 4): WRITE(E4_MS1_PIN, ms1); break; - #endif - #if HAS_E5_MS_PINS - case (E_AXIS + 5): WRITE(E5_MS1_PIN, ms1); break; - #endif - #if HAS_E6_MS_PINS - case (E_AXIS + 6): WRITE(E6_MS1_PIN, ms1); break; - #endif - #if HAS_E7_MS_PINS - case (E_AXIS + 7): WRITE(E7_MS1_PIN, ms1); break; - #endif - } - if (ms2 >= 0) switch (driver) { - #if HAS_X_MS_PINS || HAS_X2_MS_PINS - case X_AXIS: - #if HAS_X_MS_PINS - WRITE(X_MS2_PIN, ms2); - #endif - #if HAS_X2_MS_PINS - WRITE(X2_MS2_PIN, ms2); - #endif - break; - #endif - #if HAS_Y_MS_PINS || HAS_Y2_MS_PINS - case Y_AXIS: - #if HAS_Y_MS_PINS - WRITE(Y_MS2_PIN, ms2); - #endif - #if HAS_Y2_MS_PINS - WRITE(Y2_MS2_PIN, ms2); - #endif - break; - #endif - #if HAS_SOME_Z_MS_PINS - case Z_AXIS: - #if HAS_Z_MS_PINS - WRITE(Z_MS2_PIN, ms2); - #endif - #if HAS_Z2_MS_PINS - WRITE(Z2_MS2_PIN, ms2); - #endif - #if HAS_Z3_MS_PINS - WRITE(Z3_MS2_PIN, ms2); - #endif - #if HAS_Z4_MS_PINS - WRITE(Z4_MS2_PIN, ms2); - #endif - break; - #endif - #if HAS_I_MS_PINS - case I_AXIS: WRITE(I_MS2_PIN, ms2); break; - #endif - #if HAS_J_MS_PINS - case J_AXIS: WRITE(J_MS2_PIN, ms2); break; - #endif - #if HAS_K_MS_PINS - case K_AXIS: WRITE(K_MS2_PIN, ms2); break; - #endif - #if HAS_U_MS_PINS - case U_AXIS: WRITE(U_MS2_PIN, ms2); break; - #endif - #if HAS_V_MS_PINS - case V_AXIS: WRITE(V_MS2_PIN, ms2); break; - #endif - #if HAS_W_MS_PINS - case W_AXIS: WRITE(W_MS2_PIN, ms2); break; - #endif - #if HAS_E0_MS_PINS - case E_AXIS: WRITE(E0_MS2_PIN, ms2); break; - #endif - #if HAS_E1_MS_PINS - case (E_AXIS + 1): WRITE(E1_MS2_PIN, ms2); break; - #endif - #if HAS_E2_MS_PINS - case (E_AXIS + 2): WRITE(E2_MS2_PIN, ms2); break; - #endif - #if HAS_E3_MS_PINS - case (E_AXIS + 3): WRITE(E3_MS2_PIN, ms2); break; - #endif - #if HAS_E4_MS_PINS - case (E_AXIS + 4): WRITE(E4_MS2_PIN, ms2); break; - #endif - #if HAS_E5_MS_PINS - case (E_AXIS + 5): WRITE(E5_MS2_PIN, ms2); break; - #endif - #if HAS_E6_MS_PINS - case (E_AXIS + 6): WRITE(E6_MS2_PIN, ms2); break; - #endif - #if HAS_E7_MS_PINS - case (E_AXIS + 7): WRITE(E7_MS2_PIN, ms2); break; - #endif - } - if (ms3 >= 0) switch (driver) { - #if HAS_X_MS_PINS || HAS_X2_MS_PINS - case X_AXIS: - #if HAS_X_MS_PINS && PIN_EXISTS(X_MS3) - WRITE(X_MS3_PIN, ms3); - #endif - #if HAS_X2_MS_PINS && PIN_EXISTS(X2_MS3) - WRITE(X2_MS3_PIN, ms3); - #endif - break; - #endif - #if HAS_Y_MS_PINS || HAS_Y2_MS_PINS - case Y_AXIS: - #if HAS_Y_MS_PINS && PIN_EXISTS(Y_MS3) - WRITE(Y_MS3_PIN, ms3); - #endif - #if HAS_Y2_MS_PINS && PIN_EXISTS(Y2_MS3) - WRITE(Y2_MS3_PIN, ms3); - #endif - break; - #endif - #if HAS_SOME_Z_MS_PINS - case Z_AXIS: - #if HAS_Z_MS_PINS && PIN_EXISTS(Z_MS3) - WRITE(Z_MS3_PIN, ms3); - #endif - #if HAS_Z2_MS_PINS && PIN_EXISTS(Z2_MS3) - WRITE(Z2_MS3_PIN, ms3); - #endif - #if HAS_Z3_MS_PINS && PIN_EXISTS(Z3_MS3) - WRITE(Z3_MS3_PIN, ms3); - #endif - #if HAS_Z4_MS_PINS && PIN_EXISTS(Z4_MS3) - WRITE(Z4_MS3_PIN, ms3); - #endif - break; - #endif - #if HAS_I_MS_PINS && PIN_EXISTS(I_MS3) - case I_AXIS: WRITE(I_MS3_PIN, ms3); break; - #endif - #if HAS_J_MS_PINS && PIN_EXISTS(J_MS3) - case J_AXIS: WRITE(J_MS3_PIN, ms3); break; - #endif - #if HAS_K_MS_PINS && PIN_EXISTS(K_MS3) - case K_AXIS: WRITE(K_MS3_PIN, ms3); break; - #endif - #if HAS_U_MS_PINS && PIN_EXISTS(U_MS3) - case U_AXIS: WRITE(U_MS3_PIN, ms3); break; - #endif - #if HAS_V_MS_PINS && PIN_EXISTS(V_MS3) - case V_AXIS: WRITE(V_MS3_PIN, ms3); break; - #endif - #if HAS_W_MS_PINS && PIN_EXISTS(W_MS3) - case W_AXIS: WRITE(W_MS3_PIN, ms3); break; - #endif - #if HAS_E0_MS_PINS && PIN_EXISTS(E0_MS3) - case E_AXIS: WRITE(E0_MS3_PIN, ms3); break; - #endif - #if HAS_E1_MS_PINS && PIN_EXISTS(E1_MS3) - case (E_AXIS + 1): WRITE(E1_MS3_PIN, ms3); break; - #endif - #if HAS_E2_MS_PINS && PIN_EXISTS(E2_MS3) - case (E_AXIS + 2): WRITE(E2_MS3_PIN, ms3); break; - #endif - #if HAS_E3_MS_PINS && PIN_EXISTS(E3_MS3) - case (E_AXIS + 3): WRITE(E3_MS3_PIN, ms3); break; - #endif - #if HAS_E4_MS_PINS && PIN_EXISTS(E4_MS3) - case (E_AXIS + 4): WRITE(E4_MS3_PIN, ms3); break; - #endif - #if HAS_E5_MS_PINS && PIN_EXISTS(E5_MS3) - case (E_AXIS + 5): WRITE(E5_MS3_PIN, ms3); break; - #endif - #if HAS_E6_MS_PINS && PIN_EXISTS(E6_MS3) - case (E_AXIS + 6): WRITE(E6_MS3_PIN, ms3); break; - #endif - #if HAS_E7_MS_PINS && PIN_EXISTS(E7_MS3) - case (E_AXIS + 7): WRITE(E7_MS3_PIN, ms3); break; - #endif - } + #if HAS_SHARED_MICROSTEPPING_PINS + // Use shared microstepping pins for all drivers + if (ms1 >= 0) WRITE(MS1_PIN, ms1); + if (ms2 >= 0) WRITE(MS2_PIN, ms2); + // MS3 is not shared, handled per-driver below + #else // !HAS_SHARED_MICROSTEPPING_PINS + if (ms1 >= 0) switch (driver) { + #if HAS_X_MS_PINS || HAS_X2_MS_PINS + case X_AXIS: + #if HAS_X_MS_PINS + WRITE(X_MS1_PIN, ms1); + #endif + #if HAS_X2_MS_PINS + WRITE(X2_MS1_PIN, ms1); + #endif + break; + #endif + #if HAS_Y_MS_PINS || HAS_Y2_MS_PINS + case Y_AXIS: + #if HAS_Y_MS_PINS + WRITE(Y_MS1_PIN, ms1); + #endif + #if HAS_Y2_MS_PINS + WRITE(Y2_MS1_PIN, ms1); + #endif + break; + #endif + #if HAS_SOME_Z_MS_PINS + case Z_AXIS: + #if HAS_Z_MS_PINS + WRITE(Z_MS1_PIN, ms1); + #endif + #if HAS_Z2_MS_PINS + WRITE(Z2_MS1_PIN, ms1); + #endif + #if HAS_Z3_MS_PINS + WRITE(Z3_MS1_PIN, ms1); + #endif + #if HAS_Z4_MS_PINS + WRITE(Z4_MS1_PIN, ms1); + #endif + break; + #endif + #if HAS_I_MS_PINS + case I_AXIS: WRITE(I_MS1_PIN, ms1); break; + #endif + #if HAS_J_MS_PINS + case J_AXIS: WRITE(J_MS1_PIN, ms1); break; + #endif + #if HAS_K_MS_PINS + case K_AXIS: WRITE(K_MS1_PIN, ms1); break; + #endif + #if HAS_U_MS_PINS + case U_AXIS: WRITE(U_MS1_PIN, ms1); break; + #endif + #if HAS_V_MS_PINS + case V_AXIS: WRITE(V_MS1_PIN, ms1); break; + #endif + #if HAS_W_MS_PINS + case W_AXIS: WRITE(W_MS1_PIN, ms1); break; + #endif + #if HAS_E0_MS_PINS + case E_AXIS: WRITE(E0_MS1_PIN, ms1); break; + #endif + #if HAS_E1_MS_PINS + case (E_AXIS + 1): WRITE(E1_MS1_PIN, ms1); break; + #endif + #if HAS_E2_MS_PINS + case (E_AXIS + 2): WRITE(E2_MS1_PIN, ms1); break; + #endif + #if HAS_E3_MS_PINS + case (E_AXIS + 3): WRITE(E3_MS1_PIN, ms1); break; + #endif + #if HAS_E4_MS_PINS + case (E_AXIS + 4): WRITE(E4_MS1_PIN, ms1); break; + #endif + #if HAS_E5_MS_PINS + case (E_AXIS + 5): WRITE(E5_MS1_PIN, ms1); break; + #endif + #if HAS_E6_MS_PINS + case (E_AXIS + 6): WRITE(E6_MS1_PIN, ms1); break; + #endif + #if HAS_E7_MS_PINS + case (E_AXIS + 7): WRITE(E7_MS1_PIN, ms1); break; + #endif + } + if (ms2 >= 0) switch (driver) { + #if HAS_X_MS_PINS || HAS_X2_MS_PINS + case X_AXIS: + #if HAS_X_MS_PINS + WRITE(X_MS2_PIN, ms2); + #endif + #if HAS_X2_MS_PINS + WRITE(X2_MS2_PIN, ms2); + #endif + break; + #endif + #if HAS_Y_MS_PINS || HAS_Y2_MS_PINS + case Y_AXIS: + #if HAS_Y_MS_PINS + WRITE(Y_MS2_PIN, ms2); + #endif + #if HAS_Y2_MS_PINS + WRITE(Y2_MS2_PIN, ms2); + #endif + break; + #endif + #if HAS_SOME_Z_MS_PINS + case Z_AXIS: + #if HAS_Z_MS_PINS + WRITE(Z_MS2_PIN, ms2); + #endif + #if HAS_Z2_MS_PINS + WRITE(Z2_MS2_PIN, ms2); + #endif + #if HAS_Z3_MS_PINS + WRITE(Z3_MS2_PIN, ms2); + #endif + #if HAS_Z4_MS_PINS + WRITE(Z4_MS2_PIN, ms2); + #endif + break; + #endif + #if HAS_I_MS_PINS + case I_AXIS: WRITE(I_MS2_PIN, ms2); break; + #endif + #if HAS_J_MS_PINS + case J_AXIS: WRITE(J_MS2_PIN, ms2); break; + #endif + #if HAS_K_MS_PINS + case K_AXIS: WRITE(K_MS2_PIN, ms2); break; + #endif + #if HAS_U_MS_PINS + case U_AXIS: WRITE(U_MS2_PIN, ms2); break; + #endif + #if HAS_V_MS_PINS + case V_AXIS: WRITE(V_MS2_PIN, ms2); break; + #endif + #if HAS_W_MS_PINS + case W_AXIS: WRITE(W_MS2_PIN, ms2); break; + #endif + #if HAS_E0_MS_PINS + case E_AXIS: WRITE(E0_MS2_PIN, ms2); break; + #endif + #if HAS_E1_MS_PINS + case (E_AXIS + 1): WRITE(E1_MS2_PIN, ms2); break; + #endif + #if HAS_E2_MS_PINS + case (E_AXIS + 2): WRITE(E2_MS2_PIN, ms2); break; + #endif + #if HAS_E3_MS_PINS + case (E_AXIS + 3): WRITE(E3_MS2_PIN, ms2); break; + #endif + #if HAS_E4_MS_PINS + case (E_AXIS + 4): WRITE(E4_MS2_PIN, ms2); break; + #endif + #if HAS_E5_MS_PINS + case (E_AXIS + 5): WRITE(E5_MS2_PIN, ms2); break; + #endif + #if HAS_E6_MS_PINS + case (E_AXIS + 6): WRITE(E6_MS2_PIN, ms2); break; + #endif + #if HAS_E7_MS_PINS + case (E_AXIS + 7): WRITE(E7_MS2_PIN, ms2); break; + #endif + } + if (ms3 >= 0) switch (driver) { + #if HAS_X_MS_PINS || HAS_X2_MS_PINS + case X_AXIS: + #if HAS_X_MS_PINS && PIN_EXISTS(X_MS3) + WRITE(X_MS3_PIN, ms3); + #endif + #if HAS_X2_MS_PINS && PIN_EXISTS(X2_MS3) + WRITE(X2_MS3_PIN, ms3); + #endif + break; + #endif + #if HAS_Y_MS_PINS || HAS_Y2_MS_PINS + case Y_AXIS: + #if HAS_Y_MS_PINS && PIN_EXISTS(Y_MS3) + WRITE(Y_MS3_PIN, ms3); + #endif + #if HAS_Y2_MS_PINS && PIN_EXISTS(Y2_MS3) + WRITE(Y2_MS3_PIN, ms3); + #endif + break; + #endif + #if HAS_SOME_Z_MS_PINS + case Z_AXIS: + #if HAS_Z_MS_PINS && PIN_EXISTS(Z_MS3) + WRITE(Z_MS3_PIN, ms3); + #endif + #if HAS_Z2_MS_PINS && PIN_EXISTS(Z2_MS3) + WRITE(Z2_MS3_PIN, ms3); + #endif + #if HAS_Z3_MS_PINS && PIN_EXISTS(Z3_MS3) + WRITE(Z3_MS3_PIN, ms3); + #endif + #if HAS_Z4_MS_PINS && PIN_EXISTS(Z4_MS3) + WRITE(Z4_MS3_PIN, ms3); + #endif + break; + #endif + #if HAS_I_MS_PINS && PIN_EXISTS(I_MS3) + case I_AXIS: WRITE(I_MS3_PIN, ms3); break; + #endif + #if HAS_J_MS_PINS && PIN_EXISTS(J_MS3) + case J_AXIS: WRITE(J_MS3_PIN, ms3); break; + #endif + #if HAS_K_MS_PINS && PIN_EXISTS(K_MS3) + case K_AXIS: WRITE(K_MS3_PIN, ms3); break; + #endif + #if HAS_U_MS_PINS && PIN_EXISTS(U_MS3) + case U_AXIS: WRITE(U_MS3_PIN, ms3); break; + #endif + #if HAS_V_MS_PINS && PIN_EXISTS(V_MS3) + case V_AXIS: WRITE(V_MS3_PIN, ms3); break; + #endif + #if HAS_W_MS_PINS && PIN_EXISTS(W_MS3) + case W_AXIS: WRITE(W_MS3_PIN, ms3); break; + #endif + #if HAS_E0_MS_PINS && PIN_EXISTS(E0_MS3) + case E_AXIS: WRITE(E0_MS3_PIN, ms3); break; + #endif + #if HAS_E1_MS_PINS && PIN_EXISTS(E1_MS3) + case (E_AXIS + 1): WRITE(E1_MS3_PIN, ms3); break; + #endif + #if HAS_E2_MS_PINS && PIN_EXISTS(E2_MS3) + case (E_AXIS + 2): WRITE(E2_MS3_PIN, ms3); break; + #endif + #if HAS_E3_MS_PINS && PIN_EXISTS(E3_MS3) + case (E_AXIS + 3): WRITE(E3_MS3_PIN, ms3); break; + #endif + #if HAS_E4_MS_PINS && PIN_EXISTS(E4_MS3) + case (E_AXIS + 4): WRITE(E4_MS3_PIN, ms3); break; + #endif + #if HAS_E5_MS_PINS && PIN_EXISTS(E5_MS3) + case (E_AXIS + 5): WRITE(E5_MS3_PIN, ms3); break; + #endif + #if HAS_E6_MS_PINS && PIN_EXISTS(E6_MS3) + case (E_AXIS + 6): WRITE(E6_MS3_PIN, ms3); break; + #endif + #if HAS_E7_MS_PINS && PIN_EXISTS(E7_MS3) + case (E_AXIS + 7): WRITE(E7_MS3_PIN, ms3); break; + #endif + } + #endif // !HAS_SHARED_MICROSTEPPING_PINS } // MS1 MS2 MS3 Stepper Driver Microstepping mode table diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index a3f625c0eb..fa84cec25d 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -1122,7 +1122,7 @@ void Temperature::factory_reset() { if (ELAPSED(curr_time_ms, next_test_ms)) { if (current_temp >= ambient_temp) { - ambient_temp = (ambient_temp + current_temp) / 2.0f; + ambient_temp = (ambient_temp + current_temp) * 0.5f; break; } ambient_temp = current_temp; @@ -1884,7 +1884,7 @@ void Temperature::mintemp_error(const heater_id_t heater_id OPTARG(ERR_INCLUDE_T float power = 0.0; if (hotend.target != 0 && !is_idling) { // Plan power level to get to target temperature in 2 seconds - power = (hotend.target - hotend.modeled_block_temp) * mpc.block_heat_capacity / 2.0f; + power = (hotend.target - hotend.modeled_block_temp) * mpc.block_heat_capacity * 0.5f; power -= (hotend.modeled_ambient_temp - hotend.modeled_block_temp) * ambient_xfer_coeff; } @@ -2602,7 +2602,7 @@ void Temperature::task() { #if ANY_THERMISTOR_IS(-1) // For a 5V input the AD595 returns a value scaled with 10mV per °C. (Minimum input voltage is 5V.) static constexpr celsius_float_t temp_ad595(const raw_adc_t raw) { - return raw * (float(ADC_VREF_MV) / 10.0f) / float(HAL_ADC_RANGE) / (OVERSAMPLENR) + return raw * (float(ADC_VREF_MV) * 0.1f) / float(HAL_ADC_RANGE) / (OVERSAMPLENR) * (TEMP_SENSOR_AD595_GAIN) + (TEMP_SENSOR_AD595_OFFSET); } #endif diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index ecf15758e0..abe4673407 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -854,8 +854,10 @@ #include "stm32h7/pins_BTT_MANTA_M8P_V2_0.h" // STM32H7 env:STM32H723ZE_btt #elif MB(BTT_KRAKEN_V1_0) #include "stm32h7/pins_BTT_KRAKEN_V1_0.h" // STM32H7 env:STM32H723ZG_btt +#elif MB(TEENSY40) + #include "teensy4/pins_TEENSY40.h" // Teensy-4.0 env:teensy40 #elif MB(TEENSY41) - #include "teensy4/pins_TEENSY41.h" // Teensy-4.x env:teensy41 + #include "teensy4/pins_TEENSY41.h" // Teensy-4.1 env:teensy41 #elif MB(T41U5XBB) #include "teensy4/pins_T41U5XBB.h" // Teensy-4.x env:teensy41 #elif MB(FLY_D8_PRO) diff --git a/Marlin/src/pins/rambo/pins_RAMBO_THINKERV2.h b/Marlin/src/pins/rambo/pins_RAMBO_THINKERV2.h old mode 100755 new mode 100644 diff --git a/Marlin/src/pins/ramps/pins_PANOWIN_CUTLASS.h b/Marlin/src/pins/ramps/pins_PANOWIN_CUTLASS.h old mode 100755 new mode 100644 diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D_V9.h b/Marlin/src/pins/stm32f1/pins_CHITU3D_V9.h old mode 100755 new mode 100644 diff --git a/Marlin/src/pins/teensy4/env_validate.h b/Marlin/src/pins/teensy4/env_validate.h index 5a89e8a409..38b94a636d 100644 --- a/Marlin/src/pins/teensy4/env_validate.h +++ b/Marlin/src/pins/teensy4/env_validate.h @@ -21,6 +21,8 @@ */ #pragma once -#if NOT_TARGET(IS_TEENSY41) +#if defined(IS_TEENSY40) && NOT_TARGET(IS_TEENSY40) + #error "Oops! Select 'Teensy 4.0' in 'Tools > Board.'" +#elif defined(IS_TEENSY41) && NOT_TARGET(IS_TEENSY41) #error "Oops! Select 'Teensy 4.1' in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/teensy4/pins_TEENSY40.h b/Marlin/src/pins/teensy4/pins_TEENSY40.h new file mode 100644 index 0000000000..88c8ccf97e --- /dev/null +++ b/Marlin/src/pins/teensy4/pins_TEENSY40.h @@ -0,0 +1,34 @@ +/** + * 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 + +/**************************************************************************************** +* Teensy 4.0 (IMXRT1062) Breadboard pin assignments +* Requires the Teensyduino software with Teensy 4.0 selected in Arduino IDE! +* https://www.pjrc.com/teensy/teensyduino.html +****************************************************************************************/ + +#include "env_validate.h" + +#define BOARD_INFO_NAME "Teensy4.0" + +#include "pins_TEENSY4x.h" diff --git a/Marlin/src/pins/teensy4/pins_TEENSY41.h b/Marlin/src/pins/teensy4/pins_TEENSY41.h index 2a8a76f17c..121514e463 100644 --- a/Marlin/src/pins/teensy4/pins_TEENSY41.h +++ b/Marlin/src/pins/teensy4/pins_TEENSY41.h @@ -31,99 +31,11 @@ #define BOARD_INFO_NAME "Teensy4.1" -/** - * Plan for Teensy 4.0 and Teensy 4.1: - * USB - * GND |-----#####-----| VIN (3.65 TO 5.5V) - * X_STEP_PIN CS1 RX1 PWM 0 | ##### | GND - * X_DIR_PIN MISO1 TX1 PWM 1 | | 3.3V - * Y_STEP_PIN PWM 2 | | 23 A9 PWM SERVO1_PIN - * Y_DIR_PIN PWM 3 | | 22 A8 PWM SERVO0_PIN - * Z_STEP_PIN PWM 4 | | 21 A7 RX5 - * Z_DIR_PIN PWM 5 | | 20 A6 TX5 FILWIDTH_PIN - * X_ENABLE_PIN PWM 6 | | 19 A5 PWM SCL0 - * Y_ENABLE_PIN RX2 PWM 7 | | 18 A4 PWM SDA0 HEATER_1_PIN - * Z_ENABLE_PIN TX2 PWM 8 | | 17 A3 RX4 SDA1 - * E0_STEP_PIN PWM 9 | | 16 A2 TX4 SCL1 TEMP_0_PIN - * E0_DIR_PIN PWM 10 | | 15 A1 PWM RX3 TEMP_BED_PIN - * MOSI_PIN MOSI0 PWM 11 | | 14 A0 PWM TX3 TEMP_1_PIN - * MISO_PIN MISO0 PWM 12 | | 13 LED PWM SCK0 SCK_PIN - * 3.3V | | GND - * Z_STOP_PIN PWM 24 | | 41 A17 - * E0_ENABLE_PIN PWM 25 | | 40 A16 - * FAN0_PIN MOSI1 26 | | 39 A15 MISO1 X_STOP_PIN - * Z-PROBE PWR SCK1 27 | * * * * * | 38 A14 Y_STOP_PIN - * SOL1_PIN RX7 PWM 28 | | 37 PWM HEATER_0_PIN - * FAN0_PIN TX7 PWM 29 | | 36 PWM HEATER_BED_PIN - * X_CS_PIN 30 | | 35 TX8 E1_ENABLE_PIN - * y_CS_PIN 31 | SDCARD | 34 RX8 E1_DIR_PIN - * Z_CS_PIN 32 |_______________| 33 PWM E1_STEP_PIN - */ +#include "pins_TEENSY4x.h" -// -// Servos -// -#define SERVO0_PIN 22 -#define SERVO1_PIN 23 - -// -// Limit Switches -// -#define X_STOP_PIN 39 -#define Y_STOP_PIN 38 -#define Z_STOP_PIN 24 - -// -// Steppers -// -#define X_STEP_PIN 0 -#define X_DIR_PIN 1 -#define X_ENABLE_PIN 6 -//#define X_CS_PIN 30 - -#define Y_STEP_PIN 2 -#define Y_DIR_PIN 3 -#define Y_ENABLE_PIN 7 -//#define Y_CS_PIN 31 - -#define Z_STEP_PIN 4 -#define Z_DIR_PIN 5 -#define Z_ENABLE_PIN 8 -//#define Z_CS_PIN 32 - -#define E0_STEP_PIN 9 -#define E0_DIR_PIN 10 -#define E0_ENABLE_PIN 25 - -#define E1_STEP_PIN 33 -#define E1_DIR_PIN 34 -#define E1_ENABLE_PIN 35 - -// -// Heaters / Fans -// -#define HEATER_0_PIN 37 -#define HEATER_1_PIN 18 -#define HEATER_BED_PIN 36 -#ifndef FAN0_PIN - #define FAN0_PIN 29 -#endif - -// -// Temperature Sensors -// -#define TEMP_0_PIN 2 // Extruder / Analog pin numbering: 2 => A2 -#define TEMP_1_PIN 0 -#define TEMP_BED_PIN 1 // Bed / Analog pin numbering - -// -// Misc. Functions -// -#define LED_PIN 13 -#define SOL0_PIN 28 -//#define PS_ON_PIN 1 -//#define FILWIDTH_PIN 6 // A6 - -#ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION ONBOARD +// For the Ethernet Kit or WIZ812 +// https://www.pjrc.com/store/ethernet_kit.html +// https://www.pjrc.com/teensy/td_libs_Ethernet.html) +#if HAS_ETHERNET + #define ETHERNET_CS_PIN 10 // W5x00 module #endif diff --git a/Marlin/src/pins/teensy4/pins_TEENSY4x.h b/Marlin/src/pins/teensy4/pins_TEENSY4x.h new file mode 100644 index 0000000000..251f7533b3 --- /dev/null +++ b/Marlin/src/pins/teensy4/pins_TEENSY4x.h @@ -0,0 +1,127 @@ +/** + * 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 + +/**************************************************************************************** +* Teensy 4.x (IMXRT1062) Breadboard pin assignments +* Requires the Teensyduino software with Teensy 4.0 / 4.1 selected in Arduino IDE! +* https://www.pjrc.com/teensy/teensyduino.html +****************************************************************************************/ + +#include "env_validate.h" + +/** + * Plan for Teensy 4.0 and Teensy 4.1: + * USB + * GND |-----#####-----| VIN (3.65 TO 5.5V) + * X_STEP_PIN CS1 RX1 PWM 0 | ##### | GND + * X_DIR_PIN MISO1 TX1 PWM 1 | | 3.3V + * Y_STEP_PIN PWM 2 | | 23 A9 PWM SERVO1_PIN + * Y_DIR_PIN PWM 3 | | 22 A8 PWM SERVO0_PIN + * Z_STEP_PIN PWM 4 | | 21 A7 RX5 + * Z_DIR_PIN PWM 5 | | 20 A6 TX5 FILWIDTH_PIN + * X_ENABLE_PIN PWM 6 | | 19 A5 PWM SCL0 + * Y_ENABLE_PIN RX2 PWM 7 | | 18 A4 PWM SDA0 HEATER_1_PIN + * Z_ENABLE_PIN TX2 PWM 8 | | 17 A3 RX4 SDA1 + * E0_STEP_PIN PWM 9 | | 16 A2 TX4 SCL1 TEMP_0_PIN + * E0_DIR_PIN PWM 10 | | 15 A1 PWM RX3 TEMP_BED_PIN + * MOSI_PIN MOSI0 PWM 11 | | 14 A0 PWM TX3 TEMP_1_PIN + * MISO_PIN MISO0 PWM 12 | | 13 LED PWM SCK0 SCK_PIN + * 3.3V | | GND + * Z_STOP_PIN PWM 24 | | 41 A17 + * E0_ENABLE_PIN PWM 25 | | 40 A16 + * FAN0_PIN MOSI1 26 | | 39 A15 MISO1 X_STOP_PIN + * Z-PROBE PWR SCK1 27 | * * * * * | 38 A14 Y_STOP_PIN + * SOL1_PIN RX7 PWM 28 | | 37 PWM HEATER_0_PIN + * FAN0_PIN TX7 PWM 29 | | 36 PWM HEATER_BED_PIN + * X_CS_PIN 30 | | 35 TX8 E1_ENABLE_PIN + * y_CS_PIN 31 | SDCARD | 34 RX8 E1_DIR_PIN + * Z_CS_PIN 32 |_______________| 33 PWM E1_STEP_PIN + */ + +// +// Servos +// +#define SERVO0_PIN 22 +#define SERVO1_PIN 23 + +// +// Limit Switches +// +#define X_STOP_PIN 39 +#define Y_STOP_PIN 38 +#define Z_STOP_PIN 24 + +// +// Steppers +// +#define X_STEP_PIN 0 +#define X_DIR_PIN 1 +#define X_ENABLE_PIN 6 +//#define X_CS_PIN 30 + +#define Y_STEP_PIN 2 +#define Y_DIR_PIN 3 +#define Y_ENABLE_PIN 7 +//#define Y_CS_PIN 31 + +#define Z_STEP_PIN 4 +#define Z_DIR_PIN 5 +#define Z_ENABLE_PIN 8 +//#define Z_CS_PIN 32 + +#define E0_STEP_PIN 9 +#define E0_DIR_PIN 10 +#define E0_ENABLE_PIN 25 + +#define E1_STEP_PIN 33 +#define E1_DIR_PIN 34 +#define E1_ENABLE_PIN 35 + +// +// Heaters / Fans +// +#define HEATER_0_PIN 37 +#define HEATER_1_PIN 18 +#define HEATER_BED_PIN 36 +#ifndef FAN0_PIN + #define FAN0_PIN 29 +#endif + +// +// Temperature Sensors +// +#define TEMP_0_PIN 2 // Extruder / Analog pin numbering: 2 => A2 +#define TEMP_1_PIN 0 +#define TEMP_BED_PIN 1 // Bed / Analog pin numbering + +// +// Misc. Functions +// +#define LED_PIN 13 +#define SOL0_PIN 28 +//#define PS_ON_PIN 1 +//#define FILWIDTH_PIN 6 // A6 + +#ifndef SDCARD_CONNECTION + #define SDCARD_CONNECTION ONBOARD +#endif diff --git a/Marlin/src/sd/Sd2Card.cpp b/Marlin/src/sd/Sd2Card.cpp index 25fc35e6ab..97157f9718 100644 --- a/Marlin/src/sd/Sd2Card.cpp +++ b/Marlin/src/sd/Sd2Card.cpp @@ -42,22 +42,22 @@ #if DISABLED(SD_NO_DEFAULT_TIMEOUT) #ifndef SD_INIT_TIMEOUT - #define SD_INIT_TIMEOUT 2000u // (ms) Init timeout + #define SD_INIT_TIMEOUT 2000U // (ms) Init timeout #elif SD_INIT_TIMEOUT < 0 #error "SD_INIT_TIMEOUT must be greater than or equal to 0." #endif #ifndef SD_ERASE_TIMEOUT - #define SD_ERASE_TIMEOUT 10000u // (ms) Erase timeout + #define SD_ERASE_TIMEOUT 10000U // (ms) Erase timeout #elif SD_ERASE_TIMEOUT < 0 #error "SD_ERASE_TIMEOUT must be greater than or equal to 0." #endif #ifndef SD_READ_TIMEOUT - #define SD_READ_TIMEOUT 300u // (ms) Read timeout + #define SD_READ_TIMEOUT 300U // (ms) Read timeout #elif SD_READ_TIMEOUT < 0 #error "SD_READ_TIMEOUT must be greater than or equal to 0." #endif #ifndef SD_WRITE_TIMEOUT - #define SD_WRITE_TIMEOUT 600u // (ms) Write timeout + #define SD_WRITE_TIMEOUT 600U // (ms) Write timeout #elif SD_WRITE_TIMEOUT < 0 #error "SD_WRITE_TIMEOUT must be greater than or equal to 0." #endif diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 9a5394d5e7..1d6fa06998 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -1328,171 +1328,6 @@ void CardReader::cdroot() { #endif #endif - #if ENABLED(SDSORT_QUICK) - - // Quick Sort - bool CardReader::sort_cmp_files(const int16_t o1, const int16_t o2) { - auto _sort_cmp_file = [](const char *const n1, const char *const n2) -> bool { - const bool sort = strcasecmp(n1, n2) < 0; - return (TERN(SDSORT_GCODE, sort_alpha == AS_REV, ENABLED(SDSORT_REVERSE))) ? !sort : sort; - }; - - #if ENABLED(SDSORT_USES_RAM) - const bool dir1 = IS_DIR(o1), dir2 = IS_DIR(o2); - const char *name1 = card.sortnames[o1], *name2 = card.sortnames[o2]; - #else - card.selectFileByIndex(o1); - char name1_buffer[LONG_FILENAME_LENGTH]; - strcpy(name1_buffer, card.longest_filename()); - const char *name1 = name1_buffer; - const bool dir1 = card.flag.filenameIsDir; - - card.selectFileByIndex(o2); - const char *name2 = card.longest_filename(); - const bool dir2 = card.flag.filenameIsDir; - #endif - - #if HAS_FOLDER_SORTING - #if ENABLED(SDSORT_GCODE) - if (card.sort_folders && dir1 != dir2) - return (card.sort_folders > 0) ? dir1 : !dir1; - #else - if (dir1 != dir2) - return (SDSORT_FOLDERS > 0) ? dir1 : !dir1; - #endif - #endif - - return _sort_cmp_file(name1, name2); - } - - int16_t CardReader::partition(uint8_t* arr, int16_t low, int16_t high) { - int16_t pivotIndex = arr[high]; - int16_t i = (low - 1); - - for (int16_t j = low; j < high; j++) { - if (sort_cmp_files(arr[j], pivotIndex)) { - i++; - uint8_t temp = arr[i]; - arr[i] = arr[j]; - arr[j] = temp; - } - } - // Manual swap - uint8_t temp = arr[i + 1]; - arr[i + 1] = arr[high]; - arr[high] = temp; - return (i + 1); - } - - void CardReader::quicksort(uint8_t* arr, int16_t low, int16_t high) { - int16_t stack[SDSORT_LIMIT + 1]; - int16_t top = -1; // Initialize top of stack - - // Push initial values to the stack - stack[++top] = low; - stack[++top] = high; - - // Pop from stack while not empty - while (top >= 0) { - high = stack[top--]; - low = stack[top--]; - - // Set pivot element at correct position - const int16_t pivot = partition(arr, low, high); - // If elements are on left side, push to stack - if (pivot - 1 > low) { - stack[++top] = low; - stack[++top] = pivot - 1; - } - // If elements are on right side, push to stack - if (pivot + 1 < high) { - stack[++top] = pivot + 1; - stack[++top] = high; - } - } - } - - #else // !SDSORT_QUICK - - // Bubble Sort - void CardReader::bubblesort(uint8_t* arr, int16_t fileCnt) { - for (int16_t i = fileCnt; --i;) { - bool didSwap = false; - int16_t o1 = arr[0]; - #if DISABLED(SDSORT_USES_RAM) - // By default re-read the names from SD for every compare - // retaining only two filenames at a time. This is very - // slow but is safest and uses minimal RAM. - char name1[LONG_FILENAME_LENGTH]; - selectFileByIndex(o1); // Pre-fetch the first entry and save it - strcpy(name1, longest_filename()); // so the loop only needs one fetch - #if HAS_FOLDER_SORTING - bool dir1 = flag.filenameIsDir; - #endif - if ((i & 0x7) == 7) hal.watchdog_refresh(); - #endif - - for (int16_t j = 0; j < i; ++j) { - const int16_t o2 = arr[j + 1]; - - // Compare names from the array or just the two buffered names - auto _sort_cmp_file = [](char * const n1, char * const n2) -> bool { - const bool sort = strcasecmp(n1, n2) > 0; - return (TERN(SDSORT_GCODE, sort_alpha == AS_REV, ENABLED(SDSORT_REVERSE))) ? !sort : sort; - }; - #define _SORT_CMP_FILE() _sort_cmp_file(TERN(SDSORT_USES_RAM, sortnames[o1], name1), TERN(SDSORT_USES_RAM, sortnames[o2], name2)) - - #if HAS_FOLDER_SORTING - #if ENABLED(SDSORT_USES_RAM) - // Folder sorting needs an index and bit to test for folder-ness. - #define _SORT_CMP_DIR(fs) (IS_DIR(o1) == IS_DIR(o2) ? _SORT_CMP_FILE() : IS_DIR(fs > 0 ? o1 : o2)) - #else - #define _SORT_CMP_DIR(fs) ((dir1 == flag.filenameIsDir) ? _SORT_CMP_FILE() : (fs > 0 ? dir1 : !dir1)) - #endif - #endif - - // The most economical method reads names as-needed - // throughout the loop. Slow if there are many. - #if DISABLED(SDSORT_USES_RAM) - selectFileByIndex(o2); - const bool dir2 = flag.filenameIsDir; - char * const name2 = longest_filename(); // Use the string in-place - if ((i & 0x7) == 7) hal.watchdog_refresh(); - #endif - - // Sort the current pair according to settings. - if ( - #if HAS_FOLDER_SORTING - #if ENABLED(SDSORT_GCODE) - sort_folders ? _SORT_CMP_DIR(sort_folders) : _SORT_CMP_FILE() - #else - _SORT_CMP_DIR(SDSORT_FOLDERS) - #endif - #else - _SORT_CMP_FILE() - #endif - ) { - // Reorder the index, indicate that sorting happened - // Note that the next o1 will be the current o1. No new fetch needed. - arr[j] = o2; - arr[j + 1] = o1; - didSwap = true; - } - else { - // The next o1 is the current o2. No new fetch needed. - o1 = o2; - #if DISABLED(SDSORT_USES_RAM) - TERN_(HAS_FOLDER_SORTING, dir1 = dir2); - strcpy(name1, name2); - #endif - } - } - if (!didSwap) break; - } - } - - #endif // !SDSORT_QUICK - /** * Read all the files and produce a sort key * @@ -1543,6 +1378,13 @@ void CardReader::cdroot() { #endif #endif + #else // !SDSORT_USES_RAM + + // By default re-read the names from SD for every compare + // retaining only two filenames at a time. This is very + // slow but is safest and uses minimal RAM. + char name1[LONG_FILENAME_LENGTH]; + #endif if (fileCnt > 1) { @@ -1564,15 +1406,171 @@ void CardReader::cdroot() { if (flag.filenameIsDir) SBI(isDir[ind], bit); #endif #endif - if ((i & 0x7) == 7) hal.watchdog_refresh(); } - // Sorting Algorithm #if ENABLED(SDSORT_QUICK) - quicksort(sort_order, 0, fileCnt - 1); + { + auto sort_cmp_files = [&](const int16_t o1, const int16_t o2) -> bool { + #if DISABLED(SDSORT_USES_RAM) + char name1[LONG_FILENAME_LENGTH]; + selectFileByIndex(o1); + strcpy(name1, longest_filename()); + #if HAS_FOLDER_SORTING + const bool dir1 = flag.filenameIsDir; + #endif + selectFileByIndex(o2); + const char *name2 = longest_filename(); + #if HAS_FOLDER_SORTING + const bool dir2 = flag.filenameIsDir; + #endif + #else + #if HAS_FOLDER_SORTING + const bool dir1 = IS_DIR(o1), dir2 = IS_DIR(o2); + #endif + const char *name1 = sortnames[o1], *name2 = sortnames[o2]; + #endif + + #if HAS_FOLDER_SORTING + #if ENABLED(SDSORT_GCODE) + if (sort_folders && dir1 != dir2) + return (sort_folders > 0) ? dir1 : !dir1; + #else + if (dir1 != dir2) + return (SDSORT_FOLDERS > 0) ? dir1 : !dir1; + #endif + #endif + + const bool sort = strcasecmp(name1, name2) < 0; + return (TERN(SDSORT_GCODE, sort_alpha == AS_REV, ENABLED(SDSORT_REVERSE))) ? !sort : sort; + }; + + auto partition = [&](uint8_t* arr, int16_t low, int16_t high) -> int16_t { + int16_t pivotIndex = arr[high]; + int16_t i = (low - 1); + + for (int16_t j = low; j < high; j++) { + if (sort_cmp_files(arr[j], pivotIndex)) { + i++; + uint8_t temp = arr[i]; + arr[i] = arr[j]; + arr[j] = temp; + } + } + // Manual swap + uint8_t temp = arr[i + 1]; + arr[i + 1] = arr[high]; + arr[high] = temp; + return (i + 1); + }; + + // Quick Sort + int16_t stack[SDSORT_LIMIT + 1]; + int16_t top = -1; // Initialize top of stack + + int16_t low = 0, high = fileCnt - 1; + + // Push initial values to the stack + stack[++top] = low; + stack[++top] = high; + + // Pop from stack while not empty + while (top >= 0) { + high = stack[top--]; + low = stack[top--]; + + // Set pivot element at correct position + const int16_t pivot = partition(sort_order, low, high); + + // If elements are on left side, push to stack + if (pivot - 1 > low) { + stack[++top] = low; + stack[++top] = pivot - 1; + } + // If elements are on right side, push to stack + if (pivot + 1 < high) { + stack[++top] = pivot + 1; + stack[++top] = high; + } + } + + } #else - bubblesort(sort_order, fileCnt); - #endif + { + // Bubble Sort + for (int16_t i = fileCnt; --i;) { + bool didSwap = false; + int16_t o1 = sort_order[0]; + #if DISABLED(SDSORT_USES_RAM) + // By default re-read the names from SD for every compare + // retaining only two filenames at a time. This is very + // slow but is safest and uses minimal RAM. + selectFileByIndex(o1); // Pre-fetch the first entry and save it + strcpy(name1, longest_filename()); // so the loop only needs one fetch + #if HAS_FOLDER_SORTING + bool dir1 = flag.filenameIsDir; + #endif + if ((i & 0x7) == 7) hal.watchdog_refresh(); + #endif + + for (int16_t j = 0; j < i; ++j) { + const int16_t o2 = sort_order[j + 1]; + + // Compare names from the array or just the two buffered names + auto _sort_cmp_file = [](char * const n1, char * const n2) -> bool { + const bool sort = strcasecmp(n1, n2) > 0; + return (TERN(SDSORT_GCODE, sort_alpha == AS_REV, ENABLED(SDSORT_REVERSE))) ? !sort : sort; + }; + #define _SORT_CMP_FILE() _sort_cmp_file(TERN(SDSORT_USES_RAM, sortnames[o1], name1), TERN(SDSORT_USES_RAM, sortnames[o2], name2)) + + #if HAS_FOLDER_SORTING + #if ENABLED(SDSORT_USES_RAM) + // Folder sorting needs an index and bit to test for folder-ness. + #define _SORT_CMP_DIR(fs) (IS_DIR(o1) == IS_DIR(o2) ? _SORT_CMP_FILE() : IS_DIR(fs > 0 ? o1 : o2)) + #else + #define _SORT_CMP_DIR(fs) ((dir1 == flag.filenameIsDir) ? _SORT_CMP_FILE() : (fs > 0 ? dir1 : !dir1)) + #endif + #endif + + // The most economical method reads names as-needed + // throughout the loop. Slow if there are many. + #if DISABLED(SDSORT_USES_RAM) + selectFileByIndex(o2); + const bool dir2 = flag.filenameIsDir; + char * const name2 = longest_filename(); // Use the string in-place + if ((i & 0x7) == 7) hal.watchdog_refresh(); + #endif + + // Sort the current pair according to settings. + if ( + #if HAS_FOLDER_SORTING + #if ENABLED(SDSORT_GCODE) + sort_folders ? _SORT_CMP_DIR(sort_folders) : _SORT_CMP_FILE() + #else + _SORT_CMP_DIR(SDSORT_FOLDERS) + #endif + #else + _SORT_CMP_FILE() + #endif + ) { + // Reorder the index, indicate that sorting happened + // Note that the next o1 will be the current o1. No new fetch needed. + sort_order[j] = o2; + sort_order[j + 1] = o1; + didSwap = true; + } + else { + // The next o1 is the current o2. No new fetch needed. + o1 = o2; + #if DISABLED(SDSORT_USES_RAM) + TERN_(HAS_FOLDER_SORTING, dir1 = dir2); + strcpy(name1, name2); + #endif + } + } + if (!didSwap) break; + } + } + #endif // Bubble Sort // Using RAM but not keeping names around #if ENABLED(SDSORT_USES_RAM) && DISABLED(SDSORT_CACHE_NAMES) diff --git a/Marlin/src/sd/cardreader.h b/Marlin/src/sd/cardreader.h index 5f1d99a561..c6b3dc6384 100644 --- a/Marlin/src/sd/cardreader.h +++ b/Marlin/src/sd/cardreader.h @@ -403,10 +403,6 @@ private: #endif // SDSORT_USES_RAM static void flush_presort(); - static bool sort_cmp_files(const int16_t o1, const int16_t o2); - static int16_t partition(uint8_t* arr, int16_t low, int16_t high); - static void quicksort(uint8_t* arr, int16_t low, int16_t high); - static void bubblesort(uint8_t* arr, int16_t fileCnt); #endif // SDCARD_SORT_ALPHA // diff --git a/Marlin/tests/core/test_macros.cpp b/Marlin/tests/core/test_macros.cpp index bb269dec2b..75a1e88f71 100644 --- a/Marlin/tests/core/test_macros.cpp +++ b/Marlin/tests/core/test_macros.cpp @@ -251,14 +251,14 @@ MARLIN_TEST(macros_numeric, NOLESS_int) { MARLIN_TEST(macros_numeric, NOLESS_uint) { // Scenario 1: Input was already acceptable - unsigned int b = 8u; - NOLESS(b, 5u); - TEST_ASSERT_EQUAL(8u, b); + unsigned int b = 8U; + NOLESS(b, 5U); + TEST_ASSERT_EQUAL(8U, b); // Original scenario: Input was less than the limit - b = 5u; - NOLESS(b, 10u); - TEST_ASSERT_EQUAL(10u, b); + b = 5U; + NOLESS(b, 10U); + TEST_ASSERT_EQUAL(10U, b); } MARLIN_TEST(macros_numeric, NOLESS_float) { @@ -310,14 +310,14 @@ MARLIN_TEST(macros_numeric, NOMORE_int) { MARLIN_TEST(macros_numeric, NOMORE_uint) { // Scenario 1: Input was already acceptable - unsigned int b = 8u; - NOMORE(b, 10u); - TEST_ASSERT_EQUAL(8u, b); + unsigned int b = 8U; + NOMORE(b, 10U); + TEST_ASSERT_EQUAL(8U, b); // Original scenario: Input was more than the limit - b = 15u; - NOMORE(b, 10u); - TEST_ASSERT_EQUAL(10u, b); + b = 15U; + NOMORE(b, 10U); + TEST_ASSERT_EQUAL(10U, b); } MARLIN_TEST(macros_numeric, NOMORE_float) { @@ -383,17 +383,17 @@ MARLIN_TEST(macros_numeric, LIMIT_int) { } MARLIN_TEST(macros_numeric, LIMIT_uint) { - unsigned int b = 15u; - LIMIT(b, 10u, 20u); - TEST_ASSERT_EQUAL(15u, b); + unsigned int b = 15U; + LIMIT(b, 10U, 20U); + TEST_ASSERT_EQUAL(15U, b); - b = 5u; - LIMIT(b, 10u, 20u); - TEST_ASSERT_EQUAL(10u, b); + b = 5U; + LIMIT(b, 10U, 20U); + TEST_ASSERT_EQUAL(10U, b); - b = 25u; - LIMIT(b, 10u, 20u); - TEST_ASSERT_EQUAL(20u, b); + b = 25U; + LIMIT(b, 10U, 20U); + TEST_ASSERT_EQUAL(20U, b); } MARLIN_TEST(macros_numeric, LIMIT_float) { diff --git a/Marlin/tests/feature/test_runout.cpp b/Marlin/tests/feature/test_runout.cpp index 2719446437..296e70916d 100644 --- a/Marlin/tests/feature/test_runout.cpp +++ b/Marlin/tests/feature/test_runout.cpp @@ -29,7 +29,7 @@ MARLIN_TEST(runout, poll_runout_states) { FilamentSensorBase sensor; // Expected default value is one bit set for each extruder - uint8_t expected = static_cast(~(~0u << NUM_RUNOUT_SENSORS)); + uint8_t expected = static_cast(~(~0U << NUM_RUNOUT_SENSORS)); TEST_ASSERT_EQUAL(expected, sensor.poll_runout_states()); } diff --git a/README.md b/README.md index 90815578c8..45e91d62c0 100644 --- a/README.md +++ b/README.md @@ -63,7 +63,8 @@ -Additional documentation can be found at the [Marlin Home Page](//marlinfw.org/). +Official documentation can be found at the [Marlin Home Page](//marlinfw.org/). + Please test this firmware and let us know if it misbehaves in any way. Volunteers are standing by! --- @@ -72,7 +73,7 @@ Please test this firmware and let us know if it misbehaves in any way. Volunteer **Not for production use. Use with caution!** -Marlin 2.1 continues to support both 32-bit ARM and 8-bit AVR boards while adding support for up to 9 coordinated axes and to up to 8 extruders. +Marlin 2.1 supports both 32-bit ARM and 8-bit AVR boards while adding support for up to 9 coordinated axes and to up to 8 extruders. This branch is for patches to the latest 2.1.x release version. Periodically this branch will form the basis for the next minor 2.1.x release. @@ -80,27 +81,32 @@ Download earlier versions of Marlin on the [Releases page](//github.com/MarlinFi ## Example Configurations -Before you can build Marlin for your machine you'll need a configuration for your specific hardware. Upon request, your vendor will be happy to provide you with the complete source code and configurations for your machine, but you'll need to get updated configuration files if you want to install a newer version of Marlin. Fortunately, Marlin users have contributed dozens of tested configurations to get you started. Visit the [MarlinFirmware/Configurations](//github.com/MarlinFirmware/Configurations) repository to find the right configuration for your hardware. +Before you can build Marlin for your machine you'll need a configuration for your specific hardware. Upon request, your vendor will be happy to provide you with the complete source code and configurations for your machine, but you'll need to get updated configuration files if you want to install a newer version of Marlin. Fortunately, Marlin users have contributed hundreds of tested configurations to get you started. Visit the [MarlinFirmware/Configurations](//github.com/MarlinFirmware/Configurations) repository to find the right configuration for your hardware. Make sure to select a compatible branch! [The Marlin Download Page](//marlinfw.org/meta/download/) matches compatible software and configuration packages. ## Building Marlin 2.1 To build and upload Marlin you will use one of these tools: - The free [Visual Studio Code](//code.visualstudio.com/download) using the [Auto Build Marlin](//marlinfw.org/docs/basics/auto_build_marlin.html) extension. -- The free [Arduino IDE](//www.arduino.cc/en/main/software) : See [Building Marlin with Arduino](//marlinfw.org/docs/basics/install_arduino.html) +- Marlin is optimized to build with the [PlatformIO IDE](//platformio.org/) extension for Visual Studio Code. - You can also use VSCode with devcontainer : See [Installing Marlin (VSCode devcontainer)](http://marlinfw.org/docs/basics/install_devcontainer_vscode.html). +- You can still build Marlin with [Arduino IDE](//www.arduino.cc/en/main/software) : See [Building Marlin with Arduino](//marlinfw.org/docs/basics/install_arduino.html). We hope to improve the Arduino build experience, but at this time, PlatformIO is the preferred choice. -Marlin is optimized to build with the **PlatformIO IDE** extension for **Visual Studio Code**. You can still build Marlin with **Arduino IDE**, and we hope to improve the Arduino build experience, but at this time PlatformIO is the better choice. +## 32-bit ARM boards + +Marlin is compatible with a plethora of 32-bit ARM boards, which offer ample computational power and memory and allows Marlin to deliver state-of-the-art performance and features we like to see in modern 3d printers. Some of the newer features in Marlin will require use of a 32-bit ARM board. ## 8-Bit AVR Boards -We intend to continue supporting 8-bit AVR boards in perpetuity, maintaining a single codebase that can apply to all machines. We want casual hobbyists and tinkerers and owners of older machines to benefit from the community's innovations just as much as those with fancier machines. Plus, those old AVR-based machines are often the best for your testing and feedback! +Marlin originates from the era of Arduino based 8-bit boards, and we aim to support 8-bit AVR boards in perpetuity. Both 32-bit and 8-bit boards are covered by a single code base that can apply to all machines. Our goal is to support casual hobbyists, tinkerers, and owners of older machines and boards, striving to allow them to benefit from the community's innovations just as much as those with fancier machines and newer baords. In addition, these venerable AVR-based machines are often the best for testing and feedback! ## Hardware Abstraction Layer (HAL) -Marlin includes an abstraction layer to provide a common API for all the platforms it targets. This allows Marlin code to address the details of motion and user interface tasks at the lowest and highest levels with no system overhead, tying all events directly to the hardware clock. +Marlin's Hardware Abstraction Layer provides a common API for all the platforms it targets. This allows Marlin code to address the details of motion and user interface tasks at the lowest and highest levels with no system overhead, tying all events directly to the hardware clock. -Every new HAL opens up a world of hardware. At this time we need HALs for RP2040 and the Duet3D family of boards. A HAL that wraps an RTOS is an interesting concept that could be explored. Did you know that Marlin includes a Simulator that can run on Windows, macOS, and Linux? Join the Discord to help move these sub-projects forward! +Every new HAL opens up a world of hardware. Marlin currently has HALs for more than a dozen platforms. While AVR and STM32 are the most well known and popular ones, others like ESP32 and LPC1768 support a variety of less common boards. At this time, an HAL for RP2040 is available in beta; we would like to add one for the Duet3D family of boards. A HAL that wraps an RTOS is an interesting concept that could be explored. + +Did you know that Marlin includes a Simulator that can run on Windows, macOS, and Linux? Join the Discord to help move these sub-projects forward! ### Supported Platforms diff --git a/buildroot/bin/ci_src_filter b/buildroot/bin/ci_src_filter index 1043e57d81..566e3e1e95 100755 --- a/buildroot/bin/ci_src_filter +++ b/buildroot/bin/ci_src_filter @@ -6,7 +6,9 @@ set -e FN="platformio.ini" if [[ $1 == "-n" ]]; then - awk '/default_src_filter/ { sub("default_src_filter", "org_src_filter"); print "default_src_filter = +"; } 1' $FN > $FN~ && mv $FN~ $FN + if ! grep -q "org_src_filter" "$FN"; then + awk '/default_src_filter/ { sub("default_src_filter", "org_src_filter"); print "default_src_filter = +"; } 1' $FN > $FN~ && mv $FN~ $FN + fi else git checkout $FN 2>/dev/null fi diff --git a/buildroot/bin/restore_configs b/buildroot/bin/restore_configs index 0bbd36fd1c..041ef045da 100755 --- a/buildroot/bin/restore_configs +++ b/buildroot/bin/restore_configs @@ -3,31 +3,34 @@ import os, sys, subprocess files_to_remove = [ - "Marlin/_Bootscreen.h", - "Marlin/_Statusscreen.h", - "marlin_config.json", - ".pio/build/mc.zip" + "Marlin/_Bootscreen.h", + "Marlin/_Statusscreen.h", + "marlin_config.json", + ".pio/build/mc.zip" ] for file in files_to_remove: - if os.path.exists(file): - os.remove(file) + if os.path.exists(file): + os.remove(file) def use_example_configs(): - try: - subprocess.run(['use_example_configs'], check=True) - except FileNotFoundError: - print("use_example_configs not found, skipping.") - pass + try: + subprocess.run(['use_example_configs'], check=True) + except FileNotFoundError: + try: + subprocess.run(['./buildroot/bin/use_example_configs'], check=True) + except FileNotFoundError: + print("use_example_configs not found, skipping.") + pass if len(sys.argv) > 1 and sys.argv[1] in ['-d', '--default']: - use_example_configs() + use_example_configs() else: - files_to_checkout = [ - "Marlin/Configuration.h", - "Marlin/Configuration_adv.h", - "Marlin/config.ini", - "Marlin/src/pins/*/pins_*.h" - ] - for file in files_to_checkout: - subprocess.run(["git", "checkout", file], stderr=subprocess.DEVNULL) + files_to_checkout = [ + "Marlin/Configuration.h", + "Marlin/Configuration_adv.h", + "Marlin/config.ini", + "Marlin/src/pins/*/pins_*.h" + ] + for file in files_to_checkout: + subprocess.run(["git", "checkout", file], stderr=subprocess.DEVNULL) diff --git a/buildroot/bin/use_example_configs b/buildroot/bin/use_example_configs index 08b32d67f6..401e15da61 100755 --- a/buildroot/bin/use_example_configs +++ b/buildroot/bin/use_example_configs @@ -21,115 +21,118 @@ DEBUGGING = False CONFIG_FILES = ("Configuration.h", "Configuration_adv.h", "_Bootscreen.h", "_Statusscreen.h") def debug_print(s): - if DEBUGGING: print(s) + if DEBUGGING: print(s) def get_current_branch(): - try: - result = subprocess.run(['git', 'branch'], capture_output=True, text=True, check=True) - for line in result.stdout.splitlines(): - if line.startswith('*'): - return line[2:] - except subprocess.CalledProcessError: - return None + try: + result = subprocess.run(['git', 'branch'], capture_output=True, text=True, check=True) + for line in result.stdout.splitlines(): + if line.startswith('*'): + return line[2:] + except subprocess.CalledProcessError: + return None def sparse_checkout(branch, config_path, repo_url="https://github.com/MarlinFirmware/Configurations.git"): - configs_dir = Path("ConfigurationsRepo") - config_subdir = f"config/{config_path}" + configs_dir = Path("ConfigurationsRepo") + config_subdir = f"config/{config_path}" - if not configs_dir.exists(): - # Step 1: Clone with no checkout - subprocess.run([ - "git", "clone", "--depth", "1", "--filter=blob:none", "--sparse", - "--branch", branch, repo_url, str(configs_dir) - ], check=True) + if not configs_dir.exists(): + # Step 1: Clone with no checkout + subprocess.run([ + "git", "clone", "--depth", "1", "--filter=blob:none", "--sparse", + "--branch", branch, repo_url, str(configs_dir) + ], check=True) - # Step 2: Enable sparse checkout and set the folder - subprocess.run(["git", "sparse-checkout", "set", config_subdir], cwd=str(configs_dir), check=True) - # Step 3: Pull the latest for that branch/folder - subprocess.run(["git", "pull"], cwd=str(configs_dir), check=True) + # Step 2: Enable sparse checkout and set the folder + subprocess.run(["git", "sparse-checkout", "set", config_subdir], cwd=str(configs_dir), check=True) + # Step 3: Pull the latest for that branch/folder + subprocess.run(["git", "pull"], cwd=str(configs_dir), check=True) def copy_config_files(branch, config_path, dest_dir): - sparse_checkout(branch, config_path) + sparse_checkout(branch, config_path) - src_dir = Path("ConfigurationsRepo") / "config" / config_path - for fname in CONFIG_FILES: - src_file = src_dir / fname - if src_file.exists(): - dest_file = dest_dir / fname - debug_print(f"Copying {src_file} to {dest_file}") - dest_file.write_bytes(src_file.read_bytes()) - else: - debug_print(f"{fname} not found in {src_dir}") + src_dir = Path("ConfigurationsRepo") / "config" / config_path + for fname in CONFIG_FILES: + src_file = src_dir / fname + if src_file.exists(): + dest_file = dest_dir / fname + debug_print(f"Copying {src_file} to {dest_file}") + dest_file.write_bytes(src_file.read_bytes()) + else: + debug_print(f"{fname} not found in {src_dir}") def fetch_config_files(branch, config_path, dest_dir): - config_path_url = config_path.replace(' ', '%20') - base_url = f"https://raw.githubusercontent.com/MarlinFirmware/Configurations/{branch}/config/{config_path_url}" + config_path_url = config_path.replace(' ', '%20') + base_url = f"https://raw.githubusercontent.com/MarlinFirmware/Configurations/{branch}/config/{config_path_url}" - for file in CONFIG_FILES: - url = f"{base_url}/{file}" - dest_file = dest_dir / file - if os.getenv('DEBUG', '0') == '1': - debug_print(f"Fetching {file} from {url} to {dest_file}") - - try: - urllib.request.urlretrieve(url, dest_file) - except urllib.error.HTTPError as e: - if e.code == 404: + for file in CONFIG_FILES: + url = f"{base_url}/{file}" + dest_file = dest_dir / file if os.getenv('DEBUG', '0') == '1': - print(f"File {file} not found (404), skipping.") - else: - raise + debug_print(f"Fetching {file} from {url} to {dest_file}") + + try: + urllib.request.urlretrieve(url, dest_file) + except urllib.error.HTTPError as e: + if e.code == 404: + if os.getenv('DEBUG', '0') == '1': + print(f"File {file} not found (404), skipping.") + else: + raise def fetch_configs(branch, config_path): - print(f"Fetching {config_path} configurations from {branch}...") + print(f"Fetching {config_path} configurations from {branch}...") - marlin_dir = Path("Marlin") - if not marlin_dir.exists(): - print(f"Directory 'Marlin' not found at the current location.") - sys.exit(1) + marlin_dir = Path("Marlin") + if not marlin_dir.exists(): + print(f"Directory 'Marlin' not found at the current location.") + sys.exit(1) - if os.environ.get('GITHUB_ACTIONS'): # Running on GitHub ? - copy_config_files(branch, config_path, marlin_dir) - else: - fetch_config_files(branch, config_path, marlin_dir) + if os.environ.get('GITHUB_ACTIONS'): # Running on GitHub ? + copy_config_files(branch, config_path, marlin_dir) + else: + fetch_config_files(branch, config_path, marlin_dir) def main(): - branch = get_current_branch() - if not branch: - print("Not a git repository or no branch found.") - sys.exit(1) + branch = get_current_branch() + if not branch: + print("Not a git repository or no branch found.") + sys.exit(1) - if branch.startswith("bugfix-2."): - branch = branch - elif branch.endswith("-2.1.x") or branch == "2.1.x": - branch = "latest-2.1.x" - elif branch.endswith("-2.0.x") or branch == "2.0.x": - branch = "latest-2.0.x" - elif branch.endswith("-1.1.x") or branch == "1.1.x": - branch = "latest-1.1.x" - elif branch.endswith("-1.0.x") or branch == "1.0.x": - branch = "latest-1.0.x" - else: - branch = "bugfix-2.1.x" - - if len(sys.argv) > 1: - arg = sys.argv[1] - if ':' in arg: - part1, part2 = arg.split(':', 1) - config_path = part2 - branch = part1 + if branch.startswith("bugfix-2."): + branch = branch + elif branch.endswith("-2.1.x") or branch == "2.1.x": + branch = "latest-2.1.x" + elif branch.endswith("-2.0.x") or branch == "2.0.x": + branch = "latest-2.0.x" + elif branch.endswith("-1.1.x") or branch == "1.1.x": + branch = "latest-1.1.x" + elif branch.endswith("-1.0.x") or branch == "1.0.x": + branch = "latest-1.0.x" else: - config_path = arg - config_path = 'examples/'+config_path - else: - config_path = "default" + branch = "bugfix-2.1.x" - try: - subprocess.run(['restore_configs'], check=True) - except FileNotFoundError: - print("restore_configs not found, skipping.") + if len(sys.argv) > 1: + arg = sys.argv[1] + if ':' in arg: + part1, part2 = arg.split(':', 1) + config_path = part2 + branch = part1 + else: + config_path = arg + config_path = 'examples/'+config_path + else: + config_path = "default" - fetch_configs(branch, config_path) + try: + subprocess.run(['restore_configs'], check=True) + except FileNotFoundError: + try: + subprocess.run(['./buildroot/bin/restore_configs'], check=True) + except FileNotFoundError: + print("restore_configs not found, skipping.") + + fetch_configs(branch, config_path) if __name__ == "__main__": - main() + main() diff --git a/buildroot/share/PlatformIO/ldscripts/mks_robin_mini.ld b/buildroot/share/PlatformIO/ldscripts/mks_robin_mini.ld old mode 100755 new mode 100644 diff --git a/buildroot/share/PlatformIO/ldscripts/mks_robin_nano.ld b/buildroot/share/PlatformIO/ldscripts/mks_robin_nano.ld old mode 100755 new mode 100644 diff --git a/buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_V2/hal_conf_extra.h b/buildroot/share/PlatformIO/variants/MARLIN_TH3D_EZBOARD_V2/hal_conf_extra.h old mode 100755 new mode 100644 diff --git a/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/ld/common.inc b/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/ld/common.inc old mode 100755 new mode 100644 diff --git a/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/ld/extra_libs.inc b/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/ld/extra_libs.inc old mode 100755 new mode 100644 diff --git a/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/ld/stm32f103z_dfu.ld b/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/ld/stm32f103z_dfu.ld old mode 100755 new mode 100644 diff --git a/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/ld/stm32f103zc.ld b/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/ld/stm32f103zc.ld old mode 100755 new mode 100644 diff --git a/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/ld/stm32f103zd.ld b/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/ld/stm32f103zd.ld old mode 100755 new mode 100644 diff --git a/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/ld/stm32f103ze.ld b/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/ld/stm32f103ze.ld old mode 100755 new mode 100644 diff --git a/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/ld/vector_symbols.inc b/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/ld/vector_symbols.inc old mode 100755 new mode 100644 diff --git a/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/wirish/start.S b/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/wirish/start.S old mode 100755 new mode 100644 diff --git a/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/wirish/start_c.c b/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/wirish/start_c.c old mode 100755 new mode 100644 diff --git a/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/wirish/syscalls.c b/buildroot/share/PlatformIO/variants/marlin_maple_CHITU_F103/wirish/syscalls.c old mode 100755 new mode 100644 diff --git a/buildroot/share/git/README.md b/buildroot/share/git/README.md old mode 100755 new mode 100644 diff --git a/buildroot/tests/BTT_SKR_SE_BX b/buildroot/tests/BTT_SKR_SE_BX index 8ba87da069..dd8e30d434 100755 --- a/buildroot/tests/BTT_SKR_SE_BX +++ b/buildroot/tests/BTT_SKR_SE_BX @@ -9,5 +9,5 @@ set -e # # Build with the default configurations # -use_example_configs BIQU/BX -exec_test $1 $2 "BIQU/BX" "$3" +use_example_configs BIQU/BX/base +exec_test $1 $2 "BIQU/BX/base" "$3" diff --git a/buildroot/web-ui/data/www/chart.min.js b/buildroot/web-ui/data/www/chart.min.js old mode 100755 new mode 100644 diff --git a/ini/due.ini b/ini/due.ini index 7e4017e257..12a0005ffc 100644 --- a/ini/due.ini +++ b/ini/due.ini @@ -16,10 +16,11 @@ # - RADDS # [env:DUE] -platform = atmelsam -board = due -build_src_filter = ${common.default_src_filter} + + -build_flags = -DWATCHDOG_PIO_RESET +platform = atmelsam +#platform_packages = toolchain-gccarmnoneeabi@1.120301.0 # Otherwise it's GCC 7.2.1 +board = due +build_src_filter = ${common.default_src_filter} + + +build_flags = -DWATCHDOG_PIO_RESET [env:DUE_USB] extends = env:DUE diff --git a/ini/features.ini b/ini/features.ini index 3799c2864c..c3fc6df537 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -20,8 +20,9 @@ MARLIN_TEST_BUILD = build_src_filter=+ POSTMORTEM_DEBUGGING = build_src_filter=+ + build_flags=-funwind-tables MKS_WIFI_MODULE = QRCode=https://github.com/makerbase-mks/QRCode/archive/261c5a696a.zip -HAS_TRINAMIC_CONFIG = TMCStepper=https://github.com/MarlinFirmware/TMCStepper/archive/v0.8.8.zip +HAS_TRINAMIC_CONFIG = TMCStepper=https://github.com/MarlinFirmware/TMCStepper/archive/v0.8.9.zip build_src_filter=+ + + + + +HAS_TMC_WITHOUT_SW_SERIAL = build_flags=-DTMCSTEPPER_SW_SERIAL=false HAS_STEPPER_CONTROL = build_src_filter=+ HAS_T(RINAMIC_CONFIG|MC_SPI) = build_src_filter=+ EDITABLE_HOMING_CURRENT = build_src_filter=+ diff --git a/ini/stm32-common.ini b/ini/stm32-common.ini index 12c07ef824..2ba6baed1b 100644 --- a/ini/stm32-common.ini +++ b/ini/stm32-common.ini @@ -10,14 +10,15 @@ #################################### [common_stm32] -platform = ststm32@~12.1 -board_build.core = stm32 -build_flags = ${common.build_flags} -std=gnu++14 +platform = ststm32@~12.1 +#platform_packages = toolchain-gccarmnoneeabi@1.100301.220327 # Otherwise it's GCC 9.2.1 +board_build.core = stm32 +build_flags = ${common.build_flags} -std=gnu++14 -DHAL_STM32 -DPLATFORM_M997_SUPPORT -DUSBCON -DUSBD_USE_CDC -DTIM_IRQ_PRIO=13 -DADC_RESOLUTION=12 -build_unflags = -std=gnu++11 -build_src_filter = ${common.default_src_filter} + - + -extra_scripts = ${common.extra_scripts} +build_unflags = -std=gnu++11 +build_src_filter = ${common.default_src_filter} + - + +extra_scripts = ${common.extra_scripts} pre:buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py custom_marlin.HAS_LTDC_TFT = build_src_filter=+ custom_marlin.HAS_FSMC_TFT = build_src_filter=+ diff --git a/ini/stm32f1-maple.ini b/ini/stm32f1-maple.ini index dd72b8980c..304102351d 100644 --- a/ini/stm32f1-maple.ini +++ b/ini/stm32f1-maple.ini @@ -33,7 +33,7 @@ lib_ignore = SPI, FreeRTOS701, FreeRTOS821 lib_deps = ${common.lib_deps} SoftwareSerialM platform_packages = tool-stm32duino - toolchain-gccarmnoneeabi@1.100301.220327 + toolchain-gccarmnoneeabi@1.120301.0 # Otherwise it's GCC 7.2.1 extra_scripts = ${common.extra_scripts} pre:buildroot/share/PlatformIO/scripts/fix_framework_weakness.py pre:buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py @@ -65,7 +65,8 @@ monitor_speed = 115200 [env:STM32F103RC_meeb_maple] extends = env:STM32F103RC_maple board = marlin_maple_MEEB_3DP -platform_packages = platformio/tool-dfuutil@~1.11.0 +platform_packages = ${env:STM32F103RC_maple.platform_packages} + platformio/tool-dfuutil@~1.11.0 build_flags = ${env:STM32F103RC_maple.build_flags} -DDEBUG_LEVEL=0 -DSS_TIMER=4 @@ -93,7 +94,6 @@ extends = env:STM32F103RC_maple extra_scripts = ${env:STM32F103RC_maple.extra_scripts} buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py build_flags = ${env:STM32F103RC_maple.build_flags} -DDEBUG_LEVEL=0 -platform_packages = toolchain-gccarmnoneeabi@1.90301.200702 lib_ldf_mode = chain debug_tool = stlink upload_protocol = serial @@ -109,7 +109,6 @@ extends = env:STM32F103RC_maple board_build.address = 0x08007000 board_build.ldscript = STM32F103RC_SKR_MINI_256K.ld build_flags = ${env:STM32F103RC_maple.build_flags} -DDEBUG_LEVEL=0 -DSS_TIMER=4 -platform_packages = toolchain-gccarmnoneeabi@1.90301.200702 monitor_speed = 115200 [env:STM32F103RC_btt_USB_maple] @@ -136,7 +135,6 @@ upload_protocol = jlink [env:STM32F103RC_creality_maple] extends = env:STM32F103RC_maple build_flags = ${env:STM32F103RC_maple.build_flags} -DTEMP_TIMER_CHAN=4 -platform_packages = toolchain-gccarmnoneeabi@1.90301.200702 board_build.address = 0x08007000 board_build.ldscript = creality256k.ld board_build.rename = firmware-{date}-{time}.bin @@ -160,7 +158,6 @@ board_build.ldscript = crealityPro.ld [env:GD32F103RC_voxelab_maple] extends = env:STM32F103RC_maple build_flags = ${env:STM32F103RC_maple.build_flags} -DTEMP_TIMER_CHAN=4 -platform_packages = toolchain-gccarmnoneeabi@1.90301.200702 board_build.address = 0x08007000 board_build.ldscript = creality256k.ld debug_tool = jlink @@ -170,7 +167,6 @@ upload_protocol = jlink extends = env:STM32F103RE_maple build_flags = ${env:STM32F103RE_maple.build_flags} -DTEMP_TIMER_CHAN=4 -DVOXELAB_N32 -DSDCARD_FLASH_LIMIT_256K -platform_packages = toolchain-gccarmnoneeabi@1.90301.200702 board_build.address = 0x08007000 board_build.ldscript = creality.ld debug_tool = jlink @@ -393,13 +389,11 @@ lib_ignore = Adafruit NeoPixel, SPI, SailfishLCD, SailfishRGB_LED [env:STM32F103RC_ZM3E2_USB_maple] extends = ZONESTAR_ZM3E_maple -platform_packages = toolchain-gccarmnoneeabi@1.90301.200702 board = genericSTM32F103RC board_build.ldscript = ZONESTAR_ZM3E_256K.ld [env:STM32F103VC_ZM3E4_USB_maple] extends = ZONESTAR_ZM3E_maple -platform_packages = toolchain-gccarmnoneeabi@1.90301.200702 board = genericSTM32F103VC board_build.ldscript = ZONESTAR_ZM3E_256K.ld build_flags = ${ZONESTAR_ZM3E_maple.build_flags} -DTONE_TIMER=1 -DTONE_CHANNEL=2 diff --git a/ini/teensy.ini b/ini/teensy.ini index dac4b40c30..3e988b8d7c 100644 --- a/ini/teensy.ini +++ b/ini/teensy.ini @@ -71,10 +71,20 @@ board = teensy36 build_src_filter = ${teensy_arm.build_src_filter} + # -# Teensy 4.0 / 4.1 (ARM Cortex-M7) +# Teensy 4.0 (ARM Cortex-M7) +# +[env:teensy40] +extends = teensy_arm +board = teensy40 +build_src_filter = ${teensy_arm.build_src_filter} + +build_flags = -DIS_TEENSY40 + +# +# Teensy 4.1 (ARM Cortex-M7) # [env:teensy41] extends = teensy_arm board = teensy41 build_src_filter = ${teensy_arm.build_src_filter} + +build_flags = -DIS_TEENSY41 lib_ignore =