From 9bbbcd439b5acab59338352d7c65d6e54352afcc Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 4 May 2025 13:55:50 -0500 Subject: [PATCH 001/102] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Cla?= =?UTF-8?q?rify=20parking=5Fextruder=5Funpark=5Fafter=5Fhoming?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/calibrate/G28.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index 6c8af9ddb0..e9d72a83f6 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -300,7 +300,8 @@ void GcodeSuite::G28() { #endif // PARKING_EXTRUDER homing requires different handling of movement / solenoid activation, depending on the side of homing #if ENABLED(PARKING_EXTRUDER) - const bool pe_final_change_must_unpark = parking_extruder_unpark_after_homing(old_tool_index, X_HOME_DIR + 1 == old_tool_index * 2); + const bool homed_towards_tool = old_tool_index == TERN(X_HOME_TO_MIN, 0, 1), + pe_final_change_must_unpark = parking_extruder_unpark_after_homing(old_tool_index, homed_towards_tool); #endif tool_change(0, true); #endif From 44ef6e2b70c8a68913f10aab550422b9ad351e37 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 4 May 2025 15:19:22 -0500 Subject: [PATCH 002/102] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20Y=5FSTOP=5FPIN=20a?= =?UTF-8?q?lias=20for=20Y=5FMAX=5FPIN?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/pins_postprocess.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/pins/pins_postprocess.h b/Marlin/src/pins/pins_postprocess.h index 4d2455bd31..a18c099196 100644 --- a/Marlin/src/pins/pins_postprocess.h +++ b/Marlin/src/pins/pins_postprocess.h @@ -638,7 +638,7 @@ #endif #elif Y_HOME_TO_MIN #define Y_STOP_PIN Y_MIN_PIN - #elif X_HOME_TO_MAX + #elif Y_HOME_TO_MAX #define Y_STOP_PIN Y_MAX_PIN #endif #if !defined(Y2_STOP_PIN) && ENABLED(Y_DUAL_ENDSTOPS) && PIN_EXISTS(Y_STOP) From 555b080d85501e92e401f185b0494489dc20ff29 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 5 May 2025 00:33:33 +0000 Subject: [PATCH 003/102] [cron] Bump distribution date (2025-05-05) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index a58dfbe2a8..4abad36238 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-05-04" +//#define STRING_DISTRIBUTION_DATE "2025-05-05" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index b066410475..bb924b75bb 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-05-04" + #define STRING_DISTRIBUTION_DATE "2025-05-05" #endif /** From 735cd9a092e4b843ccd68efc1f4573e25ceecb3a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 5 May 2025 12:28:11 -0500 Subject: [PATCH 004/102] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20TH3D=20EZ=20V2=20s?= =?UTF-8?q?ensorless=20homing?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h b/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h index ebb651e0d5..4d2e2f556d 100644 --- a/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h +++ b/Marlin/src/pins/stm32f4/pins_TH3D_EZBOARD_V2.h @@ -63,13 +63,13 @@ // #if ANY(SENSORLESS_HOMING, SENSORLESS_PROBING) // Sensorless homing pins - #if ENABLED(X_AXIS_SENSORLESS_HOMING) + #if AXIS_HAS_STALLGUARD(X) && defined(X_STALL_SENSITIVITY) #define X_STOP_PIN PB4 #else #define X_STOP_PIN PC1 #endif - #if ENABLED(Y_AXIS_SENSORLESS_HOMING) + #if AXIS_HAS_STALLGUARD(Y) && defined(Y_STALL_SENSITIVITY) #define Y_STOP_PIN PB9 #else #define Y_STOP_PIN PC2 From c9e7d6f55c411a7aecf289e3d343b1c10375d03d Mon Sep 17 00:00:00 2001 From: B Date: Mon, 5 May 2025 11:08:45 -0700 Subject: [PATCH 005/102] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Upd?= =?UTF-8?q?ate=20GD32=20MFL=20Platform,=20Arduino=20Core=20(#27830)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/GD32_MFL/HAL.h | 2 +- Marlin/src/HAL/GD32_MFL/MarlinSerial.cpp | 6 +- Marlin/src/HAL/GD32_MFL/MarlinSerial.h | 4 +- Marlin/src/HAL/GD32_MFL/fastio.h | 17 +- Marlin/src/HAL/GD32_MFL/pinsDebug.h | 10 +- Marlin/src/HAL/GD32_MFL/sd/SDCard.cpp | 246 +++++++++++------------ Marlin/src/HAL/GD32_MFL/sd/SDCard.h | 198 +++++++++--------- Marlin/src/HAL/GD32_MFL/sd/sdio.cpp | 2 +- Marlin/src/HAL/GD32_MFL/sd/sdio.h | 2 +- Marlin/src/HAL/GD32_MFL/timers.h | 4 +- ini/gd32.ini | 4 +- 11 files changed, 253 insertions(+), 242 deletions(-) diff --git a/Marlin/src/HAL/GD32_MFL/HAL.h b/Marlin/src/HAL/GD32_MFL/HAL.h index fd3a10d72b..56e52b53b5 100644 --- a/Marlin/src/HAL/GD32_MFL/HAL.h +++ b/Marlin/src/HAL/GD32_MFL/HAL.h @@ -105,7 +105,7 @@ extern "C" char* dtostrf(double val, signed char width, unsigned char prec, char class MarlinHAL { public: // Before setup() - MarlinHAL() {} + MarlinHAL() = default; // Watchdog static void watchdog_init() IF_DISABLED(USE_WATCHDOG, {}); diff --git a/Marlin/src/HAL/GD32_MFL/MarlinSerial.cpp b/Marlin/src/HAL/GD32_MFL/MarlinSerial.cpp index 271247295c..95ea8bea25 100644 --- a/Marlin/src/HAL/GD32_MFL/MarlinSerial.cpp +++ b/Marlin/src/HAL/GD32_MFL/MarlinSerial.cpp @@ -33,8 +33,8 @@ using namespace arduino; -MarlinSerial& MarlinSerial::get_instance(usart::USART_Base Base, pin_size_t rxPin, pin_size_t txPin) { - UsartSerial& serial = UsartSerial::get_instance(Base, rxPin, txPin); +auto MarlinSerial::get_instance(usart::USART_Base Base, pin_size_t rxPin, pin_size_t txPin) -> MarlinSerial& { + auto& serial = UsartSerial::get_instance(Base, rxPin, txPin); return *reinterpret_cast(&serial); } @@ -61,7 +61,7 @@ MarlinSerial& MarlinSerial::get_instance(usart::USART_Base Base, pin_size_t rxPi static void emergency_callback() { if (!current_serial_instance) return; - const uint8_t last_data = current_serial_instance->get_last_data(); + const auto last_data = current_serial_instance->get_last_data(); emergency_parser.update(current_serial_instance->emergency_state, last_data); } diff --git a/Marlin/src/HAL/GD32_MFL/MarlinSerial.h b/Marlin/src/HAL/GD32_MFL/MarlinSerial.h index f47c6da032..6b33ce0e61 100644 --- a/Marlin/src/HAL/GD32_MFL/MarlinSerial.h +++ b/Marlin/src/HAL/GD32_MFL/MarlinSerial.h @@ -43,7 +43,7 @@ using namespace arduino; struct MarlinSerial : public UsartSerial { - static MarlinSerial& get_instance(usart::USART_Base Base, pin_size_t rxPin = NO_PIN, pin_size_t txPin = NO_PIN); + static auto get_instance(usart::USART_Base Base, pin_size_t rxPin = NO_PIN, pin_size_t txPin = NO_PIN) -> MarlinSerial&; void begin(unsigned long baudrate, uint16_t config); inline void begin(unsigned long baudrate) { begin(baudrate, SERIAL_8N1); } @@ -57,7 +57,7 @@ struct MarlinSerial : public UsartSerial { EmergencyParser::State emergency_state; // Accessor method to get the last received byte - uint8_t get_last_data() { return usart_.get_last_data(); } + auto get_last_data() -> uint8_t { return usart_.get_last_data(); } // Register the emergency callback void register_emergency_callback(void (*callback)()); diff --git a/Marlin/src/HAL/GD32_MFL/fastio.h b/Marlin/src/HAL/GD32_MFL/fastio.h index 35bd2b1ef7..35829e856f 100644 --- a/Marlin/src/HAL/GD32_MFL/fastio.h +++ b/Marlin/src/HAL/GD32_MFL/fastio.h @@ -21,26 +21,27 @@ */ #pragma once -// Fast I/O interfaces for GD32F303RE +// Fast I/O interfaces for GD32 #include +#include #include #include template static inline void fast_write_pin_wrapper(pin_size_t IO, T V) { - auto port = getPortFromPin(IO); - auto pin = getPinInPort(IO); - if (static_cast(V)) gpio::fast_set_pin(port, pin); - else gpio::fast_clear_pin(port, pin); + const PortPinPair& pp = port_pin_map[IO]; + gpio::fast_write_pin(pp.port, pp.pin, static_cast(V)); } -static inline bool fast_read_pin_wrapper(pin_size_t IO) { - return gpio::fast_read_pin(getPortFromPin(IO), getPinInPort(IO)); +static inline auto fast_read_pin_wrapper(pin_size_t IO) -> bool { + const PortPinPair& pp = port_pin_map[IO]; + return gpio::fast_read_pin(pp.port, pp.pin); } static inline void fast_toggle_pin_wrapper(pin_size_t IO) { - gpio::fast_toggle_pin(getPortFromPin(IO), getPinInPort(IO)); + const PortPinPair& pp = port_pin_map[IO]; + gpio::fast_toggle_pin(pp.port, pp.pin); } // ------------------------ diff --git a/Marlin/src/HAL/GD32_MFL/pinsDebug.h b/Marlin/src/HAL/GD32_MFL/pinsDebug.h index d3b3794df2..be7e4ce1ba 100644 --- a/Marlin/src/HAL/GD32_MFL/pinsDebug.h +++ b/Marlin/src/HAL/GD32_MFL/pinsDebug.h @@ -70,8 +70,9 @@ bool isAnalogPin(const pin_t pin) { if (!isValidPin(pin)) return false; if (getAdcChannel(pin) != adc::ADC_Channel::INVALID) { - auto& instance = gpio::GPIO::get_instance(getPortFromPin(pin)).value(); - return instance.get_pin_mode(getPinInPort(pin)) == gpio::Pin_Mode::ANALOG && !M43_NEVER_TOUCH(pin); + const PortPinPair& pp = port_pin_map[pin]; + auto& instance = gpio::GPIO::get_instance(pp.port).value(); + return instance.get_pin_mode(pp.pin) == gpio::Pin_Mode::ANALOG && !M43_NEVER_TOUCH(pin); } return false; @@ -80,8 +81,9 @@ bool isAnalogPin(const pin_t pin) { bool getValidPinMode(const pin_t pin) { if (!isValidPin(pin)) return false; - auto& instance = gpio::GPIO::get_instance(getPortFromPin(pin)).value(); - gpio::Pin_Mode mode = instance.get_pin_mode(getPinInPort(pin)); + const PortPinPair& pp = port_pin_map[pin]; + auto& instance = gpio::GPIO::get_instance(pp.port).value(); + gpio::Pin_Mode mode = instance.get_pin_mode(pp.pin); return mode != gpio::Pin_Mode::ANALOG && mode != gpio::Pin_Mode::INPUT_FLOATING && mode != gpio::Pin_Mode::INPUT_PULLUP && mode != gpio::Pin_Mode::INPUT_PULLDOWN; diff --git a/Marlin/src/HAL/GD32_MFL/sd/SDCard.cpp b/Marlin/src/HAL/GD32_MFL/sd/SDCard.cpp index c46e0fc6fb..2e7ba4dfd9 100644 --- a/Marlin/src/HAL/GD32_MFL/sd/SDCard.cpp +++ b/Marlin/src/HAL/GD32_MFL/sd/SDCard.cpp @@ -28,7 +28,7 @@ namespace sdio { -CardDMA& CardDMA::get_instance() { +auto CardDMA::get_instance() -> CardDMA& { static CardDMA instance; return instance; } @@ -38,9 +38,7 @@ CardDMA::CardDMA() : sdcard_cid_{0U, 0U, 0U, 0U}, sdcard_scr_{0U, 0U}, desired_clock_(Default_Desired_Clock), - stop_condition_(0U), total_bytes_(0U), - count_(0U), sdio_(SDIO::get_instance()), config_(sdio_.get_config()), dmaBase_(dma::DMA_Base::DMA1_BASE), @@ -50,15 +48,15 @@ CardDMA::CardDMA() : transfer_error_(SDIO_Error_Type::OK), interface_version_(Interface_Version::UNKNOWN), card_type_(Card_Type::UNKNOWN), + current_state_(Operational_State::READY), transfer_end_(false), - is_rx_(false), multiblock_(false), - current_state_(Operational_State::READY) + is_rx_(false) { } // Initialize card and put in standby state -SDIO_Error_Type CardDMA::init() { +auto CardDMA::init() -> SDIO_Error_Type { // Reset SDIO peripheral sdio_.reset(); sync_domains(); @@ -79,7 +77,7 @@ SDIO_Error_Type CardDMA::init() { } // Startup command procedure according to SDIO specification -SDIO_Error_Type CardDMA::begin_startup_procedure() { +auto CardDMA::begin_startup_procedure() -> SDIO_Error_Type { sdio_.set_power_mode(Power_Control::POWER_ON); sdio_.set_clock_enable(true); sync_domains(); @@ -124,12 +122,12 @@ SDIO_Error_Type CardDMA::begin_startup_procedure() { } // Voltage validation -SDIO_Error_Type CardDMA::validate_voltage() { +auto CardDMA::validate_voltage() -> SDIO_Error_Type { uint32_t response = 0U; uint32_t count = 0U; bool valid_voltage = false; - while ((count < Max_Voltage_Checks) && (valid_voltage == false)) { + while (count < Max_Voltage_Checks && valid_voltage == false) { if (send_command_and_check(Command_Index::CMD55, 0, Command_Response::RSP_SHORT, Wait_Type::WT_NONE, [this, cmd = Command_Index::CMD55]() { return get_r1_result(cmd); @@ -144,7 +142,7 @@ SDIO_Error_Type CardDMA::validate_voltage() { return SDIO_Error_Type::ACMD41_FAILED; } response = sdio_.get_response(Response_Type::RESPONSE0); - valid_voltage = (((response >> 31U) == 1U) ? true : false); + valid_voltage = ((response >> 31U) == 1U); count++; } @@ -171,7 +169,7 @@ void CardDMA::begin_shutdown_procedure() { } // Initialize card -SDIO_Error_Type CardDMA::card_init() { +auto CardDMA::card_init() -> SDIO_Error_Type { if (sdio_.get_power_mode() == static_cast(Power_Control::POWER_OFF)) { return SDIO_Error_Type::INVALID_OPERATION; } @@ -221,7 +219,7 @@ SDIO_Error_Type CardDMA::card_init() { return SDIO_Error_Type::OK; } -SDIO_Error_Type CardDMA::store_cid() { +auto CardDMA::store_cid() -> SDIO_Error_Type { // Store the CID register values sdcard_cid_[0] = sdio_.get_response(Response_Type::RESPONSE0); sdcard_cid_[1] = sdio_.get_response(Response_Type::RESPONSE1); @@ -231,7 +229,7 @@ SDIO_Error_Type CardDMA::store_cid() { return SDIO_Error_Type::OK; } -SDIO_Error_Type CardDMA::store_csd() { +auto CardDMA::store_csd() -> SDIO_Error_Type { // Store the CSD register values sdcard_csd_[0] = sdio_.get_response(Response_Type::RESPONSE0); sdcard_csd_[1] = sdio_.get_response(Response_Type::RESPONSE1); @@ -241,7 +239,7 @@ SDIO_Error_Type CardDMA::store_csd() { return SDIO_Error_Type::OK; } -SDIO_Error_Type CardDMA::set_hardware_bus_width(Bus_Width width) { +auto CardDMA::set_hardware_bus_width(Bus_Width width) -> SDIO_Error_Type { if (card_type_ == Card_Type::SD_MMC || width == Bus_Width::WIDTH_8BIT) { return SDIO_Error_Type::UNSUPPORTED_FUNCTION; } @@ -283,7 +281,7 @@ SDIO_Error_Type CardDMA::set_hardware_bus_width(Bus_Width width) { return SDIO_Error_Type::UNSUPPORTED_FUNCTION; } -SDIO_Error_Type CardDMA::read(uint8_t* buf, uint32_t address, uint32_t count) { +auto CardDMA::read(uint8_t* buf, uint32_t address, uint32_t count) -> SDIO_Error_Type { if (current_state_ == Operational_State::READY) { transfer_error_ = SDIO_Error_Type::OK; current_state_ = Operational_State::BUSY; @@ -340,7 +338,7 @@ SDIO_Error_Type CardDMA::read(uint8_t* buf, uint32_t address, uint32_t count) { } } -SDIO_Error_Type CardDMA::write(uint8_t* buf, uint32_t address, uint32_t count) { +auto CardDMA::write(uint8_t* buf, uint32_t address, uint32_t count) -> SDIO_Error_Type { // Enable the interrupts sdio_.set_interrupt_enable(Interrupt_Type::DTCRCERRIE, true); sdio_.set_interrupt_enable(Interrupt_Type::DTTMOUTIE, true); @@ -363,7 +361,7 @@ SDIO_Error_Type CardDMA::write(uint8_t* buf, uint32_t address, uint32_t count) { // CMD25/CMD24 (WRITE_MULTIPLE_BLOCK/WRITE_BLOCK) send write command Command_Index write_cmd = (count > 1U) ? Command_Index::CMD25 : Command_Index::CMD24; if (send_command_and_check(write_cmd, address, Command_Response::RSP_SHORT, - Wait_Type::WT_NONE, [this, cmd = write_cmd]() { + Wait_Type::WT_NONE, [this, cmd = write_cmd]() { return get_r1_result(cmd); }) != SDIO_Error_Type::OK) { sdio_.clear_multiple_interrupt_flags(clear_common_flags); @@ -379,16 +377,16 @@ SDIO_Error_Type CardDMA::write(uint8_t* buf, uint32_t address, uint32_t count) { Block_Size block_size = get_data_block_size_index(total_bytes_); sdio_.set_data_state_machine_and_send(Data_Timeout, total_bytes_, block_size, - Transfer_Mode::BLOCK, Transfer_Direction::SDIO_TO_CARD, true); + Transfer_Mode::BLOCK, Transfer_Direction::SDIO_TO_CARD, true); - while ((dma_.get_flag(dma::Status_Flags::FLAG_FTFIF)) || (dma_.get_flag(dma::Status_Flags::FLAG_ERRIF))) { + while (dma_.get_flag(dma::Status_Flags::FLAG_FTFIF) || dma_.get_flag(dma::Status_Flags::FLAG_ERRIF)) { // Wait for the IRQ handler to clear } return SDIO_Error_Type::OK; } -SDIO_Error_Type CardDMA::erase(uint32_t address_start, uint32_t address_end) { +auto CardDMA::erase(uint32_t address_start, uint32_t address_end) -> SDIO_Error_Type { SDIO_Error_Type result = SDIO_Error_Type::OK; // Card command classes CSD @@ -459,9 +457,11 @@ void CardDMA::handle_interrupts() { disable_all_interrupts(); sdio_.set_data_state_machine_enable(false); - if ((multiblock_) && (!is_rx_)) { + if (multiblock_ && !is_rx_) { transfer_error_ = stop_transfer(); - if (transfer_error_ != SDIO_Error_Type::OK) {} + if (transfer_error_ != SDIO_Error_Type::OK) { + return; + } } if (!is_rx_) { @@ -497,7 +497,7 @@ void CardDMA::handle_interrupts() { } } -SDIO_Error_Type CardDMA::select_deselect() { +auto CardDMA::select_deselect() -> SDIO_Error_Type { // CMD7 (SELECT/DESELECT_CARD) if (send_command_and_check(Command_Index::CMD7, static_cast(sdcard_rca_ << RCA_Shift), Command_Response::RSP_SHORT, Wait_Type::WT_NONE, [this, cmd = Command_Index::CMD7]() { @@ -508,7 +508,7 @@ SDIO_Error_Type CardDMA::select_deselect() { return SDIO_Error_Type::OK; } -SDIO_Error_Type CardDMA::get_card_interface_status(uint32_t* status) { +auto CardDMA::get_card_interface_status(uint32_t* status) -> SDIO_Error_Type { if (status == nullptr) return SDIO_Error_Type::INVALID_PARAMETER; // CMD13 (SEND_STATUS) @@ -524,7 +524,7 @@ SDIO_Error_Type CardDMA::get_card_interface_status(uint32_t* status) { return SDIO_Error_Type::OK; } -SDIO_Error_Type CardDMA::get_sdcard_status(uint32_t* status) { +auto CardDMA::get_sdcard_status(uint32_t* status) -> SDIO_Error_Type { uint32_t count = 0U; // CMD16 (SET_BLOCKLEN) @@ -599,7 +599,7 @@ void CardDMA::check_dma_complete() { } } -SDIO_Error_Type CardDMA::stop_transfer() { +auto CardDMA::stop_transfer() -> SDIO_Error_Type { // CMD12 (STOP_TRANSMISSION) if (send_command_and_check(Command_Index::CMD12, 0, Command_Response::RSP_SHORT, Wait_Type::WT_NONE, [this, cmd = Command_Index::CMD12]() { return get_r1_result(cmd); @@ -609,7 +609,7 @@ SDIO_Error_Type CardDMA::stop_transfer() { return SDIO_Error_Type::OK; } -Transfer_State CardDMA::get_transfer_state() { +auto CardDMA::get_transfer_state() -> Transfer_State { Transfer_State transfer_state = Transfer_State::IDLE; if (sdio_.get_flag(Status_Flags::FLAG_TXRUN) | sdio_.get_flag(Status_Flags::FLAG_RXRUN)) { transfer_state = Transfer_State::BUSY; @@ -618,7 +618,7 @@ Transfer_State CardDMA::get_transfer_state() { return transfer_state; } -uint32_t CardDMA::get_card_capacity() const { +[[nodiscard]] auto CardDMA::get_card_capacity() const -> uint32_t { auto extract_bits = [](uint32_t value, uint8_t start_bit, uint8_t length) -> uint32_t { return (value >> start_bit) & ((1U << length) - 1U); }; @@ -665,7 +665,7 @@ uint32_t CardDMA::get_card_capacity() const { return capacity; } -SDIO_Error_Type CardDMA::get_card_specific_data(Card_Info* info) { +auto CardDMA::get_card_specific_data(Card_Info* info) -> SDIO_Error_Type { if (info == nullptr) return SDIO_Error_Type::INVALID_PARAMETER; // Store basic card information @@ -735,28 +735,20 @@ SDIO_Error_Type CardDMA::get_card_specific_data(Card_Info* info) { return SDIO_Error_Type::OK; } -constexpr Block_Size CardDMA::get_data_block_size_index(uint16_t size) { - switch (size) { - case 1: return Block_Size::BYTES_1; - case 2: return Block_Size::BYTES_2; - case 4: return Block_Size::BYTES_4; - case 8: return Block_Size::BYTES_8; - case 16: return Block_Size::BYTES_16; - case 32: return Block_Size::BYTES_32; - case 64: return Block_Size::BYTES_64; - case 128: return Block_Size::BYTES_128; - case 256: return Block_Size::BYTES_256; - case 512: return Block_Size::BYTES_512; - case 1024: return Block_Size::BYTES_1024; - case 2048: return Block_Size::BYTES_2048; - case 4096: return Block_Size::BYTES_4096; - case 8192: return Block_Size::BYTES_8192; - case 16384: return Block_Size::BYTES_16384; - default: return Block_Size::BYTES_1; - } +constexpr auto CardDMA::get_data_block_size_index(uint16_t size) -> Block_Size { + if (size < 1 || size > 16384) return Block_Size::BYTES_1; + + // Check if size is a power of two + if ((size & (size - 1)) != 0) return Block_Size::BYTES_1; + + // Count trailing zeros to find the index + uint16_t index = 0; + while ((size >>= 1) != 0) ++index; + + return static_cast(index); } -SDIO_Error_Type CardDMA::get_card_state(Card_State* card_state) { +auto CardDMA::get_card_state(Card_State* card_state) -> SDIO_Error_Type { // CMD13 (SEND_STATUS) if (send_command_and_check(Command_Index::CMD13, static_cast(sdcard_rca_ << RCA_Shift), Command_Response::RSP_SHORT, Wait_Type::WT_NONE, [this, cmd = Command_Index::CMD13]() { @@ -773,7 +765,7 @@ SDIO_Error_Type CardDMA::get_card_state(Card_State* card_state) { if (response & All_R1_Error_Bits) { for (const auto& entry : errorTableR1) { - if (response & entry.mask) { + if (TEST(response, entry.bit_position)) { return entry.errorType; } } @@ -783,23 +775,28 @@ SDIO_Error_Type CardDMA::get_card_state(Card_State* card_state) { return SDIO_Error_Type::OK; } -SDIO_Error_Type CardDMA::get_command_sent_result() { - volatile uint32_t timeout = 0x00FFFFFFU; +auto CardDMA::get_command_sent_result() -> SDIO_Error_Type { + constexpr uint32_t MAX_TIMEOUT = 0x00FFFFFFU; + uint32_t timeout = MAX_TIMEOUT; - while ((sdio_.get_flag(Status_Flags::FLAG_CMDSEND) == false) && (timeout != 0U)) { - timeout = timeout - 1U; + // Wait for command sent flag or timeout + while (!sdio_.get_flag(Status_Flags::FLAG_CMDSEND) && timeout) { + --timeout; } - if (timeout == 0U) return SDIO_Error_Type::RESPONSE_TIMEOUT; - sdio_.clear_multiple_interrupt_flags(clear_command_flags); + // Check if timeout occurred + if (timeout == 0U) { + return SDIO_Error_Type::RESPONSE_TIMEOUT; + } + + // Clear command flags and return success + sdio_.clear_multiple_interrupt_flags(clear_command_flags); return SDIO_Error_Type::OK; } -SDIO_Error_Type CardDMA::check_sdio_status(Command_Index index, bool check_index, bool ignore_crc) { +auto CardDMA::check_sdio_status(Command_Index index, bool check_index, bool ignore_crc) -> SDIO_Error_Type { // Wait until one of the relevant flags is set - bool flag_set = sdio_.wait_cmd_flags(); - - if (!flag_set) { + if (!sdio_.wait_cmd_flags()) { return SDIO_Error_Type::RESPONSE_TIMEOUT; } @@ -810,56 +807,55 @@ SDIO_Error_Type CardDMA::check_sdio_status(Command_Index index, bool check_index // If cmd was received, check the index // Responses that dont do an index check will send an invalid cmd index if (check_index && (index != Command_Index::INVALID)) { - uint8_t idx = sdio_.get_command_index(); - if (idx != static_cast(index)) { + uint8_t received_idx = sdio_.get_command_index(); + if (received_idx != static_cast(index)) { + sdio_.clear_multiple_interrupt_flags(clear_command_flags); return SDIO_Error_Type::ILLEGAL_COMMAND; } } - // Clear all flags before returning + + // Command received successfully sdio_.clear_multiple_interrupt_flags(clear_command_flags); return SDIO_Error_Type::OK; } - // Timeout check + // Check for timeout if (sdio_.get_flag(Status_Flags::FLAG_CMDTMOUT)) { sdio_.clear_flag(Clear_Flags::FLAG_CMDTMOUTC); return SDIO_Error_Type::RESPONSE_TIMEOUT; } - // CRC check - if (!ignore_crc) { - if (sdio_.get_flag(Status_Flags::FLAG_CCRCERR)) { - sdio_.clear_flag(Clear_Flags::FLAG_CCRCERRC); - return SDIO_Error_Type::COMMAND_CRC_ERROR; - } + // Check for CRC error if not ignored + if (!ignore_crc && sdio_.get_flag(Status_Flags::FLAG_CCRCERR)) { + sdio_.clear_flag(Clear_Flags::FLAG_CCRCERRC); + return SDIO_Error_Type::COMMAND_CRC_ERROR; } - // Responses that dont do an index check will send an invalid cmd index + // Final index check (redundant with the first check, but keeping for safety) + // This code path should rarely be taken due to the earlier checks if (check_index && (index != Command_Index::INVALID)) { - uint8_t idx = sdio_.get_command_index(); - if (idx != static_cast(index)) { + uint8_t received_idx = sdio_.get_command_index(); + if (received_idx != static_cast(index)) { + sdio_.clear_multiple_interrupt_flags(clear_command_flags); return SDIO_Error_Type::ILLEGAL_COMMAND; } } - // Clear all flags before returning + // Clear all flags and return success sdio_.clear_multiple_interrupt_flags(clear_command_flags); - return SDIO_Error_Type::OK; } -SDIO_Error_Type CardDMA::get_r1_result(Command_Index index) { +auto CardDMA::get_r1_result(Command_Index index) -> SDIO_Error_Type { SDIO_Error_Type result = check_sdio_status(index, true, false); - if (result != SDIO_Error_Type::OK) { - return result; - } + if (result != SDIO_Error_Type::OK) return result; // Get the R1 response and check for errors uint32_t response = sdio_.get_response(Response_Type::RESPONSE0); if (response & All_R1_Error_Bits) { for (const auto& entry : errorTableR1) { - if (response & entry.mask) { + if (TEST(response, entry.bit_position)) { return entry.errorType; } } @@ -869,7 +865,7 @@ SDIO_Error_Type CardDMA::get_r1_result(Command_Index index) { return SDIO_Error_Type::OK; } -SDIO_Error_Type CardDMA::get_r6_result(Command_Index index, uint16_t* rca) { +auto CardDMA::get_r6_result(Command_Index index, uint16_t* rca) -> SDIO_Error_Type { SDIO_Error_Type result = check_sdio_status(index, true, false); if (result != SDIO_Error_Type::OK) return result; @@ -877,7 +873,7 @@ SDIO_Error_Type CardDMA::get_r6_result(Command_Index index, uint16_t* rca) { if (response & R6_Error_Bits) { for (const auto& entry : errorTableR6) { - if (response & entry.mask) { + if (TEST(response, entry.bit_position)) { return entry.errorType; } } @@ -888,18 +884,13 @@ SDIO_Error_Type CardDMA::get_r6_result(Command_Index index, uint16_t* rca) { return SDIO_Error_Type::OK; } -SDIO_Error_Type CardDMA::get_r7_result() { - return check_sdio_status(Command_Index::INVALID, false, false); -} - -SDIO_Error_Type CardDMA::get_scr(uint16_t rca, uint32_t* scr) { +auto CardDMA::get_scr(uint16_t rca, uint32_t* scr) -> SDIO_Error_Type { uint32_t temp_scr[2] = {0U, 0U}; uint32_t index_scr = 0U; - uint32_t* src_data = scr; // CMD16 (SET_BLOCKLEN) if (send_command_and_check(Command_Index::CMD16, 8U, Command_Response::RSP_SHORT, - Wait_Type::WT_NONE, [this, cmd = Command_Index::CMD16]() { + Wait_Type::WT_NONE, [this, cmd = Command_Index::CMD16]() { return get_r1_result(cmd); }) != SDIO_Error_Type::OK) { return SDIO_Error_Type::CMD16_FAILED; @@ -907,7 +898,7 @@ SDIO_Error_Type CardDMA::get_scr(uint16_t rca, uint32_t* scr) { // CMD55 (APP_CMD) if (send_command_and_check(Command_Index::CMD55, static_cast(sdcard_rca_ << RCA_Shift), - Command_Response::RSP_SHORT, Wait_Type::WT_NONE, [this, cmd = Command_Index::CMD55]() { + Command_Response::RSP_SHORT, Wait_Type::WT_NONE, [this, cmd = Command_Index::CMD55]() { return get_r1_result(cmd); }) != SDIO_Error_Type::OK) { return SDIO_Error_Type::CMD55_FAILED; @@ -919,7 +910,7 @@ SDIO_Error_Type CardDMA::get_scr(uint16_t rca, uint32_t* scr) { // ACMD51 (SEND_SCR) if (send_command_and_check(Command_Index::ACMD51, 0U, Command_Response::RSP_SHORT, - Wait_Type::WT_NONE, [this, cmd = Command_Index::ACMD51]() { + Wait_Type::WT_NONE, [this, cmd = Command_Index::ACMD51]() { return get_r1_result(cmd); }) != SDIO_Error_Type::OK) { return SDIO_Error_Type::ACMD51_FAILED; @@ -928,36 +919,41 @@ SDIO_Error_Type CardDMA::get_scr(uint16_t rca, uint32_t* scr) { // Store SCR while (!sdio_.check_scr_flags()) { if (sdio_.get_flag(Status_Flags::FLAG_RXDTVAL)) { - *(temp_scr + index_scr) = sdio_.read_fifo_word(); - ++index_scr; + temp_scr[index_scr++] = sdio_.read_fifo_word(); } } + // Check for errors if (sdio_.get_flag(Status_Flags::FLAG_DTTMOUT)) { sdio_.clear_flag(Clear_Flags::FLAG_DTTMOUTC); return SDIO_Error_Type::DATA_TIMEOUT; - } else if (sdio_.get_flag(Status_Flags::FLAG_DTCRCERR)) { + } + else if (sdio_.get_flag(Status_Flags::FLAG_DTCRCERR)) { sdio_.clear_flag(Clear_Flags::FLAG_DTCRCERRC); return SDIO_Error_Type::DATA_CRC_ERROR; - } else if (sdio_.get_flag(Status_Flags::FLAG_RXORE)) { + } + else if (sdio_.get_flag(Status_Flags::FLAG_RXORE)) { sdio_.clear_flag(Clear_Flags::FLAG_RXOREC); return SDIO_Error_Type::RX_FIFO_OVERRUN; } sdio_.clear_multiple_interrupt_flags(clear_data_flags); - constexpr uint32_t Zero_Seven = (0xFFU << 0U); - constexpr uint32_t Eight_Fifteen = (0xFFU << 8U); - constexpr uint32_t Sixteen_Twentythree = (0xFFU << 16U); - constexpr uint32_t TwentyFour_Thirtyone = (0xFFU << 24U); + constexpr uint32_t BYTE0_MASK = 0xFFU; + constexpr uint32_t BYTE1_MASK = 0xFF00U; + constexpr uint32_t BYTE2_MASK = 0xFF0000U; + constexpr uint32_t BYTE3_MASK = 0xFF000000U; - // adjust SCR value - *src_data = ((temp_scr[1] & Zero_Seven) << 24U) | ((temp_scr[1] & Eight_Fifteen) << 8U) | - ((temp_scr[1] & Sixteen_Twentythree) >> 8U) | ((temp_scr[1] & TwentyFour_Thirtyone) >> 24U); + // Byte-swap the SCR values (convert from big-endian to little-endian) + scr[0] = ((temp_scr[1] & BYTE0_MASK) << 24) | + ((temp_scr[1] & BYTE1_MASK) << 8) | + ((temp_scr[1] & BYTE2_MASK) >> 8) | + ((temp_scr[1] & BYTE3_MASK) >> 24); - src_data = src_data + 1U; - *src_data = ((temp_scr[0] & Zero_Seven) << 24U) | ((temp_scr[0] & Eight_Fifteen) << 8U) | - ((temp_scr[0] & Sixteen_Twentythree) >> 8U) | ((temp_scr[0] & TwentyFour_Thirtyone) >> 24U); + scr[1] = ((temp_scr[0] & BYTE0_MASK) << 24) | + ((temp_scr[0] & BYTE1_MASK) << 8) | + ((temp_scr[0] & BYTE2_MASK) >> 8) | + ((temp_scr[0] & BYTE3_MASK) >> 24); return SDIO_Error_Type::OK; } @@ -965,23 +961,22 @@ SDIO_Error_Type CardDMA::get_scr(uint16_t rca, uint32_t* scr) { // DMA for rx/tx is always DMA1 channel 3 void CardDMA::set_dma_parameters(uint8_t* buf, uint32_t count, bool is_write) { constexpr uint32_t flag_bits = (1U << static_cast(dma::INTF_Bits::GIF3)); - dma_.clear_flags(flag_bits); // Disable and reset DMA dma_.set_channel_enable(false); dma_.clear_channel(); - dma_.init({ - count, - static_cast(reinterpret_cast(buf)), - static_cast(reinterpret_cast(sdio_.reg_address(SDIO_Regs::FIFO))), - dma::Bit_Width::WIDTH_32BIT, - dma::Bit_Width::WIDTH_32BIT, - dma::Increase_Mode::INCREASE_DISABLE, - dma::Increase_Mode::INCREASE_ENABLE, - dma::Channel_Priority::MEDIUM_PRIORITY, - is_write ? dma::Transfer_Direction::M2P : dma::Transfer_Direction::P2M + dma_.init(dma::DMA_Config{ + .count = count, + .memory_address = static_cast(reinterpret_cast(buf)), + .peripheral_address = static_cast(reinterpret_cast(sdio_.reg_address(SDIO_Regs::FIFO))), + .peripheral_bit_width = dma::Bit_Width::WIDTH_32BIT, + .memory_bit_width = dma::Bit_Width::WIDTH_32BIT, + .peripheral_increase = dma::Increase_Mode::INCREASE_DISABLE, + .memory_increase = dma::Increase_Mode::INCREASE_ENABLE, + .channel_priority = dma::Channel_Priority::MEDIUM_PRIORITY, + .direction = is_write ? dma::Transfer_Direction::M2P : dma::Transfer_Direction::P2M }); dma_.set_memory_to_memory_enable(false); @@ -995,24 +990,29 @@ void CardDMA::set_dma_parameters(uint8_t* buf, uint32_t count, bool is_write) { dma_.set_channel_enable(true); } -SDIO_Error_Type CardDMA::wait_for_card_ready() { - volatile uint32_t timeout = 0x00FFFFFFU; +auto CardDMA::wait_for_card_ready() -> SDIO_Error_Type { + constexpr uint32_t MAX_TIMEOUT = 0x00FFFFFFU; + uint32_t timeout = MAX_TIMEOUT; uint32_t response = sdio_.get_response(Response_Type::RESPONSE0); - while (((response & static_cast(R1_Status::READY_FOR_DATA)) == 0U) && (timeout != 0U)) { - // Continue to send CMD13 to poll the state of card until buffer empty or timeout - timeout = timeout - 1U; + // Poll until card is ready for data or timeout occurs + while (((response & static_cast(R1_Status::READY_FOR_DATA)) == 0U) && timeout) { + --timeout; + // CMD13 (SEND_STATUS) if (send_command_and_check(Command_Index::CMD13, static_cast(sdcard_rca_ << RCA_Shift), - Command_Response::RSP_SHORT, Wait_Type::WT_NONE, [this, cmd = Command_Index::CMD13]() { + Command_Response::RSP_SHORT, Wait_Type::WT_NONE, [this, cmd = Command_Index::CMD13]() { return get_r1_result(cmd); }) != SDIO_Error_Type::OK) { return SDIO_Error_Type::CMD13_FAILED; } + + // Get updated response response = sdio_.get_response(Response_Type::RESPONSE0); } - return (timeout == 0U) ? SDIO_Error_Type::ERROR : SDIO_Error_Type::OK; + // Return error if timeout occurred, otherwise success + return timeout ? SDIO_Error_Type::OK : SDIO_Error_Type::ERROR; } } // namespace sdio diff --git a/Marlin/src/HAL/GD32_MFL/sd/SDCard.h b/Marlin/src/HAL/GD32_MFL/sd/SDCard.h index e202be6eb5..b03d128dc8 100644 --- a/Marlin/src/HAL/GD32_MFL/sd/SDCard.h +++ b/Marlin/src/HAL/GD32_MFL/sd/SDCard.h @@ -26,76 +26,82 @@ class DMA; class CardDMA { public: - static CardDMA& get_instance(); + static auto get_instance() -> CardDMA&; - SDIO_Error_Type init(); - SDIO_Error_Type card_init(); - SDIO_Error_Type begin_startup_procedure(); + // Initialization + auto init() -> SDIO_Error_Type; + auto card_init() -> SDIO_Error_Type; + + // Startup and shutdown procedures + auto begin_startup_procedure() -> SDIO_Error_Type; void begin_shutdown_procedure(); + // Configuration - SDIO_Error_Type set_hardware_bus_width(Bus_Width width); - // Main read/write functions for single and multiblock transfers - SDIO_Error_Type read(uint8_t* buf, uint32_t address, uint32_t count); - SDIO_Error_Type write(uint8_t* buf, uint32_t address, uint32_t count); - // DMA transfers - // Other card functions - SDIO_Error_Type erase(uint32_t address_start, uint32_t address_end); - // Interrupt handler - void handle_interrupts(); + auto set_hardware_bus_width(Bus_Width width) -> SDIO_Error_Type; + auto send_bus_width_command(uint32_t width_value) -> SDIO_Error_Type; + + // Main read/write/erase functions + auto read(uint8_t* buf, uint32_t address, uint32_t count) -> SDIO_Error_Type; + auto write(uint8_t* buf, uint32_t address, uint32_t count) -> SDIO_Error_Type; + auto erase(uint32_t address_start, uint32_t address_end) -> SDIO_Error_Type; + // Card select - SDIO_Error_Type select_deselect(); + auto select_deselect() -> SDIO_Error_Type; - SDIO_Error_Type get_card_interface_status(uint32_t* status); - SDIO_Error_Type get_sdcard_status(uint32_t* status); + // Status and state + auto get_card_interface_status(uint32_t* status) -> SDIO_Error_Type; + auto get_sdcard_status(uint32_t* status) -> SDIO_Error_Type; + auto get_transfer_state() -> Transfer_State; + auto get_card_state(Card_State* card_state) -> SDIO_Error_Type; + auto check_sdio_status(Command_Index index = Command_Index::INVALID, bool check_index = false, bool ignore_crc = false) -> SDIO_Error_Type; - void check_dma_complete(); - SDIO_Error_Type stop_transfer(); - - Transfer_State get_transfer_state(); - uint32_t get_card_capacity() const; - - SDIO_Error_Type send_bus_width_command(uint32_t width_value); - - SDIO_Error_Type get_card_specific_data(Card_Info* info); - constexpr Block_Size get_data_block_size_index(uint16_t size); - - SDIO_Error_Type get_card_state(Card_State* card_state); - SDIO_Error_Type check_sdio_status(Command_Index index = Command_Index::INVALID, bool check_index = false, bool ignore_crc = false); - - // DMA configuration + // DMA void set_dma_parameters(uint8_t* buf, uint32_t count, bool is_write); + void check_dma_complete(); + + // Stop transfer + auto stop_transfer() -> SDIO_Error_Type; + + // Card information + auto get_card_specific_data(Card_Info* info) -> SDIO_Error_Type; + constexpr auto get_data_block_size_index(uint16_t size) -> Block_Size; + [[nodiscard]] auto get_card_capacity() const -> uint32_t; // SDIO configuration void sdio_configure(const SDIO_Config config) { sdio_.init(config); } - // Varaible stored parameters - SDIO_Error_Type get_scr(uint16_t rca, uint32_t* scr); - SDIO_Error_Type store_cid(); - SDIO_Error_Type store_csd(); + // Interrupt handler + void handle_interrupts(); - // Accessor methods - SDIO_Config& get_config() { return config_; } - dma::DMA& get_dma_instance() { return dma_; } + // Varaible stored parameters + auto get_scr(uint16_t rca, uint32_t* scr) -> SDIO_Error_Type; + auto store_cid() -> SDIO_Error_Type; + auto store_csd() -> SDIO_Error_Type; + + // Inlined accessor methods + auto get_config() -> SDIO_Config& { return config_; } + auto get_dma_instance() -> dma::DMA& { return dma_; } void set_data_end_interrupt() { sdio_.set_interrupt_enable(Interrupt_Type::DTENDIE, true); } void set_sdio_dma_enable(bool enable) { sdio_.set_dma_enable(enable); } - bool get_is_sdio_rx() { return is_rx_; } + auto get_is_sdio_rx() -> bool { return is_rx_; } void clear_sdio_data_flags() { sdio_.clear_multiple_interrupt_flags(clear_data_flags); } void clear_sdio_cmd_flags() { sdio_.clear_multiple_interrupt_flags(clear_command_flags); } void clear_sdio_common_flags() { sdio_.clear_multiple_interrupt_flags(clear_common_flags); } - Operational_State get_state() { return current_state_; } + auto get_state() -> Operational_State { return current_state_; } void set_state(Operational_State state) { current_state_ = state; } - void set_transfer_end(bool value) { transfer_end_ = value; } void set_transfer_error(SDIO_Error_Type error) { transfer_error_ = error; } + void set_transfer_end(bool end) { transfer_end_ = end; }; - inline SDIO_Error_Type set_desired_clock(uint32_t desired_clock, bool wide_bus, bool low_power) { - sdio_.init({ - desired_clock, - Clock_Edge::RISING_EDGE, - wide_bus ? Bus_Width::WIDTH_4BIT : Bus_Width::WIDTH_1BIT, - false, - low_power, - false + auto set_desired_clock(uint32_t desired_clock, bool wide_bus, bool low_power) -> SDIO_Error_Type { + sdio_.init(SDIO_Config{ + .desired_clock = desired_clock, + .enable_bypass = false, + .enable_powersave = low_power, + .enable_hwclock = false, + .clock_edge = Clock_Edge::RISING_EDGE, + .width = wide_bus ? Bus_Width::WIDTH_4BIT : Bus_Width::WIDTH_1BIT }); + sync_domains(); desired_clock_ = desired_clock; @@ -107,19 +113,17 @@ private: // Prevent copying or assigning CardDMA(const CardDMA&) = delete; - CardDMA& operator=(const CardDMA&) = delete; + auto operator=(const CardDMA&) -> CardDMA& = delete; // Helper function - SDIO_Error_Type wait_for_card_ready(); + auto wait_for_card_ready() -> SDIO_Error_Type; // Member variables alignas(4) uint32_t sdcard_csd_[4]; alignas(4) uint32_t sdcard_cid_[4]; alignas(4) uint32_t sdcard_scr_[2]; uint32_t desired_clock_; - uint32_t stop_condition_; uint32_t total_bytes_; - uint32_t count_; SDIO& sdio_; SDIO_Config& config_; const dma::DMA_Base dmaBase_; @@ -129,66 +133,70 @@ private: SDIO_Error_Type transfer_error_; Interface_Version interface_version_; Card_Type card_type_; - volatile bool transfer_end_; - volatile bool is_rx_; - volatile bool multiblock_; - volatile Operational_State current_state_; + Operational_State current_state_; + bool transfer_end_; + bool multiblock_; + bool is_rx_; // Private helper methods - SDIO_Error_Type validate_voltage(); - SDIO_Error_Type get_r1_result(Command_Index index); - //SDIO_Error_Type get_r2_r3_result(); - SDIO_Error_Type get_r6_result(Command_Index index, uint16_t* rca); - SDIO_Error_Type get_r7_result(); - //SDIO_Error_Type get_r1_error_type(uint32_t response); - SDIO_Error_Type get_command_sent_result(); + auto validate_voltage() -> SDIO_Error_Type; + auto get_command_sent_result() -> SDIO_Error_Type; + auto get_r1_result(Command_Index index) -> SDIO_Error_Type; + auto get_r6_result(Command_Index index, uint16_t* rca) -> SDIO_Error_Type; + auto get_r7_result() -> SDIO_Error_Type { return check_sdio_status(Command_Index::INVALID, false, false); }; + void sync_domains() { delayMicroseconds(8); } - inline void sync_domains() { - delayMicroseconds(8); - } - - inline bool validate_transfer_params(uint32_t* buf, uint16_t size) { + auto validate_transfer_params(uint32_t* buf, uint16_t size) -> bool { if (buf == nullptr) return false; // Size must be > 0, <= 2048 and power of 2 - if ((size == 0U) || (size > 2048U) || (size & (size - 1U))) { - return false; - } - return true; + return size > 0U && size <= 2048U && !(size & (size - 1U)); } void process_sdsc_specific_csd(Card_Info* info, const uint8_t* csd_bytes) { - info->csd.device_size = (static_cast(csd_bytes[6] & 0x03U) << 10U) | - (static_cast(csd_bytes[7]) << 2U) | - (static_cast((csd_bytes[8] & 0xC0U) >> 6U)); - info->csd.device_size_multiplier = static_cast((csd_bytes[9] & 0x03U) << 1U | - (csd_bytes[10] & 0x80U) >> 7U); + const uint32_t device_size = ((csd_bytes[6] & 0x3U) << 10) | + (csd_bytes[7] << 2) | + ((csd_bytes[8] >> 6) & 0x3U); - info->block_size = static_cast(1 << info->csd.read_block_length); - info->capacity = static_cast((info->csd.device_size + 1U) * - (1U << (info->csd.device_size_multiplier + 2U)) * - info->block_size); + const uint8_t device_size_multiplier = ((csd_bytes[9] & 0x3U) << 1) | + ((csd_bytes[10] >> 7) & 0x1U); + + // Store calculated values + info->csd.device_size = device_size; + info->csd.device_size_multiplier = device_size_multiplier; + + // Calculate block size and capacity + info->block_size = 1U << info->csd.read_block_length; + info->capacity = (device_size + 1U) * + (1U << (device_size_multiplier + 2U)) * + info->block_size; } void process_sdhc_specific_csd(Card_Info* info, const uint8_t* csd_bytes) { - info->csd.device_size = static_cast((csd_bytes[7] & 0x3FU) << 16U) | - static_cast((csd_bytes[8]) << 8U) | - static_cast(csd_bytes[9]); + info->csd.device_size = static_cast((csd_bytes[7] & 0x3FU) << 16) | + static_cast((csd_bytes[8]) << 8) | + static_cast(csd_bytes[9]); + // Set block size and calculate capacity info->block_size = BLOCK_SIZE; info->capacity = static_cast((info->csd.device_size + 1U) * - BLOCK_SIZE * KILOBYTE); + BLOCK_SIZE * KILOBYTE); } void process_common_csd_tail(Card_Info* info, const uint8_t* csd_bytes) { - info->csd.sector_size = static_cast(((csd_bytes[9] & 0x3FU) << 1U) | - (csd_bytes[10] & 0x80U) >> 7U); - info->csd.speed_factor = static_cast((csd_bytes[11] & 0x1CU) >> 2U); - info->csd.write_block_length = static_cast(((csd_bytes[11] & 0x03U) << 2U) | - ((csd_bytes[12] & 0xC0U) >> 6U)); - info->csd.checksum = static_cast((csd_bytes[15] & 0xFEU) >> 1U); + // Calculate sector_size + info->csd.sector_size = static_cast(((csd_bytes[9] & 0x3FU) << 1) | + (csd_bytes[10] & 0x80U) >> 7); + + // Calculate speed_factor and write_block_length + info->csd.speed_factor = static_cast((csd_bytes[11] & 0x1CU) >> 2); + info->csd.write_block_length = static_cast(((csd_bytes[11] & 0x3U) << 2) | + ((csd_bytes[12] & 0xC0U) >> 6)); + + // Calculate checksum + info->csd.checksum = static_cast((csd_bytes[15] & 0xFEU) >> 1); } - inline void disable_all_interrupts() { + void disable_all_interrupts() { sdio_.set_interrupt_enable(Interrupt_Type::DTCRCERRIE, false); sdio_.set_interrupt_enable(Interrupt_Type::DTTMOUTIE, false); sdio_.set_interrupt_enable(Interrupt_Type::DTENDIE, false); @@ -200,8 +208,8 @@ private: } template - inline SDIO_Error_Type send_command_and_check(Command_Index command, uint32_t argument, - Command_Response response, Wait_Type type, CheckFunc check_result) { + auto send_command_and_check(Command_Index command, uint32_t argument, + Command_Response response, Wait_Type type, CheckFunc check_result) -> SDIO_Error_Type { sdio_.set_command_state_machine(command, argument, response, type); sync_domains(); sdio_.set_command_state_machine_enable(true); diff --git a/Marlin/src/HAL/GD32_MFL/sd/sdio.cpp b/Marlin/src/HAL/GD32_MFL/sd/sdio.cpp index 69905feb51..a474c1977e 100644 --- a/Marlin/src/HAL/GD32_MFL/sd/sdio.cpp +++ b/Marlin/src/HAL/GD32_MFL/sd/sdio.cpp @@ -47,7 +47,7 @@ inline constexpr uint8_t SDIO_READ_RETRIES = READ_RETRIES; Card_State cardState = Card_State::READY; -bool SDIO_SetBusWidth(Bus_Width width) { +auto SDIO_SetBusWidth(Bus_Width width) -> bool { return (CardDMA_I.set_hardware_bus_width(width) == SDIO_Error_Type::OK); } diff --git a/Marlin/src/HAL/GD32_MFL/sd/sdio.h b/Marlin/src/HAL/GD32_MFL/sd/sdio.h index b6b027ba77..a39e8c7a66 100644 --- a/Marlin/src/HAL/GD32_MFL/sd/sdio.h +++ b/Marlin/src/HAL/GD32_MFL/sd/sdio.h @@ -32,5 +32,5 @@ #define SDIO_CMD_PIN PD2 void sdio_mfl_init(); -bool SDIO_SetBusWidth(sdio::Bus_Width width); +auto SDIO_SetBusWidth(sdio::Bus_Width width) -> bool; void DMA1_IRQHandler(dma::DMA_Channel channel); diff --git a/Marlin/src/HAL/GD32_MFL/timers.h b/Marlin/src/HAL/GD32_MFL/timers.h index 0eb6bd563a..49d005b8cd 100644 --- a/Marlin/src/HAL/GD32_MFL/timers.h +++ b/Marlin/src/HAL/GD32_MFL/timers.h @@ -89,7 +89,7 @@ static inline constexpr struct {timer::TIMER_Base base; uint8_t timer_number;} b }; // Converts a timer base to an integer timer index. -constexpr int timer_base_to_index(timer::TIMER_Base base) { +constexpr auto timer_base_to_index(timer::TIMER_Base base) -> int { for (const auto& timer : base_to_index) { if (timer.base == base) { return static_cast(timer.timer_number); @@ -131,7 +131,7 @@ FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_number) FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_number, const hal_timer_t value) { if (!HAL_timer_initialized(timer_number)) return; - const uint32_t new_value = static_cast(value + 1U); + const auto new_value = static_cast(value + 1U); GeneralTimer& timer = (timer_number == MF_TIMER_STEP) ? Step_Timer : Temp_Timer; if (timer_number == MF_TIMER_STEP || timer_number == MF_TIMER_TEMP) { diff --git a/ini/gd32.ini b/ini/gd32.ini index 5187895021..d9cc3f7082 100644 --- a/ini/gd32.ini +++ b/ini/gd32.ini @@ -10,7 +10,7 @@ #################################### [gd32_base] -platform = https://github.com/bmourit/platform-mfl/archive/refs/tags/V1.0.3.zip +platform = https://github.com/bmourit/platform-mfl/archive/refs/tags/V1.0.4.zip board_build.core = gd32 build_src_filter = ${common.default_src_filter} + + build_unflags = -std=gnu++11 -std=gnu++14 -std=gnu++17 @@ -28,7 +28,7 @@ extra_scripts = ${common.extra_scripts} # [env:GD32F303RE_creality_mfl] extends = gd32_base -board = mfl_creality_422 +board = mfl_creality_v4 board_build.offset = 0x7000 board_upload.offset_address = 0x08007000 board_build.rename = firmware-{time}.bin From e2583b4f85eb128611b0af1af7117e215ddb0961 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 6 May 2025 00:31:19 +0000 Subject: [PATCH 006/102] [cron] Bump distribution date (2025-05-06) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 4abad36238..38fbe78024 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-05-05" +//#define STRING_DISTRIBUTION_DATE "2025-05-06" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index bb924b75bb..200c24ea62 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-05-05" + #define STRING_DISTRIBUTION_DATE "2025-05-06" #endif /** From 67948ad6c62b1034b815d219c0b7bfc475b03767 Mon Sep 17 00:00:00 2001 From: Andrew <18502096+classicrocker883@users.noreply.github.com> Date: Mon, 5 May 2025 21:19:52 -0400 Subject: [PATCH 007/102] =?UTF-8?q?=F0=9F=9A=B8=20Fix=20ProUI=20LCD=20wake?= =?UTF-8?q?=20up=20(2)=20(#27835)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to #27832 --- Marlin/src/lcd/e3v2/proui/dwin.cpp | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index aa77704786..c3a69c1c66 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -1278,7 +1278,7 @@ void hmiWaitForUser() { if (!wait_for_user) { switch (checkkey) { case ID_PrintDone: select_page.reset(); gotoMainMenu(); break; - default: hmiReturnScreen(); break; + default: ui.reset_status(true); hmiReturnScreen(); break; } } } @@ -1958,8 +1958,11 @@ void MarlinUI::update() { #if HAS_LCD_BRIGHTNESS void MarlinUI::_set_brightness() { - if (!backlight) wait_for_user = true; dwinLCDBrightness(backlight ? brightness : 0); + if (!backlight) + wait_for_user = true; + else if (checkkey != ID_PrintDone) + wait_for_user = false; } #endif From 3a3c3b8a222f0b9f989e7f2fb2afc109637685f7 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 5 May 2025 20:32:02 -0500 Subject: [PATCH 008/102] =?UTF-8?q?=F0=9F=94=A8=20Fix=20build=20flags=20fo?= =?UTF-8?q?r=20env:mks=5Fmonster8=5Fusb=5Fflash=5Fdrive?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ini/stm32f4.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index 0e9dc9102a..c29e3180eb 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -639,7 +639,7 @@ upload_protocol = jlink [env:mks_monster8_usb_flash_drive] extends = env:mks_monster8 platform_packages = ${stm_flash_drive.platform_packages} -build_flags = ${stm_flash_drive.build_flags} ${stm32f4_I2C1_CAN.build_flags} ${USB_HS_IN_FS.build_flags} +build_flags = ${env:mks_monster8.build_flags} ${stm_flash_drive.build_flags} ${stm32f4_I2C1_CAN.build_flags} ${USB_HS_IN_FS.build_flags} # # MKS Monster8 V1 / V2 (STM32F407VET6 ARM Cortex-M4) with USB Flash Drive Support and Shared Media From b7a1681d38cb30e5477e0560ef8cf29791b0286c Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 5 May 2025 21:07:47 -0500 Subject: [PATCH 009/102] =?UTF-8?q?=F0=9F=94=A8=20Fix=20some=20build=5Ffla?= =?UTF-8?q?gs=20inheritance?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/share/PlatformIO/variants/README.md | 23 +++++++++++++ ini/stm32-common.ini | 3 +- ini/stm32f4.ini | 32 +++++++++---------- 3 files changed, 40 insertions(+), 18 deletions(-) create mode 100644 buildroot/share/PlatformIO/variants/README.md diff --git a/buildroot/share/PlatformIO/variants/README.md b/buildroot/share/PlatformIO/variants/README.md new file mode 100644 index 0000000000..ae64b1b439 --- /dev/null +++ b/buildroot/share/PlatformIO/variants/README.md @@ -0,0 +1,23 @@ +# Marlin Custom Variants + +This `buildroot/share/PlatformIO/variants` folder contains Marlin custom variants for both generic and custom boards. + +Marlin specifies board variants in PlatformIO INI files in one of two ways: +- The `board_build.variant = VARIANT_MAME` field specifies the variant subfolder name directly. +- The `board = board_name` field names a custom board JSON file that contains a `build.variant` field. + +## Variant File Naming + +With the latest STM32 platform (17.x) the `variant.h` and `variant.cpp` files are required to have more unique names. If the variant is based on a generic board definition the name `variant_generic.h`/`.cpp` should be used. Otherwise, the capitalized name of the `board` should be used. + +### Examples + +| board | board file | variant | Variant Files | +|-------|------------|---------|---------------| +|`marlin_STM32F407VGT6_CCM`|`marlin_STM32F407VGT6_CCM.json`|`MARLIN_BTT_E3_RRF`|`variants/MARLIN_BTT_E3_RRF/variant.*`| +|`genericSTM32F103VE`|n/a|`MARLIN_F103Vx`|`variants/MARLIN_F103Vx/variant_generic.*`| +|`marlin_STM32F407ZE`|`marlin_STM32F407ZE.json`|`MARLIN_F407ZE`|`variants/MARLIN_F407ZE/variant_MARLIN_F407ZE.*`| + +# Marlin Custom Boards + +The `buildroot/share/PlatformIO/boards` folder contains Marlin's custom board definition JSON files. These files provide hardware IDs, board statistics, additional build flags, custom variant name, linker definition filename, remote debug options, upload devices, etc. diff --git a/ini/stm32-common.ini b/ini/stm32-common.ini index ec058d1087..12c07ef824 100644 --- a/ini/stm32-common.ini +++ b/ini/stm32-common.ini @@ -41,6 +41,5 @@ extra_scripts = ${common_stm32.extra_scripts} [stm_flash_drive] # Arduino_Core_STM32 uses usb-host-msc-cdc-msc-3 branch platform_packages = framework-arduinoststm32@https://github.com/rhapsodyv/Arduino_Core_STM32/archive/39f37d6d6a.zip -build_flags = ${common_stm32.build_flags} - -DHAL_PCD_MODULE_ENABLED -DHAL_HCD_MODULE_ENABLED +build_flags = -DHAL_PCD_MODULE_ENABLED -DHAL_HCD_MODULE_ENABLED -DUSBHOST -DUSBH_IRQ_PRIO=3 -DUSBH_IRQ_SUBPRIO=4 diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index c29e3180eb..f32734eee3 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -219,7 +219,7 @@ upload_protocol = stlink [env:BTT_SKR_PRO_usb_flash_drive] extends = env:BTT_SKR_PRO platform_packages = ${stm_flash_drive.platform_packages} -build_flags = ${stm_flash_drive.build_flags} -DSTM32F407_5ZX +build_flags = ${env:BTT_SKR_PRO.build_flags} ${stm_flash_drive.build_flags} -DSTM32F407_5ZX build_unflags = ${env:BTT_SKR_PRO.build_unflags} -DUSBCON -DUSBD_USE_CDC # @@ -266,7 +266,7 @@ build_flags = ${stm32_variant.build_flags} -DSTM32F407IX [env:BTT_GTR_V1_0_usb_flash_drive] extends = env:BTT_GTR_V1_0 platform_packages = ${stm_flash_drive.platform_packages} -build_flags = ${stm_flash_drive.build_flags} -DSTM32F407IX +build_flags = ${env:BTT_GTR_V1_0.build_flags} ${stm_flash_drive.build_flags} -DSTM32F407IX build_unflags = ${env:BTT_GTR_V1_0.build_unflags} -DUSBCON -DUSBD_USE_CDC # @@ -304,7 +304,7 @@ board = marlin_STM32F407VGT6_CCM board_build.variant = MARLIN_F4x7Vx board_build.offset = 0x8000 board_upload.offset_address = 0x08008000 -build_flags = ${stm_flash_drive.build_flags} ${USB_HS_IN_FS.build_flags} +build_flags = ${stm32_variant.build_flags} ${stm_flash_drive.build_flags} ${USB_HS_IN_FS.build_flags} -DHSE_VALUE=8000000U -DHAL_SD_MODULE_ENABLED -DPIN_SERIAL3_RX=PD_9 -DPIN_SERIAL3_TX=PD_8 upload_protocol = stlink @@ -362,7 +362,7 @@ build_flags = ${stm32_variant.build_flags} extends = env:STM32F446ZE_btt platform_packages = ${stm_flash_drive.platform_packages} build_unflags = -DUSBD_USE_CDC -build_flags = ${stm_flash_drive.build_flags} -DSTM32F446_5VX +build_flags = ${env:STM32F446ZE_btt.build_flags} ${stm_flash_drive.build_flags} -DSTM32F446_5VX ${USB_HS_IN_FS.build_flags} -DUSBD_USE_CDC_MSC # @@ -385,7 +385,7 @@ build_flags = ${stm32_variant.build_flags} extends = env:STM32F429ZG_btt platform_packages = ${stm_flash_drive.platform_packages} build_unflags = -DUSBD_USE_CDC -build_flags = ${stm_flash_drive.build_flags} +build_flags = ${env:STM32F429ZG_btt.build_flags} ${stm_flash_drive.build_flags} ${USB_HS_IN_FS.build_flags} -DUSBD_USE_CDC_MSC # @@ -406,7 +406,7 @@ build_flags = ${stm32_variant.build_flags} extends = env:STM32F407ZE_btt platform_packages = ${stm_flash_drive.platform_packages} build_unflags = -DUSBD_USE_CDC -build_flags = ${stm_flash_drive.build_flags} ${USB_HS_IN_FS.build_flags} -DUSBD_USE_CDC_MSC +build_flags = ${env:STM32F407ZE_btt.build_flags} ${stm_flash_drive.build_flags} ${USB_HS_IN_FS.build_flags} -DUSBD_USE_CDC_MSC # # Lerdge base @@ -438,7 +438,7 @@ board_build.crypt_lerdge = Lerdge_X_firmware_force.bin [env:LERDGEX_usb_flash_drive] extends = env:LERDGEX platform_packages = ${stm_flash_drive.platform_packages} -build_flags = ${stm_flash_drive.build_flags} ${lerdge_common.build_flags} +build_flags = ${env:LERDGEX.build_flags} ${stm_flash_drive.build_flags} # # Lerdge S (STM32F407ZG) @@ -453,7 +453,7 @@ board_build.crypt_lerdge = Lerdge_firmware_force.bin [env:LERDGES_usb_flash_drive] extends = env:LERDGES platform_packages = ${stm_flash_drive.platform_packages} -build_flags = ${stm_flash_drive.build_flags} ${lerdge_common.build_flags} +build_flags = ${env:LERDGES.build_flags} ${stm_flash_drive.build_flags} # # Lerdge K (STM32F407ZG) @@ -469,7 +469,7 @@ build_flags = ${lerdge_common.build_flags} -DLERDGEK [env:LERDGEK_usb_flash_drive] extends = env:LERDGEK platform_packages = ${stm_flash_drive.platform_packages} -build_flags = ${stm_flash_drive.build_flags} ${lerdge_common.build_flags} +build_flags = ${env:LERDGEK.build_flags} ${stm_flash_drive.build_flags} # # RUMBA32 @@ -512,7 +512,7 @@ board = genericSTM32F407VET6 board_build.variant = MARLIN_F4x7Vx board_build.offset = 0x0000 board_upload.offset_address = 0x08000000 -build_flags = ${stm_flash_drive.build_flags} +build_flags = ${stm32_variant.build_flags} ${stm_flash_drive.build_flags} build_unflags = ${stm32_variant.build_unflags} -DUSBCON -DUSBD_USE_CDC debug_tool = jlink upload_protocol = jlink @@ -544,7 +544,7 @@ upload_protocol = jlink [env:mks_robin_nano_v3_usb_flash_drive] extends = env:mks_robin_nano_v3 platform_packages = ${stm_flash_drive.platform_packages} -build_flags = ${stm_flash_drive.build_flags} ${stm32f4_I2C1.build_flags} ${USB_HS_IN_FS.build_flags} +build_flags = ${env:mks_robin_nano_v3.build_flags} ${stm_flash_drive.build_flags} ${stm32f4_I2C1.build_flags} ${USB_HS_IN_FS.build_flags} # # MKS Robin Nano V3 with USB Flash Drive Support and Shared Media @@ -600,7 +600,7 @@ upload_protocol = jlink [env:mks_eagle_usb_flash_drive] extends = env:mks_eagle platform_packages = ${stm_flash_drive.platform_packages} -build_flags = ${stm_flash_drive.build_flags} ${stm32f4_I2C1.build_flags} ${USB_HS_IN_FS.build_flags} +build_flags = ${env:mks_eagle.build_flags} ${stm_flash_drive.build_flags} ${stm32f4_I2C1.build_flags} ${USB_HS_IN_FS.build_flags} # # MKS Eagle with USB Flash Drive Support and Shared Media @@ -699,9 +699,9 @@ board_build.offset = 0xC000 board_upload.offset_address = 0x0800C000 board_build.rename = elegoo.bin platform_packages = ${stm_flash_drive.platform_packages} -build_flags = ${stm32_variant.build_flags} ${stm32f4_I2C1.build_flags} - ${stm_flash_drive.build_flags} ${USB_HS_IN_FS.build_flags} - -DHAL_PCD_MODULE_ENABLED -DHAL_SD_MODULE_ENABLED -DHAL_SRAM_MODULE_ENABLED +build_flags = ${stm32_variant.build_flags} ${stm_flash_drive.build_flags} + ${stm32f4_I2C1.build_flags} ${USB_HS_IN_FS.build_flags} + -DHAL_SD_MODULE_ENABLED -DHAL_SRAM_MODULE_ENABLED -DMCU_STM32F407VE -DSS_TIMER=4 -DENABLE_HWSERIAL3 -DSTM32_FLASH_SIZE=512 -DTIMER_TONE=TIM3 -DTIMER_SERVO=TIM2 @@ -997,6 +997,6 @@ board = marlin_STM32F407VGT6_CCM board_build.variant = MARLIN_F4x7Vx board_build.offset = 0x8000 board_upload.offset_address = 0x08008000 -build_flags = ${stm_flash_drive.build_flags} ${USB_HS_IN_FS.build_flags} +build_flags = ${stm32_variant.build_flags} ${stm_flash_drive.build_flags} ${USB_HS_IN_FS.build_flags} -DHSE_VALUE=8000000U -DHAL_SD_MODULE_ENABLED -DPIN_SERIAL3_RX=PD_9 -DPIN_SERIAL3_TX=PD_8 From 5266ffb922402f2a5decfc2eb70a93c71bbca1a0 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 7 May 2025 00:31:25 +0000 Subject: [PATCH 010/102] [cron] Bump distribution date (2025-05-07) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 38fbe78024..1453ec68e8 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-05-06" +//#define STRING_DISTRIBUTION_DATE "2025-05-07" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 200c24ea62..a682e48fa1 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-05-06" + #define STRING_DISTRIBUTION_DATE "2025-05-07" #endif /** From d806175a80786eba5ebc98ddfd889ff22daa9b51 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 6 May 2025 22:06:47 -0500 Subject: [PATCH 011/102] =?UTF-8?q?=E2=9C=A8=20OTA=5FFIRMWARE=5FUPDATE=20(?= =?UTF-8?q?Creality=20STM32F401RE)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to #25773 --- Marlin/Configuration_adv.h | 3 +++ Marlin/src/gcode/ota/M936.cpp | 1 - 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index a48a337270..f31a284d81 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1938,6 +1938,9 @@ //#define CUSTOM_FIRMWARE_UPLOAD #endif + // "Over-the-air" Firmware Update with M936 - Required to set EEPROM flag + //#define OTA_FIRMWARE_UPDATE + /** * Set this option to one of the following (or the board's defaults apply): * diff --git a/Marlin/src/gcode/ota/M936.cpp b/Marlin/src/gcode/ota/M936.cpp index f42d197f4e..353e423c77 100644 --- a/Marlin/src/gcode/ota/M936.cpp +++ b/Marlin/src/gcode/ota/M936.cpp @@ -34,7 +34,6 @@ /** * M936: Set one of the OTA update flags. * V2 = Upgrade the motherboard firmware - * V3 = Upgrade the RTS controller firmware */ void GcodeSuite::M936() { static uint8_t ota_update_flag = 0x00; From 222efe13824c9dd2b1c79f7e9f2f6bcd85d2ba41 Mon Sep 17 00:00:00 2001 From: David Buezas Date: Wed, 7 May 2025 05:15:44 +0200 Subject: [PATCH 012/102] =?UTF-8?q?=F0=9F=94=A7=20No=20SMOOTH=5FLIN=5FADVA?= =?UTF-8?q?NCE=20+=20NONLINEAR=5FEXTRUSION=20(#27817)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/SanityCheck.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 8a293b52a8..df86cea522 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -868,6 +868,8 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L #error "SMOOTH_LIN_ADVANCE requires a 32-bit CPU." #elif ENABLED(S_CURVE_ACCELERATION) #error "SMOOTH_LIN_ADVANCE is not compatible with S_CURVE_ACCELERATION." + #elif ENABLED(NONLINEAR_EXTRUSION) + #error "SMOOTH_LIN_ADVANCE doesn't currently support NONLINEAR_EXTRUSION." #elif ENABLED(INPUT_SHAPING_E_SYNC) && NONE(INPUT_SHAPING_X, INPUT_SHAPING_Y) #error "INPUT_SHAPING_E_SYNC requires INPUT_SHAPING_X or INPUT_SHAPING_Y." #endif From a4d254ee62b36d44f9ca22dffba04c5d4c43f8fe Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Thu, 8 May 2025 06:36:06 +1200 Subject: [PATCH 013/102] =?UTF-8?q?=F0=9F=9A=B8=20Fix=2016x4=20SD=20Print?= =?UTF-8?q?=20Progress=20display=20(#27844)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/HD44780/marlinui_HD44780.cpp | 2 +- ini/native.ini | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp index 265f62ab88..359122f8b6 100644 --- a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp +++ b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp @@ -1001,7 +1001,7 @@ void MarlinUI::draw_status_screen() { #if LCD_WIDTH < 20 #if HAS_PRINT_PROGRESS - TERN_(SHOW_PROGRESS_PERCENT, setPercentPos(0, 2)); + TERN_(SHOW_PROGRESS_PERCENT, setPercentPos(0, 1)); rotate_progress(); #endif diff --git a/ini/native.ini b/ini/native.ini index f01e72ca67..f27285e83a 100644 --- a/ini/native.ini +++ b/ini/native.ini @@ -58,7 +58,7 @@ debug_build_flags = -fstack-protector-strong -g -g3 -ggdb lib_compat_mode = off build_src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} - MarlinSimUI=https://github.com/p3p/MarlinSimUI/archive/6ea016e104.zip + MarlinSimUI=https://github.com/p3p/MarlinSimUI/archive/dd9c41f1b2.zip Adafruit NeoPixel=https://github.com/p3p/Adafruit_NeoPixel/archive/c6b319f447.zip LiquidCrystal=https://github.com/p3p/LiquidCrystal/archive/322fb5fc23.zip extra_scripts = ${common.extra_scripts} From aa7af2e2ea6f3744152031d10ee645cd8d470855 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 8 May 2025 00:31:45 +0000 Subject: [PATCH 014/102] [cron] Bump distribution date (2025-05-08) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 1453ec68e8..e21fc7c479 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-05-07" +//#define STRING_DISTRIBUTION_DATE "2025-05-08" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index a682e48fa1..9eb50bff90 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-05-07" + #define STRING_DISTRIBUTION_DATE "2025-05-08" #endif /** From 72f3a4ac3118e8235030e907bf3473ea7502eba3 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 8 May 2025 13:45:38 -0500 Subject: [PATCH 015/102] =?UTF-8?q?=E2=9A=A1=EF=B8=8F=20Optimal=20recalcul?= =?UTF-8?q?ate=5Fmax=5Fe=5Fjerk?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/planner.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index a2f91edc81..73c77ee7f5 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -1088,8 +1088,8 @@ class Planner { #if HAS_LINEAR_E_JERK FORCE_INLINE static void recalculate_max_e_jerk() { const float prop = junction_deviation_mm * SQRT(0.5) / (1.0f - SQRT(0.5)); - EXTRUDER_LOOP() - max_e_jerk[E_INDEX_N(e)] = SQRT(prop * settings.max_acceleration_mm_per_s2[E_AXIS_N(e)]); + for (uint8_t i = 0; i < DISTINCT_E; ++i) + max_e_jerk[i] = SQRT(prop * settings.max_acceleration_mm_per_s2[E_AXIS + i]); } #endif From fd117480d2cca5d55c787035550005c2d4cc1776 Mon Sep 17 00:00:00 2001 From: B Date: Thu, 8 May 2025 14:17:47 -0700 Subject: [PATCH 016/102] =?UTF-8?q?=E2=9A=A1=EF=B8=8F=20GD32:=20Fast=20GPI?= =?UTF-8?q?O=20optimization=20(#27845)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/GD32_MFL/fastio.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/src/HAL/GD32_MFL/fastio.h b/Marlin/src/HAL/GD32_MFL/fastio.h index 35829e856f..11020f3e52 100644 --- a/Marlin/src/HAL/GD32_MFL/fastio.h +++ b/Marlin/src/HAL/GD32_MFL/fastio.h @@ -29,17 +29,17 @@ #include template -static inline void fast_write_pin_wrapper(pin_size_t IO, T V) { +FORCE_INLINE static void fast_write_pin_wrapper(pin_size_t IO, T V) { const PortPinPair& pp = port_pin_map[IO]; gpio::fast_write_pin(pp.port, pp.pin, static_cast(V)); } -static inline auto fast_read_pin_wrapper(pin_size_t IO) -> bool { +FORCE_INLINE static auto fast_read_pin_wrapper(pin_size_t IO) -> bool { const PortPinPair& pp = port_pin_map[IO]; return gpio::fast_read_pin(pp.port, pp.pin); } -static inline void fast_toggle_pin_wrapper(pin_size_t IO) { +FORCE_INLINE static void fast_toggle_pin_wrapper(pin_size_t IO) { const PortPinPair& pp = port_pin_map[IO]; gpio::fast_toggle_pin(pp.port, pp.pin); } From 94e2558e6c34abdb8ef3d64a3d7b1580b634a22f Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 9 May 2025 00:31:31 +0000 Subject: [PATCH 017/102] [cron] Bump distribution date (2025-05-09) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index e21fc7c479..e9be5139e7 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-05-08" +//#define STRING_DISTRIBUTION_DATE "2025-05-09" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 9eb50bff90..336dd6bff4 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-05-08" + #define STRING_DISTRIBUTION_DATE "2025-05-09" #endif /** From b22df8b189c85302040f932df6175e01277af7da Mon Sep 17 00:00:00 2001 From: B Date: Fri, 9 May 2025 09:58:25 -0700 Subject: [PATCH 018/102] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Fix?= =?UTF-8?q?=20GD32=20EEPROM=20timings=20(#27846)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../HAL/GD32_MFL/eeprom/eeprom_bl24cxx.cpp | 2 +- Marlin/src/libs/BL24CXX.cpp | 87 +++++++++++++++++-- 2 files changed, 79 insertions(+), 10 deletions(-) diff --git a/Marlin/src/HAL/GD32_MFL/eeprom/eeprom_bl24cxx.cpp b/Marlin/src/HAL/GD32_MFL/eeprom/eeprom_bl24cxx.cpp index 9c44933fe3..1053c80a41 100644 --- a/Marlin/src/HAL/GD32_MFL/eeprom/eeprom_bl24cxx.cpp +++ b/Marlin/src/HAL/GD32_MFL/eeprom/eeprom_bl24cxx.cpp @@ -62,7 +62,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui // so only write bytes that have changed! if (v != eeprom_read_byte(p)) { eeprom_write_byte(p, v); - if (++written & 0x7F) delay(4); else safe_delay(4); + if (++written & 0x7F) delay(2); else safe_delay(2); if (eeprom_read_byte(p) != v) { SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); return true; diff --git a/Marlin/src/libs/BL24CXX.cpp b/Marlin/src/libs/BL24CXX.cpp index 43c68887b1..091b233549 100644 --- a/Marlin/src/libs/BL24CXX.cpp +++ b/Marlin/src/libs/BL24CXX.cpp @@ -44,6 +44,10 @@ #define EEPROM_DEVICE_ADDRESS (0x50 << 1) #endif +#ifdef ARDUINO_ARCH_MFL + #define EXTRA_EEPROM_DELAY +#endif + // IO direction setting #ifdef __STM32F1__ #define SDA_IN() do{ PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH &= 0XFFFF0FFF; PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH |= 8 << 12; }while(0) @@ -60,6 +64,14 @@ #define IIC_SDA_1() WRITE(IIC_EEPROM_SDA, HIGH) #define READ_SDA() READ(IIC_EEPROM_SDA) +#ifdef EXTRA_EEPROM_DELAY + #define EXTRA_DELAY 1 + #define EXTRA_DELAY_LOW 4 // SCL low period (tLOW) +#else + #define EXTRA_DELAY 0 + #define EXTRA_DELAY_LOW 0 +#endif + // // Simple IIC interface via libmaple // @@ -70,28 +82,51 @@ void IIC::init() { SET_OUTPUT(IIC_EEPROM_SCL); IIC_SCL_1(); IIC_SDA_1(); + + #ifdef EXTRA_EEPROM_DELAY + delay_us(EXTRA_DELAY); // Ensure bus free time + #endif } // Generate IIC start signal void IIC::start() { SDA_OUT(); // SDA line output IIC_SDA_1(); + + #ifdef EXTRA_EEPROM_DELAY + delay_us(4 + EXTRA_DELAY); // Setup time before SCL high + #endif + IIC_SCL_1(); - delay_us(4); + delay_us(4 + EXTRA_DELAY); IIC_SDA_0(); // START:when CLK is high, DATA change from high to low - delay_us(4); + delay_us(4 + EXTRA_DELAY); IIC_SCL_0(); // Clamp the I2C bus, ready to send or receive data + + #ifdef EXTRA_EEPROM_DELAY + delay_us(EXTRA_DELAY_LOW); // Ensure SCL low period + #endif } // Generate IIC stop signal void IIC::stop() { SDA_OUT(); // SDA line output IIC_SCL_0(); + + #ifdef EXTRA_EEPROM_DELAY + delay_us(EXTRA_DELAY_LOW); // Ensure SCL low period + #endif + IIC_SDA_0(); // STOP:when CLK is high DATA change from low to high - delay_us(4); + delay_us(4 + EXTRA_DELAY); IIC_SCL_1(); + + #ifdef EXTRA_EEPROM_DELAY + delay_us(4 + EXTRA_DELAY); // Setup time with SCL high + #endif + IIC_SDA_1(); // Send I2C bus end signal - delay_us(4); + delay_us(4 + EXTRA_DELAY); } // Wait for the response signal to arrive @@ -100,8 +135,9 @@ void IIC::stop() { uint8_t IIC::wait_ack() { uint8_t ucErrTime = 0; SDA_IN(); // SDA is set as input - IIC_SDA_1(); delay_us(1); - IIC_SCL_1(); delay_us(1); + IIC_SDA_1(); delay_us(1 + EXTRA_DELAY); + IIC_SCL_1(); delay_us(1 + EXTRA_DELAY); + while (READ_SDA()) { if (++ucErrTime > 250) { stop(); @@ -109,29 +145,52 @@ uint8_t IIC::wait_ack() { } } IIC_SCL_0(); // Clock output 0 + + #ifdef EXTRA_EEPROM_DELAY + delay_us(EXTRA_DELAY); // Hold time after SCL falls + #endif + return 0; } // Generate ACK response void IIC::ack() { IIC_SCL_0(); + + #ifdef EXTRA_EEPROM_DELAY + delay_us(EXTRA_DELAY_LOW); // Ensure SCL low period + #endif + SDA_OUT(); IIC_SDA_0(); delay_us(2); IIC_SCL_1(); - delay_us(2); + delay_us(2 + EXTRA_DELAY); IIC_SCL_0(); + + #ifdef EXTRA_EEPROM_DELAY + delay_us(EXTRA_DELAY); // Data hold time + #endif } // No ACK response void IIC::nAck() { IIC_SCL_0(); + + #ifdef EXTRA_EEPROM_DELAY + delay_us(EXTRA_DELAY_LOW); // Ensure SCL low period + #endif + SDA_OUT(); IIC_SDA_1(); delay_us(2); IIC_SCL_1(); - delay_us(2); + delay_us(2 + EXTRA_DELAY); IIC_SCL_0(); + + #ifdef EXTRA_EEPROM_DELAY + delay_us(EXTRA_DELAY); // Data hold time + #endif } // Send one IIC byte @@ -141,13 +200,18 @@ void IIC::nAck() { void IIC::send_byte(uint8_t txd) { SDA_OUT(); IIC_SCL_0(); // Pull down the clock to start data transmission + + #ifdef EXTRA_EEPROM_DELAY + delay_us(EXTRA_DELAY_LOW); // Ensure SCL low period + #endif + for (uint8_t t = 0; t < 8; ++t) { // IIC_SDA = (txd & 0x80) >> 7; if (txd & 0x80) IIC_SDA_1(); else IIC_SDA_0(); txd <<= 1; delay_us(2); // All three delays are necessary for TEA5767 IIC_SCL_1(); - delay_us(2); + delay_us(2 + EXTRA_DELAY); IIC_SCL_0(); delay_us(2); } @@ -161,6 +225,11 @@ uint8_t IIC::read_byte(unsigned char ack_chr) { IIC_SCL_0(); delay_us(2); IIC_SCL_1(); + + #ifdef EXTRA_EEPROM_DELAY + delay_us(EXTRA_DELAY); // Delay before reading to allow EEPROM to output data + #endif + receive <<= 1; if (READ_SDA()) receive++; delay_us(1); From 6cda10de0fa8224c30f86baff50be3b14a1e9e1e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 9 May 2025 16:21:29 -0500 Subject: [PATCH 019/102] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Rel?= =?UTF-8?q?ocate=20some=20factory=20reset,=20etc.?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/marlinui.cpp | 22 +++++ Marlin/src/lcd/marlinui.h | 1 + Marlin/src/module/endstops.cpp | 35 +++++++ Marlin/src/module/endstops.h | 5 + Marlin/src/module/settings.cpp | 148 ++---------------------------- Marlin/src/module/temperature.cpp | 91 +++++++++++++++++- Marlin/src/module/temperature.h | 10 +- 7 files changed, 164 insertions(+), 148 deletions(-) diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 2b730581c8..28697affab 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -140,6 +140,28 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; preheat_t MarlinUI::material_preset[PREHEAT_COUNT]; // Initialized by settings.load + void MarlinUI::reset_material_presets() { + #define _PITEM(N,T) PREHEAT_##N##_##T, + #if HAS_HOTEND + constexpr uint16_t hpre[] = { REPEAT2_S(1, INCREMENT(PREHEAT_COUNT), _PITEM, TEMP_HOTEND) }; + #endif + #if HAS_HEATED_BED + constexpr uint16_t bpre[] = { REPEAT2_S(1, INCREMENT(PREHEAT_COUNT), _PITEM, TEMP_BED) }; + #endif + #if HAS_HEATED_CHAMBER + constexpr uint16_t cpre[] = { REPEAT2_S(1, INCREMENT(PREHEAT_COUNT), _PITEM, TEMP_CHAMBER) }; + #endif + #if HAS_FAN + constexpr uint8_t fpre[] = { REPEAT2_S(1, INCREMENT(PREHEAT_COUNT), _PITEM, FAN_SPEED) }; + #endif + for (uint8_t i = 0; i < PREHEAT_COUNT; ++i) { + TERN_(HAS_HOTEND, material_preset[i].hotend_temp = hpre[i]); + TERN_(HAS_HEATED_BED, material_preset[i].bed_temp = bpre[i]); + TERN_(HAS_HEATED_CHAMBER, material_preset[i].chamber_temp = cpre[i]); + TERN_(HAS_FAN, material_preset[i].fan_speed = fpre[i]); + } + } + FSTR_P MarlinUI::get_preheat_label(const uint8_t m) { #define _PDEF(N) static PGMSTR(preheat_##N##_label, PREHEAT_##N##_LABEL); #define _PLBL(N) preheat_##N##_label, diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index a610796ebc..578d143d96 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -648,6 +648,7 @@ public: #if HAS_PREHEAT enum PreheatTarget : uint8_t { PT_HOTEND, PT_BED, PT_FAN, PT_CHAMBER, PT_ALL = 0xFF }; static preheat_t material_preset[PREHEAT_COUNT]; + static void reset_material_presets(); static FSTR_P get_preheat_label(const uint8_t m); static void apply_preheat(const uint8_t m, const uint8_t pmask, const uint8_t e=active_extruder); static void preheat_set_fan(const uint8_t m) { TERN_(HAS_FAN, apply_preheat(m, _BV(PT_FAN))); } diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 7b8cb41505..b0ad431476 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -251,6 +251,41 @@ void Endstops::init() { } // Endstops::init +void Endstops::factory_reset() { + #if ENABLED(X_DUAL_ENDSTOPS) + #ifndef X2_ENDSTOP_ADJUSTMENT + #define X2_ENDSTOP_ADJUSTMENT 0 + #endif + endstops.x2_endstop_adj = X2_ENDSTOP_ADJUSTMENT; + #endif + + #if ENABLED(Y_DUAL_ENDSTOPS) + #ifndef Y2_ENDSTOP_ADJUSTMENT + #define Y2_ENDSTOP_ADJUSTMENT 0 + #endif + endstops.y2_endstop_adj = Y2_ENDSTOP_ADJUSTMENT; + #endif + + #if ENABLED(Z_MULTI_ENDSTOPS) + #ifndef Z2_ENDSTOP_ADJUSTMENT + #define Z2_ENDSTOP_ADJUSTMENT 0 + #endif + endstops.z2_endstop_adj = Z2_ENDSTOP_ADJUSTMENT; + #if NUM_Z_STEPPERS >= 3 + #ifndef Z3_ENDSTOP_ADJUSTMENT + #define Z3_ENDSTOP_ADJUSTMENT 0 + #endif + endstops.z3_endstop_adj = Z3_ENDSTOP_ADJUSTMENT; + #endif + #if NUM_Z_STEPPERS >= 4 + #ifndef Z4_ENDSTOP_ADJUSTMENT + #define Z4_ENDSTOP_ADJUSTMENT 0 + #endif + endstops.z4_endstop_adj = Z4_ENDSTOP_ADJUSTMENT; + #endif + #endif +} + // Called at ~1kHz from Temperature ISR: Poll endstop state if required void Endstops::poll() { diff --git a/Marlin/src/module/endstops.h b/Marlin/src/module/endstops.h index 1ef217b64a..40975632ff 100644 --- a/Marlin/src/module/endstops.h +++ b/Marlin/src/module/endstops.h @@ -172,6 +172,11 @@ class Endstops { */ static void init(); + /** + * Saved settings initialization + */ + static void factory_reset(); + /** * Are endstops or the Z min probe or the CALIBRATION probe set to abort the move? */ diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 8c99c54323..d325ef95d9 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -3510,151 +3510,17 @@ void MarlinSettings::reset() { // // Endstop Adjustments // - - #if ENABLED(X_DUAL_ENDSTOPS) - #ifndef X2_ENDSTOP_ADJUSTMENT - #define X2_ENDSTOP_ADJUSTMENT 0 - #endif - endstops.x2_endstop_adj = X2_ENDSTOP_ADJUSTMENT; - #endif - - #if ENABLED(Y_DUAL_ENDSTOPS) - #ifndef Y2_ENDSTOP_ADJUSTMENT - #define Y2_ENDSTOP_ADJUSTMENT 0 - #endif - endstops.y2_endstop_adj = Y2_ENDSTOP_ADJUSTMENT; - #endif - - #if ENABLED(Z_MULTI_ENDSTOPS) - #ifndef Z2_ENDSTOP_ADJUSTMENT - #define Z2_ENDSTOP_ADJUSTMENT 0 - #endif - endstops.z2_endstop_adj = Z2_ENDSTOP_ADJUSTMENT; - #if NUM_Z_STEPPERS >= 3 - #ifndef Z3_ENDSTOP_ADJUSTMENT - #define Z3_ENDSTOP_ADJUSTMENT 0 - #endif - endstops.z3_endstop_adj = Z3_ENDSTOP_ADJUSTMENT; - #endif - #if NUM_Z_STEPPERS >= 4 - #ifndef Z4_ENDSTOP_ADJUSTMENT - #define Z4_ENDSTOP_ADJUSTMENT 0 - #endif - endstops.z4_endstop_adj = Z4_ENDSTOP_ADJUSTMENT; - #endif - #endif + endstops.factory_reset(); // - // Preheat parameters + // Material Presets // - #if HAS_PREHEAT - #define _PITEM(N,T) PREHEAT_##N##_##T, - #if HAS_HOTEND - constexpr uint16_t hpre[] = { REPEAT2_S(1, INCREMENT(PREHEAT_COUNT), _PITEM, TEMP_HOTEND) }; - #endif - #if HAS_HEATED_BED - constexpr uint16_t bpre[] = { REPEAT2_S(1, INCREMENT(PREHEAT_COUNT), _PITEM, TEMP_BED) }; - #endif - #if HAS_HEATED_CHAMBER - constexpr uint16_t cpre[] = { REPEAT2_S(1, INCREMENT(PREHEAT_COUNT), _PITEM, TEMP_CHAMBER) }; - #endif - #if HAS_FAN - constexpr uint8_t fpre[] = { REPEAT2_S(1, INCREMENT(PREHEAT_COUNT), _PITEM, FAN_SPEED) }; - #endif - for (uint8_t i = 0; i < PREHEAT_COUNT; ++i) { - TERN_(HAS_HOTEND, ui.material_preset[i].hotend_temp = hpre[i]); - TERN_(HAS_HEATED_BED, ui.material_preset[i].bed_temp = bpre[i]); - TERN_(HAS_HEATED_CHAMBER, ui.material_preset[i].chamber_temp = cpre[i]); - TERN_(HAS_FAN, ui.material_preset[i].fan_speed = fpre[i]); - } - #endif + TERN_(HAS_PREHEAT, ui.reset_material_presets()); // - // Hotend PID + // Temperature Manager // - - #if ENABLED(PIDTEMP) - #if ENABLED(PID_PARAMS_PER_HOTEND) - constexpr float defKp[] = - #ifdef DEFAULT_Kp_LIST - DEFAULT_Kp_LIST - #else - ARRAY_BY_HOTENDS1(DEFAULT_Kp) - #endif - , defKi[] = - #ifdef DEFAULT_Ki_LIST - DEFAULT_Ki_LIST - #else - ARRAY_BY_HOTENDS1(DEFAULT_Ki) - #endif - , defKd[] = - #ifdef DEFAULT_Kd_LIST - DEFAULT_Kd_LIST - #else - ARRAY_BY_HOTENDS1(DEFAULT_Kd) - #endif - ; - static_assert(WITHIN(COUNT(defKp), 1, HOTENDS), "DEFAULT_Kp_LIST must have between 1 and HOTENDS items."); - static_assert(WITHIN(COUNT(defKi), 1, HOTENDS), "DEFAULT_Ki_LIST must have between 1 and HOTENDS items."); - static_assert(WITHIN(COUNT(defKd), 1, HOTENDS), "DEFAULT_Kd_LIST must have between 1 and HOTENDS items."); - #if ENABLED(PID_EXTRUSION_SCALING) - constexpr float defKc[] = - #ifdef DEFAULT_Kc_LIST - DEFAULT_Kc_LIST - #else - ARRAY_BY_HOTENDS1(DEFAULT_Kc) - #endif - ; - static_assert(WITHIN(COUNT(defKc), 1, HOTENDS), "DEFAULT_Kc_LIST must have between 1 and HOTENDS items."); - #endif - #if ENABLED(PID_FAN_SCALING) - constexpr float defKf[] = - #ifdef DEFAULT_Kf_LIST - DEFAULT_Kf_LIST - #else - ARRAY_BY_HOTENDS1(DEFAULT_Kf) - #endif - ; - static_assert(WITHIN(COUNT(defKf), 1, HOTENDS), "DEFAULT_Kf_LIST must have between 1 and HOTENDS items."); - #endif - #define PID_DEFAULT(N,E) def##N[E] - #else - #define PID_DEFAULT(N,E) DEFAULT_##N - #endif - HOTEND_LOOP() { - thermalManager.temp_hotend[e].pid.set( - PID_DEFAULT(Kp, ALIM(e, defKp)), - PID_DEFAULT(Ki, ALIM(e, defKi)), - PID_DEFAULT(Kd, ALIM(e, defKd)) - OPTARG(PID_EXTRUSION_SCALING, PID_DEFAULT(Kc, ALIM(e, defKc))) - OPTARG(PID_FAN_SCALING, PID_DEFAULT(Kf, ALIM(e, defKf))) - ); - } - #endif - - // - // PID Extrusion Scaling - // - TERN_(PID_EXTRUSION_SCALING, thermalManager.lpq_len = 20); // Default last-position-queue size - - // - // Heated Bed PID - // - #if ENABLED(PIDTEMPBED) - thermalManager.temp_bed.pid.set(DEFAULT_bedKp, DEFAULT_bedKi, DEFAULT_bedKd); - #endif - - // - // Heated Chamber PID - // - #if ENABLED(PIDTEMPCHAMBER) - thermalManager.temp_chamber.pid.set(DEFAULT_chamberKp, DEFAULT_chamberKi, DEFAULT_chamberKd); - #endif - - // - // User-Defined Thermistors - // - TERN_(HAS_USER_THERMISTORS, thermalManager.reset_user_thermistors()); + thermalManager.factory_reset(); // // Power Monitor @@ -3750,6 +3616,7 @@ void MarlinSettings::reset() { // #if ENABLED(LIN_ADVANCE) #if ENABLED(DISTINCT_E_FACTORS) + constexpr float linAdvanceK[] = ADVANCE_K; EXTRUDER_LOOP() { const float a = linAdvanceK[_MAX(uint8_t(e), COUNT(linAdvanceK) - 1)]; @@ -3767,8 +3634,9 @@ void MarlinSettings::reset() { #else stepper.set_advance_tau(ADVANCE_TAU); #endif + #endif - #endif + #endif // LIN_ADVANCE // // Motor Current PWM diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 0ef0a2f961..30690345a5 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -711,6 +711,93 @@ volatile bool Temperature::raw_temps_ready = false; #endif +void Temperature::factory_reset() { + // + // Hotend PID + // + #if ENABLED(PIDTEMP) + #if ENABLED(PID_PARAMS_PER_HOTEND) + constexpr float defKp[] = + #ifdef DEFAULT_Kp_LIST + DEFAULT_Kp_LIST + #else + ARRAY_BY_HOTENDS1(DEFAULT_Kp) + #endif + , defKi[] = + #ifdef DEFAULT_Ki_LIST + DEFAULT_Ki_LIST + #else + ARRAY_BY_HOTENDS1(DEFAULT_Ki) + #endif + , defKd[] = + #ifdef DEFAULT_Kd_LIST + DEFAULT_Kd_LIST + #else + ARRAY_BY_HOTENDS1(DEFAULT_Kd) + #endif + ; + static_assert(WITHIN(COUNT(defKp), 1, HOTENDS), "DEFAULT_Kp_LIST must have between 1 and HOTENDS items."); + static_assert(WITHIN(COUNT(defKi), 1, HOTENDS), "DEFAULT_Ki_LIST must have between 1 and HOTENDS items."); + static_assert(WITHIN(COUNT(defKd), 1, HOTENDS), "DEFAULT_Kd_LIST must have between 1 and HOTENDS items."); + #if ENABLED(PID_EXTRUSION_SCALING) + constexpr float defKc[] = + #ifdef DEFAULT_Kc_LIST + DEFAULT_Kc_LIST + #else + ARRAY_BY_HOTENDS1(DEFAULT_Kc) + #endif + ; + static_assert(WITHIN(COUNT(defKc), 1, HOTENDS), "DEFAULT_Kc_LIST must have between 1 and HOTENDS items."); + #endif + #if ENABLED(PID_FAN_SCALING) + constexpr float defKf[] = + #ifdef DEFAULT_Kf_LIST + DEFAULT_Kf_LIST + #else + ARRAY_BY_HOTENDS1(DEFAULT_Kf) + #endif + ; + static_assert(WITHIN(COUNT(defKf), 1, HOTENDS), "DEFAULT_Kf_LIST must have between 1 and HOTENDS items."); + #endif + #define PID_DEFAULT(N,E) def##N[E] + #else + #define PID_DEFAULT(N,E) DEFAULT_##N + #endif + HOTEND_LOOP() { + temp_hotend[e].pid.set( + PID_DEFAULT(Kp, ALIM(e, defKp)), + PID_DEFAULT(Ki, ALIM(e, defKi)), + PID_DEFAULT(Kd, ALIM(e, defKd)) + OPTARG(PID_EXTRUSION_SCALING, PID_DEFAULT(Kc, ALIM(e, defKc))) + OPTARG(PID_FAN_SCALING, PID_DEFAULT(Kf, ALIM(e, defKf))) + ); + } + #endif // PIDTEMP + + // + // PID Extrusion Scaling + // + TERN_(PID_EXTRUSION_SCALING, lpq_len = 20); // Default last-position-queue size + + // + // Heated Bed PID + // + #if ENABLED(PIDTEMPBED) + temp_bed.pid.set(DEFAULT_bedKp, DEFAULT_bedKi, DEFAULT_bedKd); + #endif + + // + // Heated Chamber PID + // + #if ENABLED(PIDTEMPCHAMBER) + temp_chamber.pid.set(DEFAULT_chamberKp, DEFAULT_chamberKi, DEFAULT_chamberKd); + #endif + + // User-Defined Thermistors + TERN_(HAS_USER_THERMISTORS, reset_user_thermistors()); + +} // factory_reset + #if HAS_PID_HEATING inline void say_default_() { SERIAL_ECHOPGM("#define DEFAULT_"); } @@ -939,9 +1026,9 @@ volatile bool Temperature::raw_temps_ready = false; auto _set_hotend_pid = [](const uint8_t tool, const raw_pid_t &in_pid) { #if ENABLED(PIDTEMP) #if ENABLED(PID_PARAMS_PER_HOTEND) - thermalManager.temp_hotend[tool].pid.set(in_pid); + temp_hotend[tool].pid.set(in_pid); #else - HOTEND_LOOP() thermalManager.temp_hotend[e].pid.set(in_pid); + HOTEND_LOOP() temp_hotend[e].pid.set(in_pid); #endif updatePID(); #endif diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index 77c16bba0a..c96d9aba74 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -809,16 +809,14 @@ class Temperature { #endif public: - /** - * Instance Methods - */ - - void init(); - /** * Static (class) methods */ + static void init(); + + static void factory_reset(); + #if HAS_USER_THERMISTORS static user_thermistor_t user_thermistor[USER_THERMISTORS]; static void M305_report(const uint8_t t_index, const bool forReplay=true); From fad7bc66e9e00f51b89fcc5a3d916e96addba8f2 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 9 May 2025 16:23:14 -0500 Subject: [PATCH 020/102] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Use?= =?UTF-8?q?=20'DISTINCT=5FE=5FFACTORS'?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/feature/advance/M900.cpp | 30 ++++++++++--------- Marlin/src/inc/Conditionals-1-axes.h | 2 ++ Marlin/src/inc/SanityCheck.h | 2 +- .../generic/max_acceleration_screen.cpp | 4 +-- .../generic/max_velocity_screen.cpp | 2 +- Marlin/src/lcd/menu/menu_advanced.cpp | 8 ++--- Marlin/src/lcd/menu/menu_tune.cpp | 4 +-- 7 files changed, 28 insertions(+), 24 deletions(-) diff --git a/Marlin/src/gcode/feature/advance/M900.cpp b/Marlin/src/gcode/feature/advance/M900.cpp index 51a40f934e..dc59b5bc90 100644 --- a/Marlin/src/gcode/feature/advance/M900.cpp +++ b/Marlin/src/gcode/feature/advance/M900.cpp @@ -36,9 +36,11 @@ /** * M900: Get or Set Linear Advance K-factor * T Which tool to address - * K Set current advance K factor (Slot 0). - * L Set secondary advance K factor (Slot 1). Requires ADVANCE_K_EXTRA. - * S<0/1> Activate slot 0 or 1. Requires ADVANCE_K_EXTRA. + * K Set current advance K factor (aka Slot 0). + * + * With ADVANCE_K_EXTRA: + * S<0/1> Activate slot 0 or 1. + * L Set secondary advance K factor (Slot 1). */ void GcodeSuite::M900() { @@ -72,31 +74,31 @@ void GcodeSuite::M900() { float &lref = other_extruder_advance_K[E_INDEX_N(tool_index)]; - const bool old_slot = TEST(lin_adv_slot, tool_index), // The tool's current slot (0 or 1) - new_slot = parser.boolval('S', old_slot); // The passed slot (default = current) + const bool old_slot = TEST(lin_adv_slot, tool_index), // Each tool uses 1 bit to store its current slot (0 or 1) + new_slot = parser.boolval('S', old_slot); // The new slot (0 or 1) to set for the tool (default = no change) // If a new slot is being selected swap the current and // saved K values. Do here so K/L will apply correctly. if (new_slot != old_slot) { // Not the same slot? SET_BIT_TO(lin_adv_slot, tool_index, new_slot); // Update the slot for the tool - newK = lref; // Get new K value from backup - lref = oldK; // Save K to backup + newK = lref; // Get the backup K value (to apply below) + lref = oldK; // Back up the active K value } // Set the main K value. Apply if the main slot is active. if (parser.seenval('K')) { const float K = parser.value_float(); if (!WITHIN(K, 0, 10)) echo_value_oor('K'); - else if (new_slot) lref = K; // S1 Knn - else newK = K; // S0 Knn + else if (new_slot) lref = K; // S1 Knn (set main K in its backup slot) + else newK = K; // S0 Knn (use main K now) } // Set the extra K value. Apply if the extra slot is active. if (parser.seenval('L')) { const float L = parser.value_float(); if (!WITHIN(L, 0, 10)) echo_value_oor('L'); - else if (!new_slot) lref = L; // S0 Lnn - else newK = L; // S1 Lnn + else if (!new_slot) lref = L; // S0 Lnn (set extra K in its backup slot) + else newK = L; // S1 Lnn (use extra K now) } #else @@ -133,7 +135,7 @@ void GcodeSuite::M900() { #if ENABLED(ADVANCE_K_EXTRA) - #if DISTINCT_E < 2 + #if DISABLED(DISTINCT_E_FACTORS) SERIAL_ECHOLNPGM("Advance S", new_slot, " K", kref, "(S", !new_slot, " K", lref, ")"); #else EXTRUDER_LOOP() { @@ -146,7 +148,7 @@ void GcodeSuite::M900() { #else // !ADVANCE_K_EXTRA SERIAL_ECHO_START(); - #if DISTINCT_E < 2 + #if DISABLED(DISTINCT_E_FACTORS) SERIAL_ECHOPGM("Advance K=", planner.extruder_advance_K[0]); #if ENABLED(SMOOTH_LIN_ADVANCE) SERIAL_ECHOPGM(" TAU=", stepper.get_advance_tau()); @@ -172,7 +174,7 @@ void GcodeSuite::M900_report(const bool forReplay/*=true*/) { TERN_(MARLIN_SMALL_BUILD, return); report_heading(forReplay, F(STR_LINEAR_ADVANCE)); - #if DISTINCT_E < 2 + #if DISABLED(DISTINCT_E_FACTORS) report_echo_start(forReplay); SERIAL_ECHOPGM(" M900 K", planner.extruder_advance_K[0]); #if ENABLED(SMOOTH_LIN_ADVANCE) diff --git a/Marlin/src/inc/Conditionals-1-axes.h b/Marlin/src/inc/Conditionals-1-axes.h index 8e84d7d4d4..49b236d80e 100644 --- a/Marlin/src/inc/Conditionals-1-axes.h +++ b/Marlin/src/inc/Conditionals-1-axes.h @@ -544,6 +544,8 @@ #endif // Helper macros for extruder and hotend arrays +#define _DISTINCT_E_LOOP(E) for (int8_t E = 0; E < DISTINCT_E; E++) +#define DISTINCT_E_LOOP() _DISTINCT_E_LOOP(e) #define _EXTRUDER_LOOP(E) for (int8_t E = 0; E < EXTRUDERS; E++) #define EXTRUDER_LOOP() _EXTRUDER_LOOP(e) #define _HOTEND_LOOP(H) for (int8_t H = 0; H < HOTENDS; H++) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index df86cea522..ff75824673 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -846,7 +846,7 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L * Linear Advance 1.5 - Check K value range */ #if ENABLED(LIN_ADVANCE) - #if DISTINCT_E > 1 + #if ENABLED(DISTINCT_E_FACTORS) constexpr float lak[] = ADVANCE_K; static_assert(COUNT(lak) <= DISTINCT_E, "The ADVANCE_K array has too many elements (i.e., more than " STRINGIFY(DISTINCT_E) ")."); #define _LIN_ASSERT(N) static_assert(N >= COUNT(lak) || WITHIN(lak[N], 0, 10), "ADVANCE_K values must be from 0 to 10 (Changed in LIN_ADVANCE v1.5, Marlin 1.1.9)."); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_acceleration_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_acceleration_screen.cpp index 492b908776..e4178e6e2e 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_acceleration_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_acceleration_screen.cpp @@ -39,7 +39,7 @@ void MaxAccelerationScreen::onRedraw(draw_mode_t what) { w.color(z_axis) .adjuster( 6, GET_TEXT_F(MSG_AMAX_Z), getAxisMaxAcceleration_mm_s2(Z) ); #if DISTINCT_E == 1 w.color(e_axis).adjuster( 8, GET_TEXT_F(MSG_AMAX_E), getAxisMaxAcceleration_mm_s2(E0) ); - #elif DISTINCT_E > 1 + #elif ENABLED(DISTINCT_E_FACTORS) w.heading(GET_TEXT_F(MSG_AMAX_E)); w.color(e_axis).adjuster( 8, F(STR_E0), getAxisMaxAcceleration_mm_s2(E0) ); w.color(e_axis).adjuster(10, F(STR_E1), getAxisMaxAcceleration_mm_s2(E1) ); @@ -64,7 +64,7 @@ bool MaxAccelerationScreen::onTouchHeld(uint8_t tag) { case 7: UI_INCREMENT(AxisMaxAcceleration_mm_s2, Z ); break; case 8: UI_DECREMENT(AxisMaxAcceleration_mm_s2, E0); break; case 9: UI_INCREMENT(AxisMaxAcceleration_mm_s2, E0); break; - #if DISTINCT_E > 1 + #if ENABLED(DISTINCT_E_FACTORS) case 10: UI_DECREMENT(AxisMaxAcceleration_mm_s2, E1); break; case 11: UI_INCREMENT(AxisMaxAcceleration_mm_s2, E1); break; #if DISTINCT_E > 2 diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_velocity_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_velocity_screen.cpp index 666a7542cc..2a396205f1 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_velocity_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/max_velocity_screen.cpp @@ -66,7 +66,7 @@ bool MaxVelocityScreen::onTouchHeld(uint8_t tag) { #if DISTINCT_E case 8: UI_DECREMENT(AxisMaxFeedrate_mm_s, E0); break; case 9: UI_INCREMENT(AxisMaxFeedrate_mm_s, E0); break; - #if DISTINCT_E > 1 + #if ENABLED(DISTINCT_E_FACTORS) case 10: UI_DECREMENT(AxisMaxFeedrate_mm_s, E1); break; case 11: UI_INCREMENT(AxisMaxFeedrate_mm_s, E1); break; #if DISTINCT_E > 2 diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index 296312bb1f..92f2f51536 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -116,14 +116,14 @@ void menu_backlash(); BACK_ITEM(MSG_ADVANCED_SETTINGS); #if ENABLED(LIN_ADVANCE) - #if DISTINCT_E < 2 + #if DISABLED(DISTINCT_E_FACTORS) EDIT_ITEM(float42_52, MSG_ADVANCE_K, &planner.extruder_advance_K[0], 0, 10); #else EXTRUDER_LOOP() EDIT_ITEM_N(float42_52, e, MSG_ADVANCE_K_E, &planner.extruder_advance_K[e], 0, 10); #endif #if ENABLED(SMOOTH_LIN_ADVANCE) - #if DISTINCT_E < 2 + #if DISABLED(DISTINCT_E_FACTORS) editable.decimal = stepper.get_advance_tau(); EDIT_ITEM(float54, MSG_ADVANCE_TAU, &editable.decimal, 0.0f, 0.5f, []{ stepper.set_advance_tau(editable.decimal); }); #else @@ -749,14 +749,14 @@ void menu_advanced_settings() { #endif #if ENABLED(LIN_ADVANCE) && DISABLED(HAS_ADV_FILAMENT_MENU) - #if DISTINCT_E < 2 + #if DISABLED(DISTINCT_E_FACTORS) EDIT_ITEM(float42_52, MSG_ADVANCE_K, &planner.extruder_advance_K[0], 0, 10); #else EXTRUDER_LOOP() EDIT_ITEM_N(float42_52, e, MSG_ADVANCE_K_E, &planner.extruder_advance_K[e], 0, 10); #endif #if ENABLED(SMOOTH_LIN_ADVANCE) - #if DISTINCT_E < 2 + #if DISABLED(DISTINCT_E_FACTORS) editable.decimal = stepper.get_advance_tau(); EDIT_ITEM(float54, MSG_ADVANCE_TAU, &editable.decimal, 0.0f, 0.5f, []{ stepper.set_advance_tau(editable.decimal); }); #else diff --git a/Marlin/src/lcd/menu/menu_tune.cpp b/Marlin/src/lcd/menu/menu_tune.cpp index 51d877fc5c..d5cb805244 100644 --- a/Marlin/src/lcd/menu/menu_tune.cpp +++ b/Marlin/src/lcd/menu/menu_tune.cpp @@ -215,14 +215,14 @@ void menu_tune() { // Advance K: // #if ENABLED(LIN_ADVANCE) && DISABLED(SLIM_LCD_MENUS) - #if DISTINCT_E < 2 + #if DISABLED(DISTINCT_E_FACTORS) EDIT_ITEM(float42_52, MSG_ADVANCE_K, &planner.extruder_advance_K[0], 0, 10); #else EXTRUDER_LOOP() EDIT_ITEM_N(float42_52, e, MSG_ADVANCE_K_E, &planner.extruder_advance_K[e], 0, 10); #endif #if ENABLED(SMOOTH_LIN_ADVANCE) - #if DISTINCT_E < 2 + #if DISABLED(DISTINCT_E_FACTORS) editable.decimal = stepper.get_advance_tau(); EDIT_ITEM(float54, MSG_ADVANCE_TAU, &editable.decimal, 0.0f, 0.5f, []{ stepper.set_advance_tau(editable.decimal); }); #else From 54c1a1df4e79f1ac4e704f4311d706e934c3e9e7 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 9 May 2025 16:23:37 -0500 Subject: [PATCH 021/102] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Sin?= =?UTF-8?q?gleton=20notation?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/max7219.cpp | 2 +- Marlin/src/module/stepper.cpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/src/feature/max7219.cpp b/Marlin/src/feature/max7219.cpp index 5a61922c1d..16c7c4f55b 100644 --- a/Marlin/src/feature/max7219.cpp +++ b/Marlin/src/feature/max7219.cpp @@ -770,7 +770,7 @@ void Max7219::idle_tasks() { #ifdef MAX7219_DEBUG_SLOWDOWN static uint8_t last_slowdown_count = 0; - const uint8_t slowdown_count = Planner::slowdown_count; + const uint8_t slowdown_count = planner.slowdown_count; if (slowdown_count != last_slowdown_count) { mark16(MAX7219_DEBUG_SLOWDOWN, last_slowdown_count, slowdown_count, &row_change_mask); last_slowdown_count = slowdown_count; diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 1d02620e6f..e9f83aa532 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -2933,7 +2933,7 @@ hal_timer_t Stepper::block_phase_isr() { #endif // INPUT_SHAPING_E_SYNC float lookahead(uint32_t t) { - for (uint8_t i = 0; block_t *block = Planner::get_future_block(i); i++) { + for (uint8_t i = 0; block_t *block = planner.get_future_block(i); i++) { if (block->is_sync()) continue; if (t <= block->acceleration_time) { if (!block->use_advance_lead) return 0.0f; @@ -2969,7 +2969,7 @@ hal_timer_t Stepper::block_phase_isr() { float target_adv_steps = 0; if (current_block) { const uint32_t t = extruder_advance_tau_ticks[0] + curr_timer_tick; - target_adv_steps = lookahead(t) * Planner::extruder_advance_K[0]; + target_adv_steps = lookahead(t) * planner.extruder_advance_K[0]; } else { curr_step_rate = 0; From b12028f4dd0fecd99532175cd5a094b86cec8d54 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 9 May 2025 16:37:06 -0500 Subject: [PATCH 022/102] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20ALI?= =?UTF-8?q?M(I,ARR)=20macro?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/macros.h | 3 +++ Marlin/src/lcd/dogm/marlinui_DOGM.cpp | 2 +- Marlin/src/module/planner.h | 2 +- Marlin/src/module/settings.cpp | 7 ++----- Marlin/src/module/stepper.h | 3 +-- 5 files changed, 8 insertions(+), 9 deletions(-) diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index c75d684566..bef89040b3 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -547,6 +547,9 @@ #endif +// Limit an index to an array size +#define ALIM(I,ARR) _MIN(I, (signed)COUNT(ARR) - 1) + // Macros for adding #define INC_0 1 #define INC_1 2 diff --git a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp index 29316c553d..721389cb2c 100644 --- a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp +++ b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp @@ -197,7 +197,7 @@ bool MarlinUI::detected() { return true; } #endif { #if ENABLED(CUSTOM_BOOTSCREEN_ANIMATED_FRAME_TIME) - const uint8_t fr = _MIN(f, COUNT(custom_bootscreen_animation) - 1); + const uint8_t fr = ALIM(f, custom_bootscreen_animation); const millis_t frame_time = pgm_read_word(&custom_bootscreen_animation[fr].duration); #endif u8g.firstPage(); diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 73c77ee7f5..1c23f95cb1 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -359,7 +359,7 @@ typedef struct PlannerSettings { #if ENABLED(EDITABLE_STEPS_PER_UNIT) float axis_steps_per_mm[DISTINCT_AXES]; #else - #define _DLIM(I) _MIN(I, (signed)COUNT(_dasu) - 1) + #define _DLIM(I) ALIM(I, _dasu) #define _DASU(N) _dasu[_DLIM(N)], #define _EASU(N) _dasu[_DLIM(E_AXIS + N)], static constexpr float axis_steps_per_mm[DISTINCT_AXES] = { diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index d325ef95d9..1a46c6cc2a 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -200,9 +200,6 @@ typedef struct { bool NUM_AXIS_LIST_(X:1, Y:1, Z:1, I:1, J:1, K:1, U:1, V:1, #undef _EN_ITEM -// Limit an index to an array size -#define ALIM(I,ARR) _MIN(I, (signed)COUNT(ARR) - 1) - // Defaults for reset / fill in on load static const uint32_t _DMA[] PROGMEM = DEFAULT_MAX_ACCELERATION; static const feedRate_t _DMF[] PROGMEM = DEFAULT_MAX_FEEDRATE; @@ -3619,7 +3616,7 @@ void MarlinSettings::reset() { constexpr float linAdvanceK[] = ADVANCE_K; EXTRUDER_LOOP() { - const float a = linAdvanceK[_MAX(uint8_t(e), COUNT(linAdvanceK) - 1)]; + const float a = linAdvanceK[ALIM(e, linAdvanceK)]; planner.extruder_advance_K[e] = a; TERN_(ADVANCE_K_EXTRA, other_extruder_advance_K[e] = a); } @@ -3630,7 +3627,7 @@ void MarlinSettings::reset() { #if ENABLED(DISTINCT_E_FACTORS) constexpr float linAdvanceTau[] = ADVANCE_TAU; EXTRUDER_LOOP() - stepper.set_advance_tau(linAdvanceTau[_MAX(uint8_t(e), COUNT(linAdvanceTau) - 1)], e); + stepper.set_advance_tau(linAdvanceTau[ALIM(e, linAdvanceTau)], e); #else stepper.set_advance_tau(ADVANCE_TAU); #endif diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index 83ada9202e..1c06d83351 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -140,7 +140,6 @@ constexpr ena_mask_t enable_overlap[] = { #ifdef SHAPING_MAX_STEPRATE constexpr float max_step_rate = SHAPING_MAX_STEPRATE; #else - #define ISALIM(I, ARR) _MIN(I, COUNT(ARR) - 1) constexpr float _ISDASU[] = DEFAULT_AXIS_STEPS_PER_UNIT; constexpr feedRate_t _ISDMF[] = DEFAULT_MAX_FEEDRATE; constexpr float max_shaped_rate = TERN0(INPUT_SHAPING_X, _ISDMF[X_AXIS] * _ISDASU[X_AXIS]) + @@ -149,7 +148,7 @@ constexpr ena_mask_t enable_overlap[] = { #if defined(__AVR__) || !defined(ADAPTIVE_STEP_SMOOTHING) // min_step_isr_frequency is known at compile time on AVRs and any reduction in SRAM is welcome template constexpr float max_isr_rate() { - return _MAX(_ISDMF[ISALIM(INDEX - 1, _ISDMF)] * _ISDASU[ISALIM(INDEX - 1, _ISDASU)], max_isr_rate()); + return _MAX(_ISDMF[ALIM(INDEX - 1, _ISDMF)] * _ISDASU[ALIM(INDEX - 1, _ISDASU)], max_isr_rate()); } template<> constexpr float max_isr_rate<0>() { return TERN0(ADAPTIVE_STEP_SMOOTHING, min_step_isr_frequency); From 4de6d655acb80a3ea1d5b39607da5d4aed44c9ae Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 10 May 2025 00:30:25 +0000 Subject: [PATCH 023/102] [cron] Bump distribution date (2025-05-10) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index e9be5139e7..3c4711b876 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-05-09" +//#define STRING_DISTRIBUTION_DATE "2025-05-10" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 336dd6bff4..64a498179d 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-05-09" + #define STRING_DISTRIBUTION_DATE "2025-05-10" #endif /** From 12fdde24d89643969554222b0d94cf190cf1fe85 Mon Sep 17 00:00:00 2001 From: David Buezas Date: Tue, 13 May 2025 23:14:04 +0200 Subject: [PATCH 024/102] =?UTF-8?q?=E2=9A=A1=EF=B8=8F=20Optimize=20Smooth?= =?UTF-8?q?=20Linear=20Advance=20(via=20fixed-point)=20(#27818)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 6 +- Marlin/src/gcode/feature/advance/M900.cpp | 46 ++++--- Marlin/src/inc/SanityCheck.h | 2 +- Marlin/src/lcd/e3v2/jyersui/dwin.cpp | 25 ++-- Marlin/src/lcd/e3v2/proui/dwin.cpp | 7 +- Marlin/src/lcd/extui/ui_api.cpp | 4 +- Marlin/src/lcd/menu/menu_advanced.cpp | 28 +++-- Marlin/src/lcd/menu/menu_tune.cpp | 9 +- Marlin/src/lcd/sovol_rts/sovol_rts.cpp | 6 +- Marlin/src/lcd/tft/touch.cpp | 76 ++++++------ Marlin/src/module/planner.cpp | 13 +- Marlin/src/module/planner.h | 31 ++++- Marlin/src/module/settings.cpp | 44 ++++--- Marlin/src/module/stepper.cpp | 141 ++++++++++++---------- Marlin/src/module/stepper.h | 26 ++-- Marlin/src/module/tool_change.cpp | 2 +- 16 files changed, 265 insertions(+), 201 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index f31a284d81..762ae2aa81 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -2366,11 +2366,11 @@ * Higher k and higher XY acceleration may require larger ADVANCE_TAU to avoid skipping steps. */ #if ENABLED(DISTINCT_E_FACTORS) - #define ADVANCE_TAU { 0.01 } // (s) Smoothing time to reduce extruder acceleration, per extruder + #define ADVANCE_TAU { 0.02 } // (s) Smoothing time to reduce extruder acceleration, per extruder #else - #define ADVANCE_TAU 0.01 // (s) Smoothing time to reduce extruder acceleration + #define ADVANCE_TAU 0.02 // (s) Smoothing time to reduce extruder acceleration #endif - #define SMOOTH_LIN_ADV_HZ 5000 // (Hz) How often to update extruder speed + #define SMOOTH_LIN_ADV_HZ 1000 // (Hz) How often to update extruder speed #define INPUT_SHAPING_E_SYNC // Synchronize the extruder-shaped XY axes (to increase precision) #endif #endif diff --git a/Marlin/src/gcode/feature/advance/M900.cpp b/Marlin/src/gcode/feature/advance/M900.cpp index dc59b5bc90..7b92cad9d2 100644 --- a/Marlin/src/gcode/feature/advance/M900.cpp +++ b/Marlin/src/gcode/feature/advance/M900.cpp @@ -29,7 +29,7 @@ #include "../../../module/stepper.h" #if ENABLED(ADVANCE_K_EXTRA) - float other_extruder_advance_K[DISTINCT_E]; + float other_extruder_advance_K[EXTRUDERS]; uint8_t lin_adv_slot = 0; #endif @@ -62,17 +62,17 @@ void GcodeSuite::M900() { } #endif - float &kref = planner.extruder_advance_K[E_INDEX_N(tool_index)], newK = kref; - const float oldK = newK; + const float oldK = planner.get_advance_k(tool_index); + float newK = oldK; #if ENABLED(SMOOTH_LIN_ADVANCE) - const float oldU = stepper.get_advance_tau(E_INDEX_N(tool_index)); + const float oldU = stepper.get_advance_tau(tool_index); float newU = oldU; #endif #if ENABLED(ADVANCE_K_EXTRA) - float &lref = other_extruder_advance_K[E_INDEX_N(tool_index)]; + float &lref = other_extruder_advance_K[tool_index]; const bool old_slot = TEST(lin_adv_slot, tool_index), // Each tool uses 1 bit to store its current slot (0 or 1) new_slot = parser.boolval('S', old_slot); // The new slot (0 or 1) to set for the tool (default = no change) @@ -125,9 +125,9 @@ void GcodeSuite::M900() { if (newK != oldK || TERN0(SMOOTH_LIN_ADVANCE, newU != oldU)) { planner.synchronize(); - if (newK != oldK) kref = newK; + if (newK != oldK) planner.set_advance_k(newK, tool_index); #if ENABLED(SMOOTH_LIN_ADVANCE) - if (newU != oldU) stepper.set_advance_tau(newU); + if (newU != oldU) stepper.set_advance_tau(newU, tool_index); #endif } @@ -136,11 +136,11 @@ void GcodeSuite::M900() { #if ENABLED(ADVANCE_K_EXTRA) #if DISABLED(DISTINCT_E_FACTORS) - SERIAL_ECHOLNPGM("Advance S", new_slot, " K", kref, "(S", !new_slot, " K", lref, ")"); + SERIAL_ECHOLNPGM("Advance S", new_slot, " K", newK, "(S", !new_slot, " K", lref, ")"); #else EXTRUDER_LOOP() { const bool slot = TEST(lin_adv_slot, e); - SERIAL_ECHOLNPGM("Advance T", e, " S", slot, " K", planner.extruder_advance_K[e], + SERIAL_ECHOLNPGM("Advance T", e, " S", slot, " K", planner.get_advance_k(e), "(S", !slot, " K", other_extruder_advance_K[e], ")"); } #endif @@ -149,14 +149,14 @@ void GcodeSuite::M900() { SERIAL_ECHO_START(); #if DISABLED(DISTINCT_E_FACTORS) - SERIAL_ECHOPGM("Advance K=", planner.extruder_advance_K[0]); + SERIAL_ECHOPGM("Advance K=", planner.get_advance_k()); #if ENABLED(SMOOTH_LIN_ADVANCE) SERIAL_ECHOPGM(" TAU=", stepper.get_advance_tau()); #endif SERIAL_EOL(); #else SERIAL_ECHOPGM("Advance K"); - EXTRUDER_LOOP() SERIAL_ECHO(C(' '), C('0' + e), C(':'), planner.extruder_advance_K[e]); + EXTRUDER_LOOP() SERIAL_ECHO(C(' '), C('0' + e), C(':'), planner.get_advance_k(e)); SERIAL_EOL(); #if ENABLED(SMOOTH_LIN_ADVANCE) SERIAL_ECHOPGM("Advance TAU"); @@ -174,23 +174,21 @@ void GcodeSuite::M900_report(const bool forReplay/*=true*/) { TERN_(MARLIN_SMALL_BUILD, return); report_heading(forReplay, F(STR_LINEAR_ADVANCE)); - #if DISABLED(DISTINCT_E_FACTORS) + DISTINCT_E_LOOP() { report_echo_start(forReplay); - SERIAL_ECHOPGM(" M900 K", planner.extruder_advance_K[0]); + SERIAL_ECHOPGM( + #if ENABLED(DISTINCT_E_FACTORS) + " M900 T", e, " K" + #else + " M900 K" + #endif + ); + SERIAL_ECHO(planner.get_advance_k(e)); #if ENABLED(SMOOTH_LIN_ADVANCE) - SERIAL_ECHOPGM(" M900 U", stepper.get_advance_tau()); + SERIAL_ECHOPGM(" U", stepper.get_advance_tau(e)); #endif SERIAL_EOL(); - #else - EXTRUDER_LOOP() { - report_echo_start(forReplay); - SERIAL_ECHOPGM(" M900 T", e, " K", planner.extruder_advance_K[e]); - #if ENABLED(SMOOTH_LIN_ADVANCE) - SERIAL_ECHOPGM(" U", stepper.get_advance_tau(e)); - #endif - SERIAL_EOL(); - } - #endif + } } #endif // LIN_ADVANCE diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index ff75824673..97cc2ed198 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -3725,7 +3725,7 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i * Check per-axis initializers for errors */ -#define __PLUS_TEST(I,A) && (sanity_arr_##A[_MIN(I,signed(COUNT(sanity_arr_##A)-1))] > 0) +#define __PLUS_TEST(I,A) && (sanity_arr_##A[ALIM(I,sanity_arr_##A)] > 0) #define _PLUS_TEST(A) (1 REPEAT2(14,__PLUS_TEST,A)) #if HAS_MULTI_EXTRUDER #define _EXTRA_NOTE " (Did you forget to enable DISTINCT_E_FACTORS?)" diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp index aa087cefc4..f2c54da745 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -2398,10 +2398,13 @@ void JyersDWIN::menuItemHandler(const uint8_t menu, const uint8_t item, bool dra case MOTION_LA: if (draw) { drawMenuItem(row, ICON_MaxAccelerated, GET_TEXT_F(MSG_ADVANCE_K)); - drawFloat(planner.extruder_advance_K[0], row, false, 100); + drawFloat(planner.get_advance_k(), row, false, 100); } - else - modifyValue(planner.extruder_advance_K[0], 0, 10, 100); + else { + static float k = planner.get_advance_k(); + modifyValue(k, 0, 10, 100, []{ planner.set_advance_k(k); }); + } + break; #endif } @@ -2914,10 +2917,12 @@ void JyersDWIN::menuItemHandler(const uint8_t menu, const uint8_t item, bool dra case ADVANCED_LA: if (draw) { drawMenuItem(row, ICON_MaxAccelerated, GET_TEXT_F(MSG_ADVANCE_K)); - drawFloat(planner.extruder_advance_K[0], row, false, 100); + drawFloat(planner.get_advance_k(), row, false, 100); + } + else { + static float k = planner.get_advance_k(); + modifyValue(k, 0, 10, 100, []{ planner.set_advance_k(k); }); } - else - modifyValue(planner.extruder_advance_K[0], 0, 10, 100); break; #endif @@ -3925,10 +3930,12 @@ void JyersDWIN::menuItemHandler(const uint8_t menu, const uint8_t item, bool dra case TUNE_LA: if (draw) { drawMenuItem(row, ICON_MaxAccelerated, GET_TEXT_F(MSG_ADVANCE_K)); - drawFloat(planner.extruder_advance_K[0], row, false, 100); + drawFloat(planner.get_advance_k(), row, false, 100); + } + else { + static float k = planner.get_advance_k(); + modifyValue(k, 0, 10, 100, []{ planner.set_advance_k(k); }); } - else - modifyValue(planner.extruder_advance_K[0], 0, 10, 100); break; #endif diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index c3a69c1c66..7574439051 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -2686,7 +2686,8 @@ void applyMaxAccel() { planner.set_max_acceleration(hmiValue.axis, menuData.valu #endif #if ENABLED(LIN_ADVANCE) - void setLA_K() { setPFloatOnClick(0, 10, 3); } + void applyLA_K() { planner.set_advance_k(menuData.value / MINUNITMULT); } + void setLA_K() { setPFloatOnClick(0, 10, 3, applyLA_K); } #endif #if HAS_X_AXIS @@ -3545,7 +3546,7 @@ void drawTuneMenu() { EDIT_ITEM(ICON_JDmm, MSG_JUNCTION_DEVIATION, onDrawPFloat3Menu, setJDmm, &planner.junction_deviation_mm); #endif #if ENABLED(PROUI_ITEM_ADVK) - EDIT_ITEM(ICON_MaxAccelerated, MSG_ADVANCE_K, onDrawPFloat3Menu, setLA_K, &planner.extruder_advance_K[0]); + EDIT_ITEM(ICON_MaxAccelerated, MSG_ADVANCE_K, onDrawPFloat3Menu, setLA_K, &planner.get_advance_k()); #endif #if HAS_LOCKSCREEN MENU_ITEM(ICON_Lock, MSG_LOCKSCREEN, onDrawMenuItem, dwinLockScreen); @@ -3683,7 +3684,7 @@ void drawMotionMenu() { MENU_ITEM(ICON_Homing, MSG_HOMING_FEEDRATE, onDrawSubMenu, drawHomingFRMenu); #endif #if ENABLED(LIN_ADVANCE) - EDIT_ITEM(ICON_MaxAccelerated, MSG_ADVANCE_K, onDrawPFloat3Menu, setLA_K, &planner.extruder_advance_K[0]); + EDIT_ITEM(ICON_MaxAccelerated, MSG_ADVANCE_K, onDrawPFloat3Menu, setLA_K, &planner.get_advance_k()); #endif #if ENABLED(SHAPING_MENU) MENU_ITEM(ICON_InputShaping, MSG_INPUT_SHAPING, onDrawSubMenu, drawInputShaping_menu); diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index b3f4c39c24..5380b05596 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -643,12 +643,12 @@ namespace ExtUI { #if ENABLED(LIN_ADVANCE) float getLinearAdvance_mm_mm_s(const extruder_t extruder) { - return (extruder < EXTRUDERS) ? planner.extruder_advance_K[E_INDEX_N(extruder - E0)] : 0; + return (extruder < EXTRUDERS) ? planner.get_advance_k(E_INDEX_N(extruder - E0)) : 0; } void setLinearAdvance_mm_mm_s(const_float_t value, const extruder_t extruder) { if (extruder < EXTRUDERS) - planner.extruder_advance_K[E_INDEX_N(extruder - E0)] = constrain(value, 0, 10); + planner.set_advance_k(constrain(value, 0, 10), E_INDEX_N(extruder - E0)); } #endif diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index 92f2f51536..b15a21fc7b 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -117,10 +117,13 @@ void menu_backlash(); #if ENABLED(LIN_ADVANCE) #if DISABLED(DISTINCT_E_FACTORS) - EDIT_ITEM(float42_52, MSG_ADVANCE_K, &planner.extruder_advance_K[0], 0, 10); + editable.decimal = planner.get_advance_k(); + EDIT_ITEM(float42_52, MSG_ADVANCE_K, &editable.decimal, 0.0f, 10.0f, []{ planner.set_advance_k(editable.decimal); }); #else - EXTRUDER_LOOP() - EDIT_ITEM_N(float42_52, e, MSG_ADVANCE_K_E, &planner.extruder_advance_K[e], 0, 10); + EXTRUDER_LOOP() { + editable.decimal = planner.get_advance_k(e); + EDIT_ITEM_N(float42_52, e, MSG_ADVANCE_K_E, &editable.decimal, 0.0f, 10.0f, []{ planner.set_advance_k(editable.decimal, MenuItemBase::itemIndex); }); + } #endif #if ENABLED(SMOOTH_LIN_ADVANCE) #if DISABLED(DISTINCT_E_FACTORS) @@ -745,15 +748,19 @@ void menu_advanced_settings() { #endif #if HAS_ADV_FILAMENT_MENU - SUBMENU(MSG_FILAMENT, menu_advanced_filament); - #endif - #if ENABLED(LIN_ADVANCE) && DISABLED(HAS_ADV_FILAMENT_MENU) + SUBMENU(MSG_FILAMENT, menu_advanced_filament); + + #elif ENABLED(LIN_ADVANCE) + #if DISABLED(DISTINCT_E_FACTORS) - EDIT_ITEM(float42_52, MSG_ADVANCE_K, &planner.extruder_advance_K[0], 0, 10); + editable.decimal = planner.get_advance_k(); + EDIT_ITEM(float42_52, MSG_ADVANCE_K, &editable.decimal, 0.0f, 10.0f, []{ planner.set_advance_k(editable.decimal); }); #else - EXTRUDER_LOOP() - EDIT_ITEM_N(float42_52, e, MSG_ADVANCE_K_E, &planner.extruder_advance_K[e], 0, 10); + EXTRUDER_LOOP() { + editable.decimal = planner.get_advance_k(e); + EDIT_ITEM_N(float42_52, e, MSG_ADVANCE_K_E, &editable.decimal, 0.0f, 10.0f, []{ planner.set_advance_k(editable.decimal, MenuItemBase::itemIndex); }); + } #endif #if ENABLED(SMOOTH_LIN_ADVANCE) #if DISABLED(DISTINCT_E_FACTORS) @@ -766,7 +773,8 @@ void menu_advanced_settings() { } #endif #endif - #endif + + #endif // LIN_ADVANCE && !HAS_ADV_FILAMENT_MENU // M540 S - Abort on endstop hit when SD printing #if ENABLED(SD_ABORT_ON_ENDSTOP_HIT) diff --git a/Marlin/src/lcd/menu/menu_tune.cpp b/Marlin/src/lcd/menu/menu_tune.cpp index d5cb805244..7f4696a3f1 100644 --- a/Marlin/src/lcd/menu/menu_tune.cpp +++ b/Marlin/src/lcd/menu/menu_tune.cpp @@ -216,10 +216,13 @@ void menu_tune() { // #if ENABLED(LIN_ADVANCE) && DISABLED(SLIM_LCD_MENUS) #if DISABLED(DISTINCT_E_FACTORS) - EDIT_ITEM(float42_52, MSG_ADVANCE_K, &planner.extruder_advance_K[0], 0, 10); + editable.decimal = planner.get_advance_k(); + EDIT_ITEM(float42_52, MSG_ADVANCE_K, &editable.decimal, 0.0f, 10.0f, []{ planner.set_advance_k(editable.decimal); }); #else - EXTRUDER_LOOP() - EDIT_ITEM_N(float42_52, e, MSG_ADVANCE_K_E, &planner.extruder_advance_K[e], 0, 10); + EXTRUDER_LOOP() { + editable.decimal = planner.get_advance_k(e); + EDIT_ITEM_N(float42_52, e, MSG_ADVANCE_K_E, &editable.decimal, 0.0f, 10.0f, []{ planner.set_advance_k(editable.decimal, MenuItemBase::itemIndex); }); + } #endif #if ENABLED(SMOOTH_LIN_ADVANCE) #if DISABLED(DISTINCT_E_FACTORS) diff --git a/Marlin/src/lcd/sovol_rts/sovol_rts.cpp b/Marlin/src/lcd/sovol_rts/sovol_rts.cpp index bea95be96a..3c09838684 100644 --- a/Marlin/src/lcd/sovol_rts/sovol_rts.cpp +++ b/Marlin/src/lcd/sovol_rts/sovol_rts.cpp @@ -894,7 +894,7 @@ void RTS::handleData() { break; case 4: // Go to Advanced Settings - TERN_(LIN_ADVANCE, sendData(planner.extruder_advance_K[0] * 100, Advance_K_VP)); + TERN_(LIN_ADVANCE, sendData(planner.get_advance_k() * 100, Advance_K_VP)); gotoPage(ID_AdvWarn_L, ID_AdvWarn_D); break; @@ -1292,7 +1292,7 @@ void RTS::handleData() { #if ENABLED(LIN_ADVANCE) case 7: // Confirm - sendData(planner.extruder_advance_K[0] * 100, Advance_K_VP); + sendData(planner.get_advance_k() * 100, Advance_K_VP); gotoPage(ID_Advanced_L, ID_Advanced_D); break; #endif @@ -1350,7 +1350,7 @@ void RTS::handleData() { #endif case A_Retract: planner.settings.retract_acceleration = recdat.data[0]; break; #if ENABLED(LIN_ADVANCE) - case Advance_K: planner.extruder_advance_K[0] = float(recdat.data[0]) / 100.0f; break; + case Advance_K: planner.set_advance_k(float(recdat.data[0]) / 100.0f); break; #endif #endif case Accel: planner.settings.acceleration = recdat.data[0]; break; diff --git a/Marlin/src/lcd/tft/touch.cpp b/Marlin/src/lcd/tft/touch.cpp index bb226e50c6..fbba927a86 100644 --- a/Marlin/src/lcd/tft/touch.cpp +++ b/Marlin/src/lcd/tft/touch.cpp @@ -181,44 +181,51 @@ void Touch::touch(touch_control_t *control) { case SLIDER: hold(control); ui.encoderPosition = (x - control->x) * control->data / control->width; break; case INCREASE: hold(control, repeat_delay - 5); TERN(AUTO_BED_LEVELING_UBL, ui.external_control ? bedlevel.encoder_diff++ : ui.encoderPosition++, ui.encoderPosition++); break; case DECREASE: hold(control, repeat_delay - 5); TERN(AUTO_BED_LEVELING_UBL, ui.external_control ? bedlevel.encoder_diff-- : ui.encoderPosition--, ui.encoderPosition--); break; - case HEATER: - int8_t heater; - heater = control->data; + case HEATER: { ui.clear_for_drawing(); - #if HAS_HOTEND - if (heater >= 0) { // HotEnd - #if HOTENDS == 1 - MenuItem_int3::action(GET_TEXT_F(MSG_NOZZLE), &thermalManager.temp_hotend[0].target, 0, thermalManager.hotend_max_target(0), []{ thermalManager.start_watching_hotend(0); }); - #else - MenuItemBase::itemIndex = heater; - MenuItem_int3::action(GET_TEXT_F(MSG_NOZZLE_N), &thermalManager.temp_hotend[heater].target, 0, thermalManager.hotend_max_target(heater), []{ thermalManager.start_watching_hotend(MenuItemBase::itemIndex); }); + const int8_t heater = control->data; + switch (heater) { + default: // Hotend + #if HAS_HOTEND + #define HOTEND_HEATER(N) TERN0(HAS_MULTI_HOTEND, N) + TERN_(HAS_MULTI_HOTEND, MenuItemBase::itemIndex = heater); + MenuItem_int3::action(GET_TEXT_F(TERN(HAS_MULTI_HOTEND, MSG_NOZZLE_N, MSG_NOZZLE)), + &thermalManager.temp_hotend[HOTEND_HEATER(heater)].target, 0, thermalManager.hotend_max_target(HOTEND_HEATER(heater)), + []{ thermalManager.start_watching_hotend(HOTEND_HEATER(MenuItemBase::itemIndex)); } + ); #endif - } - #endif - #if HAS_HEATED_BED - else if (heater == H_BED) { - MenuItem_int3::action(GET_TEXT_F(MSG_BED), &thermalManager.temp_bed.target, 0, BED_MAX_TARGET, thermalManager.start_watching_bed); - } - #endif - #if HAS_HEATED_CHAMBER - else if (heater == H_CHAMBER) { - MenuItem_int3::action(GET_TEXT_F(MSG_CHAMBER), &thermalManager.temp_chamber.target, 0, CHAMBER_MAX_TARGET, thermalManager.start_watching_chamber); - } - #endif - #if HAS_COOLER - else if (heater == H_COOLER) { - MenuItem_int3::action(GET_TEXT_F(MSG_COOLER), &thermalManager.temp_cooler.target, 0, COOLER_MAX_TARGET, thermalManager.start_watching_cooler); - } - #endif + break; - break; - case FAN: + #if HAS_HEATED_BED + case H_BED: + MenuItem_int3::action(GET_TEXT_F(MSG_BED), &thermalManager.temp_bed.target, 0, BED_MAX_TARGET, thermalManager.start_watching_bed); + break; + #endif + + #if HAS_HEATED_CHAMBER + case H_CHAMBER: + MenuItem_int3::action(GET_TEXT_F(MSG_CHAMBER), &thermalManager.temp_chamber.target, 0, CHAMBER_MAX_TARGET, thermalManager.start_watching_chamber); + break; + #endif + + #if HAS_COOLER + case H_COOLER: + MenuItem_int3::action(GET_TEXT_F(MSG_COOLER), &thermalManager.temp_cooler.target, 0, COOLER_MAX_TARGET, thermalManager.start_watching_cooler); + break; + #endif + + } // switch + + } break; + + case FAN: { ui.clear_for_drawing(); static uint8_t fan, fan_speed; fan = 0; fan_speed = thermalManager.fan_speed[fan]; MenuItem_percent::action(GET_TEXT_F(MSG_FIRST_FAN_SPEED), &fan_speed, 0, 255, []{ thermalManager.set_fan_speed(fan, fan_speed); TERN_(LASER_SYNCHRONOUS_M106_M107, planner.buffer_sync_block(BLOCK_BIT_SYNC_FANS));}); - break; + } break; + case FEEDRATE: ui.clear_for_drawing(); MenuItem_int3::action(GET_TEXT_F(MSG_SPEED), &feedrate_percentage, SPEED_EDIT_MIN, SPEED_EDIT_MAX); @@ -228,11 +235,10 @@ void Touch::touch(touch_control_t *control) { case FLOWRATE: ui.clear_for_drawing(); MenuItemBase::itemIndex = control->data; - #if EXTRUDERS == 1 - MenuItem_int3::action(GET_TEXT_F(MSG_FLOW), &planner.flow_percentage[MenuItemBase::itemIndex], FLOW_EDIT_MIN, FLOW_EDIT_MAX, []{ planner.refresh_e_factor(MenuItemBase::itemIndex); }); - #else - MenuItem_int3::action(GET_TEXT_F(MSG_FLOW_N), &planner.flow_percentage[MenuItemBase::itemIndex], FLOW_EDIT_MIN, FLOW_EDIT_MAX, []{ planner.refresh_e_factor(MenuItemBase::itemIndex); }); - #endif + MenuItem_int3::action(GET_TEXT_F(TERN(HAS_MULTI_EXTRUDER, MSG_FLOW_N, MSG_FLOW)), + &planner.flow_percentage[MenuItemBase::itemIndex], FLOW_EDIT_MIN, FLOW_EDIT_MAX, + []{ planner.refresh_e_factor(MenuItemBase::itemIndex); } + ); break; #endif diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 87cb4cd21b..fe497058d9 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -236,6 +236,9 @@ float Planner::previous_nominal_speed; #if ENABLED(LIN_ADVANCE) float Planner::extruder_advance_K[DISTINCT_E]; // Initialized by settings.load + #if ENABLED(SMOOTH_LIN_ADVANCE) + uint32_t Planner::extruder_advance_K_q27[DISTINCT_E]; + #endif #endif #if HAS_POSITION_FLOAT @@ -2457,7 +2460,7 @@ bool Planner::_populate_block( block->acceleration_steps_per_s2 = accel; block->acceleration = accel / steps_per_mm; #if DISABLED(S_CURVE_ACCELERATION) - block->acceleration_rate = uint32_t(accel * (float(1UL << 24) / (STEPPER_TIMER_RATE))); + block->acceleration_rate = uint32_t(accel * (float(_BV32(24)) / (STEPPER_TIMER_RATE))); #endif #if HAS_ROUGH_LIN_ADVANCE @@ -2478,7 +2481,13 @@ bool Planner::_populate_block( } #elif ENABLED(SMOOTH_LIN_ADVANCE) block->use_advance_lead = use_advance_lead; - block->e_step_ratio = (block->direction_bits.e ? 1 : -1) * float(block->steps.e) / block->step_event_count; + const uint32_t ratio = (uint64_t(block->steps.e) * _BV32(30)) / block->step_event_count; + block->e_step_ratio_q30 = block->direction_bits.e ? ratio : -ratio; + + #if ENABLED(INPUT_SHAPING_E_SYNC) + const uint32_t xy_steps = TERN0(INPUT_SHAPING_X, block->steps.x) + TERN0(INPUT_SHAPING_Y, block->steps.y); + block->xy_length_inv_q30 = xy_steps ? (_BV32(30) / xy_steps) : 0; + #endif #endif // Formula for the average speed over a 1 step worth of distance if starting from zero and diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 1c23f95cb1..ead39a8bd4 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -247,7 +247,10 @@ typedef struct PlannerBlock { #if ENABLED(SMOOTH_LIN_ADVANCE) uint32_t cruise_time; // Cruise time in STEP timer counts - float e_step_ratio; + int32_t e_step_ratio_q30; // Ratio of e steps to block steps. + #if ENABLED(INPUT_SHAPING_E_SYNC) + uint32_t xy_length_inv_q30; // inverse of block->steps.x + block.steps.y + #endif #endif #if ANY(S_CURVE_ACCELERATION, SMOOTH_LIN_ADVANCE) uint32_t cruise_rate, // The actual cruise rate to use, between end of the acceleration phase and start of deceleration phase @@ -359,9 +362,8 @@ typedef struct PlannerSettings { #if ENABLED(EDITABLE_STEPS_PER_UNIT) float axis_steps_per_mm[DISTINCT_AXES]; #else - #define _DLIM(I) ALIM(I, _dasu) - #define _DASU(N) _dasu[_DLIM(N)], - #define _EASU(N) _dasu[_DLIM(E_AXIS + N)], + #define _DASU(N) _dasu[ALIM(N, _dasu)], + #define _EASU(N) _dasu[ALIM(E_AXIS + N, _dasu)], static constexpr float axis_steps_per_mm[DISTINCT_AXES] = { REPEAT(NUM_AXES, _DASU) TERN_(HAS_EXTRUDERS, REPEAT(DISTINCT_E, _EASU)) @@ -526,6 +528,23 @@ class Planner { #if ENABLED(LIN_ADVANCE) static float extruder_advance_K[DISTINCT_E]; + static void set_advance_k(const_float_t k, const uint8_t e=active_extruder) { + UNUSED(e); + extruder_advance_K[E_INDEX_N(e)] = k; + #if ENABLED(SMOOTH_LIN_ADVANCE) + extruder_advance_K_q27[E_INDEX_N(e)] = k * (1UL << 27); + #endif + } + static float get_advance_k(const uint8_t e=active_extruder) { + UNUSED(e); + return extruder_advance_K[E_INDEX_N(e)]; + } + #if ENABLED(SMOOTH_LIN_ADVANCE) + static uint32_t get_advance_k_q27(const uint8_t e=active_extruder) { + UNUSED(e); + return extruder_advance_K_q27[E_INDEX_N(e)]; + } + #endif #endif /** @@ -602,6 +621,10 @@ class Planner { volatile static uint32_t block_buffer_runtime_us; // Theoretical block buffer runtime in µs #endif + #if ENABLED(SMOOTH_LIN_ADVANCE) + static uint32_t extruder_advance_K_q27[DISTINCT_E]; + #endif + public: /** diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 1a46c6cc2a..59cb7244e9 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -126,7 +126,7 @@ #endif #if ENABLED(ADVANCE_K_EXTRA) - extern float other_extruder_advance_K[DISTINCT_E]; + extern float other_extruder_advance_K[EXTRUDERS]; #endif #if HAS_MULTI_EXTRUDER @@ -2641,18 +2641,14 @@ void MarlinSettings::postprocess() { _FIELD_TEST(planner_extruder_advance_K); EEPROM_READ(extruder_advance_K); if (!validating) - COPY(planner.extruder_advance_K, extruder_advance_K); + DISTINCT_E_LOOP() planner.set_advance_k(extruder_advance_K[e], e); + #if ENABLED(SMOOTH_LIN_ADVANCE) _FIELD_TEST(stepper_extruder_advance_tau); float tau[DISTINCT_E]; EEPROM_READ(tau); - if (!validating) { - #if ENABLED(DISTINCT_E_FACTORS) - EXTRUDER_LOOP() stepper.set_advance_tau(tau[e], e); - #else - stepper.set_advance_tau(tau[0]); - #endif - } + if (!validating) + DISTINCT_E_LOOP() stepper.set_advance_tau(tau[e], e); #endif } #endif @@ -3615,21 +3611,23 @@ void MarlinSettings::reset() { #if ENABLED(DISTINCT_E_FACTORS) constexpr float linAdvanceK[] = ADVANCE_K; - EXTRUDER_LOOP() { - const float a = linAdvanceK[ALIM(e, linAdvanceK)]; - planner.extruder_advance_K[e] = a; - TERN_(ADVANCE_K_EXTRA, other_extruder_advance_K[e] = a); - } - #else - planner.extruder_advance_K[0] = ADVANCE_K; - #endif - #if ENABLED(SMOOTH_LIN_ADVANCE) - #if ENABLED(DISTINCT_E_FACTORS) + #if ENABLED(SMOOTH_LIN_ADVANCE) constexpr float linAdvanceTau[] = ADVANCE_TAU; - EXTRUDER_LOOP() - stepper.set_advance_tau(linAdvanceTau[ALIM(e, linAdvanceTau)], e); - #else - stepper.set_advance_tau(ADVANCE_TAU); + #endif + + EXTRUDER_LOOP() { + const float k = linAdvanceK[ALIM(e, linAdvanceK)]; + planner.set_advance_k(k, e); + TERN_(SMOOTH_LIN_ADVANCE, stepper.set_advance_tau(linAdvanceTau[ALIM(e, linAdvanceTau)], e)); + TERN_(ADVANCE_K_EXTRA, other_extruder_advance_K[e] = k); + } + + #else // !DISTINCT_E_FACTORS + + planner.set_advance_k(ADVANCE_K); + TERN_(SMOOTH_LIN_ADVANCE, stepper.set_advance_tau(ADVANCE_TAU)); + #if ENABLED(ADVANCE_K_EXTRA) + EXTRUDER_LOOP() other_extruder_advance_K[e] = ADVANCE_K; #endif #endif diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index e9f83aa532..04c796acb3 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -1510,6 +1510,10 @@ HAL_STEP_TIMER_ISR() { #define STEP_MULTIPLY(A,B) MultiU24X32toH16(A, B) #endif +#if ENABLED(SMOOTH_LIN_ADVANCE) + FORCE_INLINE static constexpr int32_t MULT_Q(uint8_t q, int32_t x, int32_t y) { return (int64_t(x) * y) >> q; } +#endif + void Stepper::isr() { static hal_timer_t nextMainISR = 0; // Interval until the next main Stepper Pulse phase (0 = Now) @@ -2877,9 +2881,9 @@ hal_timer_t Stepper::block_phase_isr() { #if ENABLED(SMOOTH_LIN_ADVANCE) - float Stepper::extruder_advance_tau[DISTINCT_E], - Stepper::extruder_advance_tau_ticks[DISTINCT_E], - Stepper::extruder_advance_alpha[DISTINCT_E]; + float Stepper::extruder_advance_tau[DISTINCT_E]; + uint32_t Stepper::extruder_advance_tau_ticks[DISTINCT_E], + Stepper::extruder_advance_alpha_q30[DISTINCT_E]; void Stepper::set_la_interval(const int32_t rate) { if (rate == 0) { @@ -2904,117 +2908,119 @@ hal_timer_t Stepper::block_phase_isr() { constexpr uint16_t IS_COMPENSATION_BUFFER_SIZE = uint16_t(float(SMOOTH_LIN_ADV_HZ) / float(SHAPING_MIN_FREQ) / 2.0f + 0.5f); typedef struct { - xy_float_t buffer[IS_COMPENSATION_BUFFER_SIZE]; + xy_long_t buffer[IS_COMPENSATION_BUFFER_SIZE]; uint16_t index; + FORCE_INLINE void add(const xy_long_t &input) { + buffer[index] = input; + if (++index == IS_COMPENSATION_BUFFER_SIZE) index = 0; + } + FORCE_INLINE xy_long_t past_item(const uint16_t n) { + const int16_t i = int16_t(index) - n; + return buffer[i >= 0 ? i : i + IS_COMPENSATION_BUFFER_SIZE]; + } } DelayBuffer; DelayBuffer delayBuffer; - void add_to_buffer(xy_float_t input) { - delayBuffer.buffer[delayBuffer.index++] = input; - if (delayBuffer.index == IS_COMPENSATION_BUFFER_SIZE) - delayBuffer.index = 0; - } - - xy_float_t lookback(shaping_time_t t /* in stepper timer ticks */) { - constexpr float ADV_TICKS_PER_STEPPER_TICKS = float(SMOOTH_LIN_ADV_HZ) / (STEPPER_TIMER_RATE); - uint32_t delay_steps = t * ADV_TICKS_PER_STEPPER_TICKS + 0.5f; // Convert time to steps - uint16_t past_i; - if (delay_steps>= IS_COMPENSATION_BUFFER_SIZE) { - // this means the buffer is too small. TODO: how to inform user? - past_i = delayBuffer.index; - } - else { - past_i = (delayBuffer.index + IS_COMPENSATION_BUFFER_SIZE - delay_steps) % IS_COMPENSATION_BUFFER_SIZE; - } - return delayBuffer.buffer[past_i]; + xy_long_t smooth_lin_adv_lookback(const shaping_time_t stepper_ticks) { + constexpr uint32_t ADV_TICKS_PER_STEPPER_TICKS_Q30 = (uint64_t(SMOOTH_LIN_ADV_HZ) * _BV32(30)) / STEPPER_TIMER_RATE; + const uint16_t delay_steps = MULT_Q(30, stepper_ticks, ADV_TICKS_PER_STEPPER_TICKS_Q30); + return delayBuffer.past_item(delay_steps); } #endif // INPUT_SHAPING_E_SYNC - float lookahead(uint32_t t) { + int32_t smooth_lin_adv_lookahead(uint32_t stepper_ticks) { for (uint8_t i = 0; block_t *block = planner.get_future_block(i); i++) { if (block->is_sync()) continue; - if (t <= block->acceleration_time) { - if (!block->use_advance_lead) return 0.0f; - uint32_t rate = STEP_MULTIPLY(t, block->acceleration_rate) + block->initial_rate; + if (stepper_ticks <= block->acceleration_time) { + if (!block->use_advance_lead) return 0; + uint32_t rate = STEP_MULTIPLY(stepper_ticks, block->acceleration_rate) + block->initial_rate; NOMORE(rate, block->nominal_rate); - return rate * block->e_step_ratio; + return MULT_Q(30, rate, block->e_step_ratio_q30); } - t -= block->acceleration_time; + stepper_ticks -= block->acceleration_time; - if (t <= block->cruise_time) { - if (!block->use_advance_lead) return 0.0f; - return block->cruise_rate * block->e_step_ratio; + if (stepper_ticks <= block->cruise_time) { + if (!block->use_advance_lead) return 0; + return MULT_Q(30, block->cruise_rate, block->e_step_ratio_q30); } - t -= block->cruise_time; + stepper_ticks -= block->cruise_time; - if (t <= block->deceleration_time) { - if (!block->use_advance_lead) return 0.0f; - uint32_t rate = STEP_MULTIPLY(t, block->acceleration_rate); + if (stepper_ticks <= block->deceleration_time) { + if (!block->use_advance_lead) return 0; + uint32_t rate = STEP_MULTIPLY(stepper_ticks, block->acceleration_rate); if (rate < block->cruise_rate) { rate = block->cruise_rate - rate; NOLESS(rate, block->final_rate); } else rate = block->final_rate; - return rate * block->e_step_ratio; + return MULT_Q(30, rate, block->e_step_ratio_q30); } - t -= block->deceleration_time; + stepper_ticks -= block->deceleration_time; } - return 0.0f; + return 0; } hal_timer_t Stepper::smooth_lin_adv_isr() { - float target_adv_steps = 0; + int32_t target_adv_steps = 0; if (current_block) { - const uint32_t t = extruder_advance_tau_ticks[0] + curr_timer_tick; - target_adv_steps = lookahead(t) * planner.extruder_advance_K[0]; + const uint32_t stepper_ticks = extruder_advance_tau_ticks[E_INDEX_N(active_extruder)] + curr_timer_tick; + target_adv_steps = MULT_Q(27, smooth_lin_adv_lookahead(stepper_ticks), planner.get_advance_k_q27()); } else { curr_step_rate = 0; } - static float last_target_adv_steps = 0; - constexpr float dt_inv = SMOOTH_LIN_ADV_HZ; - float la_step_rate = (target_adv_steps - last_target_adv_steps) * dt_inv; + static int32_t last_target_adv_steps = 0; + constexpr uint16_t dt_inv = SMOOTH_LIN_ADV_HZ; + int32_t la_step_rate = (target_adv_steps - last_target_adv_steps) * dt_inv; last_target_adv_steps = target_adv_steps; - static float smoothed_vals[SMOOTH_LIN_ADV_EXP_ORDER] = {0}; + static int32_t smoothed_vals[SMOOTH_LIN_ADV_EXP_ORDER] = {0}; + for (uint8_t i = 0; i < SMOOTH_LIN_ADV_EXP_ORDER; i++) { // Approximate gaussian smoothing via higher order exponential smoothing - la_step_rate = extruder_advance_alpha[0] * la_step_rate + (1 - extruder_advance_alpha[0]) * smoothed_vals[i]; - smoothed_vals[i] = la_step_rate; + smoothed_vals[i] += MULT_Q(30, la_step_rate - smoothed_vals[i], extruder_advance_alpha_q30[E_INDEX_N(active_extruder)]); + la_step_rate = smoothed_vals[i]; } - const float planned_step_rate = current_block ? curr_step_rate * current_block->e_step_ratio : 0; - float total_step_rate = la_step_rate + planned_step_rate; + + const int32_t planned_step_rate = current_block + ? MULT_Q(30, curr_step_rate, current_block->e_step_ratio_q30) + : 0; + + int32_t total_step_rate = la_step_rate + planned_step_rate; #if ENABLED(INPUT_SHAPING_E_SYNC) - xy_float_t pre_shaping_rate = xy_float_t({0, 0}), - first_pulse_rate = xy_float_t({0, 0}); - float unshaped_rate_e = total_step_rate; + xy_long_t pre_shaping_rate = xy_long_t({0, 0}), + first_pulse_rate = xy_long_t({0, 0}); + int32_t unshaped_rate_e = total_step_rate; if (current_block) { - const float xy_length = TERN0(INPUT_SHAPING_X, current_block->steps.x) + TERN0(INPUT_SHAPING_Y, current_block->steps.y); - if (xy_length > 0) { + if (current_block->xy_length_inv_q30 > 0) { unshaped_rate_e = 0; - pre_shaping_rate = xy_float_t({ - TERN0(INPUT_SHAPING_X, total_step_rate * current_block->steps.x / xy_length), - TERN0(INPUT_SHAPING_Y, total_step_rate * current_block->steps.y / xy_length) + + pre_shaping_rate = xy_long_t({ + TERN0(INPUT_SHAPING_X, MULT_Q(30, total_step_rate * current_block->steps.x, current_block->xy_length_inv_q30)), + TERN0(INPUT_SHAPING_Y, MULT_Q(30, total_step_rate * current_block->steps.y, current_block->xy_length_inv_q30)) }); - first_pulse_rate = xy_float_t({ - TERN0(INPUT_SHAPING_X, pre_shaping_rate.x * Stepper::shaping_x.factor1 / 128.0f), - TERN0(INPUT_SHAPING_Y, pre_shaping_rate.y * Stepper::shaping_y.factor1 / 128.0f) + + first_pulse_rate = xy_long_t({ + TERN0(INPUT_SHAPING_X, (pre_shaping_rate.x * Stepper::shaping_x.factor1) >> 7), + TERN0(INPUT_SHAPING_Y, (pre_shaping_rate.y * Stepper::shaping_y.factor1) >> 7) }); } } - const xy_float_t second_pulse_rate = { - TERN0(INPUT_SHAPING_X, lookback(ShapingQueue::get_delay_x()).x * Stepper::shaping_x.factor2 / 128.0f), - TERN0(INPUT_SHAPING_Y, lookback(ShapingQueue::get_delay_y()).y * Stepper::shaping_y.factor2 / 128.0f) - }; - add_to_buffer(pre_shaping_rate); - const float x = TERN0(INPUT_SHAPING_X, first_pulse_rate.x + second_pulse_rate.x), - y = TERN0(INPUT_SHAPING_Y, first_pulse_rate.y + second_pulse_rate.y); + const xy_long_t second_pulse_rate = { + TERN0(INPUT_SHAPING_X, (smooth_lin_adv_lookback(ShapingQueue::get_delay_x()).x * Stepper::shaping_x.factor2)) >> 7, + TERN0(INPUT_SHAPING_Y, (smooth_lin_adv_lookback(ShapingQueue::get_delay_y()).y * Stepper::shaping_y.factor2)) >> 7 + }; + + delayBuffer.add(pre_shaping_rate); + + const int32_t x = TERN0(INPUT_SHAPING_X, first_pulse_rate.x + second_pulse_rate.x), + y = TERN0(INPUT_SHAPING_Y, first_pulse_rate.y + second_pulse_rate.y); total_step_rate = unshaped_rate_e + x + y; @@ -3025,6 +3031,7 @@ hal_timer_t Stepper::block_phase_isr() { curr_timer_tick += SMOOTH_LIN_ADV_INTERVAL; return SMOOTH_LIN_ADV_INTERVAL; } + #endif // SMOOTH_LIN_ADVANCE // Timer interrupt for E. LA_steps is set in the main routine diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index 1c06d83351..3fb0b44884 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -352,13 +352,18 @@ class Stepper { #endif #if ENABLED(SMOOTH_LIN_ADVANCE) - static void set_advance_tau(const_float_t tau, const uint8_t e=E_INDEX_N(active_extruder)) { - extruder_advance_tau[e] = tau; - extruder_advance_tau_ticks[e] = tau * (STEPPER_TIMER_RATE); // i.e., <= STEPPER_TIMER_RATE / 2 + static float extruder_advance_tau[DISTINCT_E]; // Smoothing time; also the lookahead time of the smoother + static void set_advance_tau(const_float_t tau, const uint8_t e=active_extruder) { + const uint8_t i = E_INDEX_N(e); + extruder_advance_tau[i] = tau; + extruder_advance_tau_ticks[i] = tau * STEPPER_TIMER_RATE; // α=1−exp(−dt/τ) - extruder_advance_alpha[e] = 1.0f - expf(-(SMOOTH_LIN_ADV_INTERVAL) * (SMOOTH_LIN_ADV_EXP_ORDER) / extruder_advance_tau_ticks[e]); + const float alpha_float = 1.0f - expf(-float(SMOOTH_LIN_ADV_INTERVAL) * (SMOOTH_LIN_ADV_EXP_ORDER) / extruder_advance_tau_ticks[i]); + extruder_advance_alpha_q30[i] = int32_t(alpha_float * _BV32(30)); + } + static float get_advance_tau(const uint8_t e=active_extruder) { + return extruder_advance_tau[E_INDEX_N(e)]; } - static float get_advance_tau(const uint8_t e=E_INDEX_N(active_extruder)) { return extruder_advance_tau[e]; } #endif private: @@ -449,12 +454,11 @@ class Stepper { static hal_timer_t nextAdvanceISR, la_interval; // Interval between ISR calls for LA #if ENABLED(SMOOTH_LIN_ADVANCE) - static uint32_t curr_timer_tick, // Current tick relative to block start - curr_step_rate; // Current motion step rate - static float extruder_advance_tau[DISTINCT_E], // Smoothing time; also the lookahead time of the smoother - extruder_advance_tau_ticks[DISTINCT_E], // Same as extruder_advance_tau but in in stepper timer ticks - extruder_advance_alpha[DISTINCT_E]; // The smoothing factor of each stage of the high-order exponential - // smoothing filter (calculated from tau) + static uint32_t curr_timer_tick, // Current tick relative to block start + curr_step_rate; // Current motion step rate + static uint32_t extruder_advance_tau_ticks[DISTINCT_E], // Same as extruder_advance_tau but in in stepper timer ticks + extruder_advance_alpha_q30[DISTINCT_E]; // The smoothing factor of each stage of the high-order exponential + // smoothing filter (calculated from tau) #else static int32_t la_delta_error, // Analogue of delta_error.e for E steps in LA ISR la_dividend, // Analogue of advance_dividend.e for E steps in LA ISR diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index fcaa64cefe..980f9327b5 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -1587,7 +1587,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { #endif // Migrate Linear Advance K factor to the new extruder - TERN_(LIN_ADVANCE, planner.extruder_advance_K[active_extruder] = planner.extruder_advance_K[migration_extruder]); + TERN_(LIN_ADVANCE, planner.set_advance_k(planner.get_advance_k(migration_extruder), active_extruder)); // Temporary migration toolchange_settings restored on exit. i.e., before next tool_change(). #if defined(MIGRATION_FS_EXTRA_PRIME) \ From 5a88a806909ca1c1942511d4e3c2bdcfbd3f02b1 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 13 May 2025 16:50:41 -0500 Subject: [PATCH 025/102] =?UTF-8?q?=F0=9F=9A=B8=20Extend=20M360=20(a=20Rep?= =?UTF-8?q?etier=20code)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/host/M360.cpp | 179 +++++++++++++++++++++------------ 1 file changed, 115 insertions(+), 64 deletions(-) diff --git a/Marlin/src/gcode/host/M360.cpp b/Marlin/src/gcode/host/M360.cpp index 63071f6113..a3f86d615d 100644 --- a/Marlin/src/gcode/host/M360.cpp +++ b/Marlin/src/gcode/host/M360.cpp @@ -22,6 +22,10 @@ #include "../../inc/MarlinConfig.h" +/** + * M360 Report Printer Configuration - Repetier Firmware + * See https://github.com/repetier/Repetier-Firmware/blob/master/src/ArduinoAVR/Repetier/Printer.cpp + */ #if ENABLED(REPETIER_GCODE_M360) #include "../gcode.h" @@ -33,74 +37,112 @@ #include "../../module/temperature.h" #endif -static void config_prefix(PGM_P const name, PGM_P const pref=nullptr, const int8_t ind=-1) { +#include + +struct ProgStr { + PGM_P ptr; + constexpr ProgStr(PGM_P p) : ptr(p) {} + ProgStr(FSTR_P f) : ptr(FTOP(f)) {} + ProgStr(std::nullptr_t) : ptr(nullptr) {} + + constexpr operator PGM_P() const { return ptr; } + constexpr explicit operator bool() const { return ptr != nullptr; } +}; + +static void config_prefix(ProgStr name, ProgStr pref=nullptr, int8_t ind=-1) { SERIAL_ECHOPGM("Config:"); - if (pref) SERIAL_ECHOPGM_P(pref); + if (pref) SERIAL_ECHOPGM_P(static_cast(pref)); if (ind >= 0) { SERIAL_ECHO(ind); SERIAL_CHAR(':'); } - SERIAL_ECHOPGM_P(name, C(':')); + SERIAL_ECHOPGM_P(static_cast(name), C(':')); } -static void config_line(PGM_P const name, const float val, PGM_P const pref=nullptr, const int8_t ind=-1) { + +template +static void config_line(ProgStr name, const T val, ProgStr pref=nullptr, int8_t ind=-1) { config_prefix(name, pref, ind); SERIAL_ECHOLN(val); } -static void config_line(FSTR_P const name, const float val, FSTR_P const pref=nullptr, const int8_t ind=-1) { - config_line(FTOP(name), val, FTOP(pref), ind); -} -static void config_line_e(const int8_t e, PGM_P const name, const float val) { + +template +static void config_line_e(int8_t e, ProgStr name, const T val) { config_line(name, val, PSTR("Extr."), e + 1); } -static void config_line_e(const int8_t e, FSTR_P const name, const float val) { - config_line_e(e, FTOP(name), val); -} - /** * M360: Report Firmware configuration * in RepRapFirmware-compatible format */ void GcodeSuite::M360() { - PGMSTR(X_STR, "X"); - PGMSTR(Y_STR, "Y"); - PGMSTR(Z_STR, "Z"); - #if ANY(CLASSIC_JERK, HAS_LINEAR_E_JERK) - PGMSTR(JERK_STR, "Jerk"); - #endif - // // Basics and Enabled items // config_line(F("Baudrate"), BAUDRATE); config_line(F("InputBuffer"), MAX_CMD_SIZE); config_line(F("PrintlineCache"), BUFSIZE); - config_line(F("MixingExtruder"), ENABLED(MIXING_EXTRUDER)); - config_line(F("SDCard"), ENABLED(HAS_MEDIA)); - config_line(F("Fan"), ENABLED(HAS_FAN)); - config_line(F("LCD"), ENABLED(HAS_DISPLAY)); + config_line(F("MixingExtruder"), bool(ENABLED(MIXING_EXTRUDER))); + config_line(F("SDCard"), bool(ENABLED(HAS_MEDIA))); + config_line(F("Fan"), bool(ENABLED(HAS_FAN))); + config_line(F("LCD"), bool(ENABLED(HAS_DISPLAY))); config_line(F("SoftwarePowerSwitch"), 1); - config_line(F("SupportLocalFilamentchange"), ENABLED(ADVANCED_PAUSE_FEATURE)); - config_line(F("CaseLights"), ENABLED(CASE_LIGHT_ENABLE)); - config_line(F("ZProbe"), ENABLED(HAS_BED_PROBE)); - config_line(F("Autolevel"), ENABLED(HAS_LEVELING)); - config_line(F("EEPROM"), ENABLED(EEPROM_SETTINGS)); + config_line(F("SupportLocalFilamentchange"), bool(ENABLED(ADVANCED_PAUSE_FEATURE))); + config_line(F("CaseLights"), bool(ENABLED(CASE_LIGHT_ENABLE))); + config_line(F("ZProbe"), bool(ENABLED(HAS_BED_PROBE))); + config_line(F("Autolevel"), bool(ENABLED(HAS_LEVELING))); + config_line(F("EEPROM"), bool(ENABLED(EEPROM_SETTINGS))); + + // + // Axis letters, in PROGMEM + // + #define _DEFINE_A_STR(Q) PGMSTR(Q##_STR, STR_##Q); + MAIN_AXIS_MAP(_DEFINE_A_STR); // // Homing Directions // PGMSTR(H_DIR_STR, "HomeDir"); - config_line(H_DIR_STR, X_HOME_DIR, X_STR); - config_line(H_DIR_STR, Y_HOME_DIR, Y_STR); - config_line(H_DIR_STR, Z_HOME_DIR, Z_STR); + #if X_HOME_DIR + config_line(H_DIR_STR, X_HOME_DIR, X_STR); + #endif + #if Y_HOME_DIR + config_line(H_DIR_STR, Y_HOME_DIR, Y_STR); + #endif + #if Z_HOME_DIR + config_line(H_DIR_STR, Z_HOME_DIR, Z_STR); + #endif + #if I_HOME_DIR + config_line(H_DIR_STR, I_HOME_DIR, I_STR); + #endif + #if J_HOME_DIR + config_line(H_DIR_STR, J_HOME_DIR, J_STR); + #endif + #if K_HOME_DIR + config_line(H_DIR_STR, K_HOME_DIR, K_STR); + #endif + #if U_HOME_DIR + config_line(H_DIR_STR, U_HOME_DIR, U_STR); + #endif + #if V_HOME_DIR + config_line(H_DIR_STR, V_HOME_DIR, V_STR); + #endif + #if W_HOME_DIR + config_line(H_DIR_STR, W_HOME_DIR, W_STR); + #endif + + #if ANY(CLASSIC_JERK, HAS_LINEAR_E_JERK) + PGMSTR(JERK_STR, "Jerk"); + #endif // // XYZ Axis Jerk // #if ENABLED(CLASSIC_JERK) - if (planner.max_jerk.x == planner.max_jerk.y) - config_line(F("XY"), planner.max_jerk.x, FPSTR(JERK_STR)); + #define _REPORT_JERK(Q) config_line(Q##_STR, planner.max_jerk.Q, JERK_STR); + if (TERN0(HAS_Y_AXIS, planner.max_jerk.x == planner.max_jerk.y)) + config_line(F("XY"), planner.max_jerk.x, JERK_STR); else { - config_line(X_STR, planner.max_jerk.x, JERK_STR); - config_line(Y_STR, planner.max_jerk.y, JERK_STR); + TERN_(HAS_X_AXIS, _REPORT_JERK(X)); + TERN_(HAS_Y_AXIS, _REPORT_JERK(Y)); } - config_line(Z_STR, planner.max_jerk.z, JERK_STR); + TERN_(HAS_Z_AXIS, config_line(Z_STR, planner.max_jerk.z, JERK_STR)); + SECONDARY_AXIS_MAP(_REPORT_JERK); #endif // @@ -112,53 +154,62 @@ void GcodeSuite::M360() { PGMSTR(UNRET_STR, "RetractionUndo"); PGMSTR(SPEED_STR, "Speed"); // M10 Retract with swap (long) moves - config_line(F("Length"), fwretract.settings.retract_length, FPSTR(RET_STR)); + config_line(F("Length"), fwretract.settings.retract_length, RET_STR); + config_line(F("LongLength"), fwretract.settings.swap_retract_length, RET_STR); config_line(SPEED_STR, fwretract.settings.retract_feedrate_mm_s, RET_STR); - config_line(F("ZLift"), fwretract.settings.retract_zraise, FPSTR(RET_STR)); - config_line(F("LongLength"), fwretract.settings.swap_retract_length, FPSTR(RET_STR)); + config_line(F("ZLift"), fwretract.settings.retract_zraise, RET_STR); // M11 Recover (undo) with swap (long) moves + config_line(F("ExtraLength"), fwretract.settings.retract_recover_extra, UNRET_STR); + config_line(F("ExtraLongLength"), fwretract.settings.swap_retract_recover_extra, UNRET_STR); config_line(SPEED_STR, fwretract.settings.retract_recover_feedrate_mm_s, UNRET_STR); - config_line(F("ExtraLength"), fwretract.settings.retract_recover_extra, FPSTR(UNRET_STR)); - config_line(F("ExtraLongLength"), fwretract.settings.swap_retract_recover_extra, FPSTR(UNRET_STR)); - config_line(F("LongSpeed"), fwretract.settings.swap_retract_recover_feedrate_mm_s, FPSTR(UNRET_STR)); + config_line(F("LongSpeed"), fwretract.settings.swap_retract_recover_feedrate_mm_s, UNRET_STR); #endif // // Workspace boundaries // - const xyz_pos_t dmin = { X_MIN_POS, Y_MIN_POS, Z_MIN_POS }, - dmax = { X_MAX_POS, Y_MAX_POS, Z_MAX_POS }; + const xyz_pos_t dmin = NUM_AXIS_ARRAY(X_MIN_POS, Y_MIN_POS, Z_MIN_POS, I_MIN_POS, J_MIN_POS, K_MIN_POS, U_MIN_POS, V_MIN_POS, W_MIN_POS), + dmax = NUM_AXIS_ARRAY(X_MAX_POS, Y_MAX_POS, Z_MAX_POS, I_MAX_POS, J_MAX_POS, K_MAX_POS, U_MAX_POS, V_MAX_POS, W_MAX_POS); xyz_pos_t cmin = dmin, cmax = dmax; apply_motion_limits(cmin); apply_motion_limits(cmax); const xyz_pos_t wmin = cmin.asLogical(), wmax = cmax.asLogical(); PGMSTR(MIN_STR, "Min"); + #define _REPORT_MIN(Q) config_line(MIN_STR, wmin.Q, Q##_STR); + MAIN_AXIS_MAP(_REPORT_MIN); + PGMSTR(MAX_STR, "Max"); + #define _REPORT_MAX(Q) config_line(MAX_STR, wmax.Q, Q##_STR); + MAIN_AXIS_MAP(_REPORT_MAX); + PGMSTR(SIZE_STR, "Size"); - config_line(MIN_STR, wmin.x, X_STR); - config_line(MIN_STR, wmin.y, Y_STR); - config_line(MIN_STR, wmin.z, Z_STR); - config_line(MAX_STR, wmax.x, X_STR); - config_line(MAX_STR, wmax.y, Y_STR); - config_line(MAX_STR, wmax.z, Z_STR); - config_line(SIZE_STR, wmax.x - wmin.x, X_STR); - config_line(SIZE_STR, wmax.y - wmin.y, Y_STR); - config_line(SIZE_STR, wmax.z - wmin.z, Z_STR); + #define _REPORT_SIZE(Q) config_line(SIZE_STR, wmax.Q - wmin.Q, Q##_STR); + MAIN_AXIS_MAP(_REPORT_SIZE); + + // + // Axis Steps per mm + // + PGMSTR(S_MM_STR, "Steps/mm"); + #define _REPORT_S_MM(Q) config_line(S_MM_STR, planner.settings.axis_steps_per_mm[_AXIS(Q)], Q##_STR); + MAIN_AXIS_MAP(_REPORT_S_MM); // // Print and Travel Acceleration // - #define _ACCEL(A,B) _MIN(planner.settings.max_acceleration_mm_per_s2[A##_AXIS], planner.settings.B) - PGMSTR(P_ACC_STR, "PrintAccel"); - PGMSTR(T_ACC_STR, "TravelAccel"); - config_line(P_ACC_STR, _ACCEL(X, acceleration), X_STR); - config_line(P_ACC_STR, _ACCEL(Y, acceleration), Y_STR); - config_line(P_ACC_STR, _ACCEL(Z, acceleration), Z_STR); - config_line(T_ACC_STR, _ACCEL(X, travel_acceleration), X_STR); - config_line(T_ACC_STR, _ACCEL(Y, travel_acceleration), Y_STR); - config_line(T_ACC_STR, _ACCEL(Z, travel_acceleration), Z_STR); + #define _ACCEL(Q,B) _MIN(planner.settings.max_acceleration_mm_per_s2[Q##_AXIS], planner.settings.B) + PGMSTR(P_ACC_STR, "PrintAccel"); + #define _REPORT_P_ACC(Q) config_line(P_ACC_STR, _ACCEL(Q, acceleration), Q##_STR); + MAIN_AXIS_MAP(_REPORT_P_ACC); + + PGMSTR(T_ACC_STR, "TravelAccel"); + #define _REPORT_T_ACC(Q) config_line(T_ACC_STR, _ACCEL(Q, travel_acceleration), Q##_STR); + MAIN_AXIS_MAP(_REPORT_T_ACC); + + // + // Printer Type + // config_prefix(PSTR("PrinterType")); SERIAL_ECHOLNPGM( TERN_(DELTA, "Delta") @@ -189,12 +240,12 @@ void GcodeSuite::M360() { #elif ENABLED(CLASSIC_JERK) config_line_e(e, JERK_STR, planner.max_jerk.e); #endif - config_line_e(e, F("MaxSpeed"), planner.settings.max_feedrate_mm_s[E_AXIS_N(e)]); config_line_e(e, F("Acceleration"), planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(e)]); + config_line_e(e, F("MaxSpeed"), planner.settings.max_feedrate_mm_s[E_AXIS_N(e)]); config_line_e(e, F("Diameter"), TERN(NO_VOLUMETRICS, DEFAULT_NOMINAL_FILAMENT_DIA, planner.filament_size[e])); config_line_e(e, F("MaxTemp"), thermalManager.hotend_maxtemp[e]); } #endif } -#endif +#endif // REPETIER_GCODE_M360 From eaa836b6fc89835b1e18f3e92b2f646deff306e8 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 13 May 2025 16:51:48 -0500 Subject: [PATCH 026/102] =?UTF-8?q?=F0=9F=8E=A8=20May=2013=20code=20format?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/motion.h | 10 +++++----- Marlin/src/module/planner.h | 12 ++++++------ 2 files changed, 11 insertions(+), 11 deletions(-) diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index 18376cf773..4245331010 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -141,11 +141,11 @@ inline int8_t pgm_read_any(const int8_t *p) { return TERN(__IMXRT1062__, *p, pgm static const XYZval NAME##_P DEFS_PROGMEM = NUM_AXIS_ARRAY(X_##OPT, Y_##OPT, Z_##OPT, I_##OPT, J_##OPT, K_##OPT, U_##OPT, V_##OPT, W_##OPT); \ return pgm_read_any(&NAME##_P[axis]); \ } -XYZ_DEFS(float, base_min_pos, MIN_POS); -XYZ_DEFS(float, base_max_pos, MAX_POS); -XYZ_DEFS(float, base_home_pos, HOME_POS); -XYZ_DEFS(float, max_length, MAX_LENGTH); -XYZ_DEFS(int8_t, home_dir, HOME_DIR); +XYZ_DEFS(float, base_min_pos, MIN_POS); // base_min_pos(axis) +XYZ_DEFS(float, base_max_pos, MAX_POS); // base_max_pos(axis) +XYZ_DEFS(float, base_home_pos, HOME_POS); // base_home_pos(axis) +XYZ_DEFS(float, max_length, MAX_LENGTH); // max_length(axis) +XYZ_DEFS(int8_t, home_dir, HOME_DIR); // home_dir(axis) // Flags for rotational axes constexpr AxisFlags rotational{0 LOGICAL_AXIS_GANG( diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index ead39a8bd4..0a3a35d922 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -373,12 +373,12 @@ typedef struct PlannerSettings { #undef _DLIM #endif - feedRate_t max_feedrate_mm_s[DISTINCT_AXES]; // (mm/s) M203 XYZE - Max speeds - float acceleration, // (mm/s^2) M204 S - Normal acceleration. DEFAULT ACCELERATION for all printing moves. - retract_acceleration, // (mm/s^2) M204 R - Retract acceleration. Filament pull-back and push-forward while standing still in the other axes - travel_acceleration; // (mm/s^2) M204 T - Travel acceleration. DEFAULT ACCELERATION for all NON printing moves. - feedRate_t min_feedrate_mm_s, // (mm/s) M205 S - Minimum linear feedrate - min_travel_feedrate_mm_s; // (mm/s) M205 T - Minimum travel feedrate + feedRate_t max_feedrate_mm_s[DISTINCT_AXES]; // (mm/s) M203 XYZE - Max speeds + float acceleration, // (mm/s^2) M204 S - Normal acceleration. DEFAULT ACCELERATION for all printing moves. + retract_acceleration, // (mm/s^2) M204 R - Retract acceleration. Filament pull-back and push-forward while standing still in the other axes + travel_acceleration; // (mm/s^2) M204 T - Travel acceleration. DEFAULT ACCELERATION for all NON printing moves. + feedRate_t min_feedrate_mm_s, // (mm/s) M205 S - Minimum linear feedrate + min_travel_feedrate_mm_s; // (mm/s) M205 T - Minimum travel feedrate } planner_settings_t; #if ENABLED(IMPROVE_HOMING_RELIABILITY) From c8265d61d571ba20eacfb3a57587072d005746ec Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 13 May 2025 17:14:57 -0500 Subject: [PATCH 027/102] =?UTF-8?q?=F0=9F=9A=B8=20Include=20'R'=20in=20M20?= =?UTF-8?q?8=20report?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to #21335 --- Marlin/src/feature/fwretract.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/Marlin/src/feature/fwretract.cpp b/Marlin/src/feature/fwretract.cpp index fff2a1ed39..8944d2bd35 100644 --- a/Marlin/src/feature/fwretract.cpp +++ b/Marlin/src/feature/fwretract.cpp @@ -244,6 +244,7 @@ void FWRetract::M208_report() { " M208 S", LINEAR_UNIT(settings.retract_recover_extra) , " W", LINEAR_UNIT(settings.swap_retract_recover_extra) , " F", LINEAR_UNIT(MMS_TO_MMM(settings.retract_recover_feedrate_mm_s)) + , " R", LINEAR_UNIT(MMS_TO_MMM(settings.swap_retract_recover_feedrate_mm_s)) ); } From 7a841cd8cff5683fd318e84e30e0c652f8c85af8 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 14 May 2025 00:31:35 +0000 Subject: [PATCH 028/102] [cron] Bump distribution date (2025-05-14) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 3c4711b876..bc68976ee3 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-05-10" +//#define STRING_DISTRIBUTION_DATE "2025-05-14" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 64a498179d..75995aa92a 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-05-10" + #define STRING_DISTRIBUTION_DATE "2025-05-14" #endif /** From 10ecea62c189d4bd8a7158bfd1d1347add2bf217 Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Thu, 15 May 2025 06:54:48 +1200 Subject: [PATCH 029/102] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20'PIN=5FEXIST'=20ty?= =?UTF-8?q?po=20(#27856)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/marlinui.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 28697affab..991a4f549c 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -1224,7 +1224,7 @@ void MarlinUI::init() { #ifdef NEOPIXEL_BKGD_INDEX_FIRST neo.set_background_off(); neo.show(); - #elif PIN_EXIST(LCD_BACKLIGHT) + #elif PIN_EXISTS(LCD_BACKLIGHT) WRITE(LCD_BACKLIGHT_PIN, LOW); // Backlight off #endif backlight_off_ms = 0; From 8f13c1ecb213afb2bb2d91e164061bdab3a5e1ef Mon Sep 17 00:00:00 2001 From: Giuliano <3684609+GMagician@users.noreply.github.com> Date: Wed, 14 May 2025 20:55:45 +0200 Subject: [PATCH 030/102] =?UTF-8?q?=F0=9F=8C=90=20Shorten=20Italian=20mess?= =?UTF-8?q?ages=20(#27855)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/language/language_it.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index 4bcde87859..0e8689cb0f 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -945,9 +945,9 @@ namespace LanguageWide_it { using namespace LanguageNarrow_it; #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 LSTR MSG_HOST_START_PRINT = _UxGT("Avvio stampa host"); - LSTR MSG_PRINTING_OBJECT = _UxGT("Sto stampando l'oggetto"); - LSTR MSG_CANCEL_OBJECT = _UxGT("Cancella l'oggetto"); - LSTR MSG_CANCEL_OBJECT_N = _UxGT("Cancella l'oggetto {"); + LSTR MSG_PRINTING_OBJECT = _UxGT("Stampa oggetto"); + LSTR MSG_CANCEL_OBJECT = _UxGT("Cancella oggetto"); + LSTR MSG_CANCEL_OBJECT_N = _UxGT("Cancella oggetto {"); LSTR MSG_CONTINUE_PRINT_JOB = _UxGT("Continua il job di stampa"); LSTR MSG_MEDIA_MENU = _UxGT("Selez.da supporto"); LSTR MSG_TURN_OFF = _UxGT("Spegni la stampante"); From 8e0f271f558b95a1f4993209cf92586693d7051d Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Thu, 15 May 2025 06:57:18 +1200 Subject: [PATCH 031/102] =?UTF-8?q?=F0=9F=94=A8=20ESP3DLib=20update=20for?= =?UTF-8?q?=20compatibility=20(#27851)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ini/features.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ini/features.ini b/ini/features.ini index e51ad0bda3..5bd955dd0a 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -378,7 +378,7 @@ HAS_SERVOS = build_src_filter=+ HAS_MICROSTEPS = build_src_filter=+ (ESP3D_)?WIFISUPPORT = esp32async/AsyncTCP@3.3.3, mathieucarbou/ESP Async WebServer@3.0.6 - ESP3DLib=https://github.com/luc-github/ESP3DLib/archive/dc0f3d96c6.zip + ESP3DLib=https://github.com/luc-github/ESP3DLib/archive/6d62f76c3f.zip arduinoWebSockets=links2004/WebSockets@2.3.4 luc-github/ESP32SSDP@1.1.1 lib_ignore=ESPAsyncTCP From 4a0b3d1c9b68b0c412e6bba5a03044b5d2ffacb5 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 14 May 2025 15:17:58 -0500 Subject: [PATCH 032/102] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Con?= =?UTF-8?q?solidate=20MIN/MAX/STOP=20endstop=20pin=20assign=20(#27839)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h | 71 +++---------------- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h | 59 ++------------- Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h | 41 ++--------- Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h | 41 ++--------- Marlin/src/pins/pins.h | 51 ------------- Marlin/src/pins/pins_postprocess.h | 60 +++++++++++++--- Marlin/src/pins/rambo/pins_EINSY_RAMBO.h | 24 ++++--- Marlin/src/pins/rambo/pins_EINSY_RETRO.h | 34 +++++---- Marlin/src/pins/ramps/pins_TRIGORILLA_14.h | 2 +- Marlin/src/pins/sam/pins_ARCHIM2.h | 16 ++--- Marlin/src/pins/stm32f1/pins_CHITU3D_V9.h | 4 +- Marlin/src/pins/stm32f1/pins_CREALITY_V521.h | 8 +-- Marlin/src/pins/stm32f4/pins_ARTILLERY_RUBY.h | 25 ++----- Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h | 32 +++------ .../pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h | 59 ++------------- .../pins/stm32f4/pins_BTT_SKR_PRO_common.h | 41 ++--------- .../pins/stm32f4/pins_BTT_SKR_V2_0_common.h | 61 ++-------------- Marlin/src/pins/stm32f4/pins_I3DBEEZ9.h | 53 ++------------ .../src/pins/stm32f4/pins_MELLOW_FLY_E3_V2.h | 22 ++---- Marlin/src/pins/stm32f4/pins_MKS_SKIPR_V1_0.h | 50 +++---------- Marlin/src/pins/stm32f7/pins_REMRAM_V1.h | 57 +++++++++------ .../pins/stm32g0/pins_BTT_MANTA_M8P_common.h | 40 ++--------- Marlin/src/pins/stm32g0/pins_BTT_SKRAT_V1_0.h | 61 +++------------- .../src/pins/stm32h7/pins_BTT_KRAKEN_V1_0.h | 59 ++------------- .../pins/stm32h7/pins_BTT_MANTA_M8P_V2_0.h | 59 ++------------- .../pins/stm32h7/pins_BTT_OCTOPUS_MAX_EZ.h | 59 ++------------- .../stm32h7/pins_BTT_OCTOPUS_PRO_V1_common.h | 59 ++------------- .../pins/stm32h7/pins_BTT_SKR_V3_0_common.h | 64 +++-------------- 28 files changed, 257 insertions(+), 955 deletions(-) diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h index e6b4baddaf..3afb7fe072 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -43,71 +43,18 @@ // // Limit Switches // -#ifdef X_STALL_SENSITIVITY - #ifndef X_STOP_PIN - #define X_STOP_PIN X_DIAG_PIN - #endif - #if X_HOME_TO_MIN - #ifndef X_MAX_PIN - #define X_MAX_PIN P1_28 // X+ - #endif - #else - #ifndef X_MIN_PIN - #define X_MIN_PIN P1_28 // X+ - #endif - #endif -#else - #ifndef X_MIN_PIN - #define X_MIN_PIN P1_29 // X- - #endif - #ifndef X_MAX_PIN - #define X_MAX_PIN P1_28 // X+ - #endif +#ifndef X_STOP_PIN + #define X_STOP_PIN X_DIAG_PIN #endif - -#ifdef Y_STALL_SENSITIVITY - #ifndef Y_STOP_PIN - #define Y_STOP_PIN Y_DIAG_PIN - #endif - #if Y_HOME_TO_MIN - #ifndef Y_MAX_PIN - #define Y_MAX_PIN P1_26 // Y+ - #endif - #else - #ifndef Y_MIN_PIN - #define Y_MIN_PIN P1_26 // Y+ - #endif - #endif -#else - #ifndef Y_MIN_PIN - #define Y_MIN_PIN P1_27 // Y- - #endif - #ifndef Y_MAX_PIN - #define Y_MAX_PIN P1_26 // Y+ - #endif +#define X_OTHR_PIN P1_28 // X+ +#ifndef Y_STOP_PIN + #define Y_STOP_PIN Y_DIAG_PIN #endif - -#ifdef Z_STALL_SENSITIVITY - #ifndef Z_STOP_PIN - #define Z_STOP_PIN Z_DIAG_PIN - #endif - #if Z_HOME_TO_MIN - #ifndef Z_MAX_PIN - #define Z_MAX_PIN P1_24 // Z+ - #endif - #else - #ifndef Z_MIN_PIN - #define Z_MIN_PIN P1_24 // Z+ - #endif - #endif -#else - #ifndef Z_MIN_PIN - #define Z_MIN_PIN P1_25 // Z- - #endif - #ifndef Z_MAX_PIN - #define Z_MAX_PIN P1_24 // Z+ - #endif +#define Y_OTHR_PIN P1_26 // Y+ +#ifndef Z_STOP_PIN + #define Z_STOP_PIN Z_DIAG_PIN #endif +#define Z_OTHR_PIN P1_24 // Z+ #define ONBOARD_ENDSTOPPULLUPS // Board has built-in pullups diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h index 65718bbf45..dbb8210fd1 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -70,61 +70,14 @@ // // Limit Switches // -#ifdef X_STALL_SENSITIVITY - #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_TO_MIN - #define X_MAX_PIN P1_26 // E0DET - #else - #define X_MIN_PIN P1_26 // E0DET - #endif -#elif ENABLED(X_DUAL_ENDSTOPS) - #ifndef X_MIN_PIN - #define X_MIN_PIN P1_29 // X-STOP - #endif - #ifndef X_MAX_PIN - #define X_MAX_PIN P1_26 // E0DET - #endif -#else - #define X_STOP_PIN P1_29 // X-STOP -#endif - -#ifdef Y_STALL_SENSITIVITY - #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_TO_MIN - #define Y_MAX_PIN P1_25 // E1DET - #else - #define Y_MIN_PIN P1_25 // E1DET - #endif -#elif ENABLED(Y_DUAL_ENDSTOPS) - #ifndef Y_MIN_PIN - #define Y_MIN_PIN P1_28 // Y-STOP - #endif - #ifndef Y_MAX_PIN - #define Y_MAX_PIN P1_25 // E1DET - #endif -#else - #define Y_STOP_PIN P1_28 // Y-STOP -#endif - -#ifdef Z_STALL_SENSITIVITY +#define X_STOP_PIN X_DIAG_PIN +#define X_OTHR_PIN P1_26 // E0DET +#define Y_STOP_PIN Y_DIAG_PIN +#define Y_OTHR_PIN P1_25 // E1DET +#ifndef Z_STOP_PIN #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_TO_MIN - #define Z_MAX_PIN P1_00 // PWRDET - #else - #define Z_MIN_PIN P1_00 // PWRDET - #endif -#elif ENABLED(Z_MULTI_ENDSTOPS) - #ifndef Z_MIN_PIN - #define Z_MIN_PIN P1_27 // Z-STOP - #endif - #ifndef Z_MAX_PIN - #define Z_MAX_PIN P1_00 // PWRDET - #endif -#else - #ifndef Z_STOP_PIN - #define Z_STOP_PIN P1_27 // Z-STOP - #endif #endif +#define Z_OTHR_PIN P1_00 // PWRDET // // Z Probe (when not Z_MIN_PIN) diff --git a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h index 9b1258bec2..d3451665ac 100644 --- a/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h +++ b/Marlin/src/pins/lpc1768/pins_MKS_SGEN_L.h @@ -51,41 +51,12 @@ // // Limit Switches // -#ifdef X_STALL_SENSITIVITY - #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_TO_MIN - #define X_MAX_PIN P1_28 // X+ - #else - #define X_MIN_PIN P1_28 // X+ - #endif -#else - #define X_MIN_PIN P1_29 // X- - #define X_MAX_PIN P1_28 // X+ -#endif - -#ifdef Y_STALL_SENSITIVITY - #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_TO_MIN - #define Y_MAX_PIN P1_26 // Y+ - #else - #define Y_MIN_PIN P1_26 // Y+ - #endif -#else - #define Y_MIN_PIN P1_27 // Y- - #define Y_MAX_PIN P1_26 // Y+ -#endif - -#ifdef Z_STALL_SENSITIVITY - #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_TO_MIN - #define Z_MAX_PIN P1_24 // Z+ - #else - #define Z_MIN_PIN P1_24 // Z+ - #endif -#else - #define Z_MIN_PIN P1_25 // Z- - #define Z_MAX_PIN P1_24 // Z+ -#endif +#define X_STOP_PIN X_DIAG_PIN +#define X_OTHR_PIN P1_28 // X+ +#define Y_STOP_PIN Y_DIAG_PIN +#define Y_OTHR_PIN P1_26 // Y+ +#define Z_STOP_PIN Z_DIAG_PIN +#define Z_OTHR_PIN P1_24 // Z+ // // Z Probe (when not Z_MIN_PIN) diff --git a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h index eb2f31cbcb..f98449ff53 100644 --- a/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h +++ b/Marlin/src/pins/lpc1769/pins_MKS_SGEN_L_V2.h @@ -59,41 +59,12 @@ // // Limit Switches // -#if X_STALL_SENSITIVITY - #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_TO_MIN - #define X_MAX_PIN P1_28 // X+ - #else - #define X_MIN_PIN P1_28 // X+ - #endif -#else - #define X_MIN_PIN P1_29 // X- - #define X_MAX_PIN P1_28 // X+ -#endif - -#if Y_STALL_SENSITIVITY - #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_TO_MIN - #define Y_MAX_PIN P1_26 // Y+ - #else - #define Y_MIN_PIN P1_26 // Y+ - #endif -#else - #define Y_MIN_PIN P1_27 // Y- - #define Y_MAX_PIN P1_26 // Y+ -#endif - -#if Z_STALL_SENSITIVITY - #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_TO_MIN - #define Z_MAX_PIN P1_24 // Z+ - #else - #define Z_MIN_PIN P1_24 // Z+ - #endif -#else - #define Z_MIN_PIN P1_25 // Z- - #define Z_MAX_PIN P1_24 // Z+ -#endif +#define X_STOP_PIN X_DIAG_PIN // X- +#define X_OTHR_PIN P1_28 // X+ +#define Y_STOP_PIN Y_DIAG_PIN // Y- +#define Y_OTHR_PIN P1_26 // Y+ +#define Z_STOP_PIN Z_DIAG_PIN // Z- +#define Z_OTHR_PIN P1_24 // Z+ // // Z Probe (when not Z_MIN_PIN) diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 7b2daae1ea..4a05b72a23 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -65,57 +65,6 @@ #define HAS_FREE_AUX2_PINS 1 #endif -// -// Check for additional used endstop pins -// -#ifndef X_MIN_PIN - #define X_MIN_PIN 1001 -#endif -#ifndef Y_MIN_PIN - #define Y_MIN_PIN 1002 -#endif -#ifndef Z_MIN_PIN - #define Z_MIN_PIN 1003 -#endif -#ifndef X_MAX_PIN - #define X_MAX_PIN 1004 -#endif -#ifndef Y_MAX_PIN - #define Y_MAX_PIN 1005 -#endif -#ifndef Z_MAX_PIN - #define Z_MAX_PIN 1006 -#endif -#define _ENDSTOP_IS_ANY(P) (HAS_EXTRA_ENDSTOPS && (X2_STOP_PIN == P || Y2_STOP_PIN == P || Z2_STOP_PIN == P || Z3_STOP_PIN == P || Z4_STOP_PIN == P)) -#if ENABLED(DUAL_X_CARRIAGE) || _ENDSTOP_IS_ANY(X_MIN_PIN) || _ENDSTOP_IS_ANY(X_MAX_PIN) - #define NEEDS_X_MINMAX 1 -#endif -#if _ENDSTOP_IS_ANY(Y_MIN_PIN) || _ENDSTOP_IS_ANY(Y_MAX_PIN) - #define NEEDS_Y_MINMAX 1 -#endif -#if _ENDSTOP_IS_ANY(Z_MIN_PIN) || _ENDSTOP_IS_ANY(Z_MAX_PIN) || ALL(Z_HOME_TO_MAX, Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) - #define NEEDS_Z_MINMAX 1 -#endif -#undef _ENDSTOP_IS_ANY -#if X_MIN_PIN > 1000 - #undef X_MIN_PIN -#endif -#if Y_MIN_PIN > 1000 - #undef Y_MIN_PIN -#endif -#if Z_MIN_PIN > 1000 - #undef Z_MIN_PIN -#endif -#if X_MAX_PIN > 1000 - #undef X_MAX_PIN -#endif -#if Y_MAX_PIN > 1000 - #undef Y_MAX_PIN -#endif -#if Z_MAX_PIN > 1000 - #undef Z_MAX_PIN -#endif - // Test the target within the included pins file #ifdef __MARLIN_DEPS__ #define NOT_TARGET(V...) 0 diff --git a/Marlin/src/pins/pins_postprocess.h b/Marlin/src/pins/pins_postprocess.h index a18c099196..2c29cf4d8c 100644 --- a/Marlin/src/pins/pins_postprocess.h +++ b/Marlin/src/pins/pins_postprocess.h @@ -604,14 +604,30 @@ #define NUM_SERVO_PLUGS 0 #endif -// Only used within pins files -#undef NEEDS_X_MINMAX -#undef NEEDS_Y_MINMAX -#undef NEEDS_Z_MINMAX +/** + * Endstop Pins + * + * The general idea is to provide STOP and MIN|MAX pins as needed... + * + * - Standard Homing : X_STOP_PIN with alias X_(MIN|MAX)_PIN. Same for Y, Z, etc. + * - DUAL_X_CARRIAGE : Asserts both X_MIN_PIN and X_MAX_PIN must be defined. + * - X_DUAL_ENDSTOPS : Also define X2_STOP_PIN with alias X2_(MIN|MAX)_PIN. + * - Y_DUAL_ENDSTOPS : Also define Y2_STOP_PIN with alias Y2_(MIN|MAX)_PIN. + * - Z_MULTI_ENDSTOPS : Also define Z2_STOP_PIN with alias Z2_(MIN|MAX)_PIN. Same for Z3, Z4. + * + * Pins files should define pins according to usability: + * - Define X_STOP_PIN for boards with a preferred endstop plug, including Sensorless. + * - Define X_OTHR_PIN for the "other" endstop pin on the axis. + * - Define X_MIN_PIN and/or X_MAX_PIN as preferred connectors. + * - Allow user override of these pins for easier swapping. + * + * See also Conditionals-5-post.h >> "Endstop and probe flags" + */ // // Assign endstop pins, with handling for boards that have only 3 connectors // + #if HAS_X_AXIS #ifdef X_STOP_PIN #if X_HOME_TO_MIN @@ -624,8 +640,19 @@ #elif X_HOME_TO_MAX #define X_STOP_PIN X_MAX_PIN #endif - #if !defined(X2_STOP_PIN) && ENABLED(X_DUAL_ENDSTOPS) && PIN_EXISTS(X_STOP) - #define X2_STOP_PIN X_STOP_PIN + #if ENABLED(X_DUAL_ENDSTOPS) && PIN_EXISTS(X_STOP) + #ifndef X_MIN_PIN + #define X_MIN_PIN X_STOP_PIN + #endif + #ifndef X2_STOP_PIN + #define X2_STOP_PIN X_STOP_PIN + #endif + #endif + #if !defined(X_MIN_PIN) && X_HOME_TO_MAX && defined(X_OTHR_PIN) + #define X_MIN_PIN X_OTHR_PIN + #endif + #if !defined(X_MAX_PIN) && X_HOME_TO_MIN && defined(X_OTHR_PIN) + #define X_MAX_PIN X_OTHR_PIN #endif #endif @@ -641,8 +668,19 @@ #elif Y_HOME_TO_MAX #define Y_STOP_PIN Y_MAX_PIN #endif - #if !defined(Y2_STOP_PIN) && ENABLED(Y_DUAL_ENDSTOPS) && PIN_EXISTS(Y_STOP) - #define Y2_STOP_PIN Y_STOP_PIN + #if ENABLED(Y_DUAL_ENDSTOPS) && PIN_EXISTS(Y_STOP) + #ifndef Y_MIN_PIN + #define Y_MIN_PIN Y_STOP_PIN + #endif + #ifndef Y2_STOP_PIN + #define Y2_STOP_PIN Y_STOP_PIN + #endif + #endif + #if !defined(Y_MIN_PIN) && Y_HOME_TO_MAX && defined(Y_OTHR_PIN) + #define Y_MIN_PIN Y_OTHR_PIN + #endif + #if !defined(Y_MAX_PIN) && Y_HOME_TO_MIN && defined(Y_OTHR_PIN) + #define Y_MAX_PIN Y_OTHR_PIN #endif #endif @@ -654,6 +692,12 @@ #define Z_MAX_PIN Z_STOP_PIN #endif #endif + #if !defined(Z_MIN_PIN) && Z_HOME_TO_MAX && defined(Z_OTHR_PIN) + #define Z_MIN_PIN Z_OTHR_PIN + #endif + #if !defined(Z_MAX_PIN) && Z_HOME_TO_MIN && defined(Z_OTHR_PIN) + #define Z_MAX_PIN Z_OTHR_PIN + #endif #if ENABLED(Z_MULTI_ENDSTOPS) #if ((Z_HOME_TO_MIN && !defined(Z2_MIN_PIN)) || (Z_HOME_TO_MAX && !defined(Z2_MAX_PIN))) && !defined(Z2_STOP_PIN) #error "Z2_STOP_PIN is required for Z_MULTI_ENDSTOPS. Define Z2_STOP_PIN in Configuration_adv.h." diff --git a/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h b/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h index 98a16764af..ff36b4ac54 100644 --- a/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h +++ b/Marlin/src/pins/rambo/pins_EINSY_RAMBO.h @@ -40,7 +40,9 @@ #error "For EinsyRambo you must set all *_DRIVER_TYPE to TMC2130 in Configuration.h." #endif -// TMC2130 Diag Pins (currently just for reference) +// +// Trinamic TMC2130 distinct DIAG pins +// #define X_DIAG_PIN 64 #define Y_DIAG_PIN 69 #define Z_DIAG_PIN 68 @@ -55,31 +57,31 @@ // SERVO0_PIN and Z_MIN_PIN configuration for BLTOUCH sensor when combined with SENSORLESS_HOMING. // -#if DISABLED(SENSORLESS_HOMING) - - #define X_STOP_PIN 12 - #define Y_STOP_PIN 11 - #define Z_STOP_PIN 10 - -#else +#if ENABLED(SENSORLESS_HOMING) #define X_STOP_PIN X_DIAG_PIN #define Y_STOP_PIN Y_DIAG_PIN #if ENABLED(BLTOUCH) + #define SERVO0_PIN 10 // PROBE-S #define Z_STOP_PIN 11 // Y-MIN - #define SERVO0_PIN 10 // Z-MIN #else - #define Z_STOP_PIN 10 + #define Z_STOP_PIN 10 // PROBE-S #endif +#else + + #define X_STOP_PIN 12 // X-MIN + #define Y_STOP_PIN 11 // Y-MIN + #define Z_STOP_PIN 10 // PROBE-S + #endif // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 10 + #define Z_MIN_PROBE_PIN 10 // PROBE-S #endif // diff --git a/Marlin/src/pins/rambo/pins_EINSY_RETRO.h b/Marlin/src/pins/rambo/pins_EINSY_RETRO.h index ca681b8174..99cee17cc1 100644 --- a/Marlin/src/pins/rambo/pins_EINSY_RETRO.h +++ b/Marlin/src/pins/rambo/pins_EINSY_RETRO.h @@ -53,29 +53,20 @@ // SERVO0_PIN and Z_MIN_PIN configuration for BLTOUCH sensor when combined with SENSORLESS_HOMING. // -#if DISABLED(SENSORLESS_HOMING) - - #define X_MIN_PIN 12 // X- - #define Y_MIN_PIN 11 // Y- - #define X_MAX_PIN 81 // X+ - #define Y_MAX_PIN 57 // Y+ - -#else +#if ENABLED(SENSORLESS_HOMING) + #define X_STOP_PIN X_DIAG_PIN #if X_HOME_TO_MIN - #define X_MIN_PIN X_DIAG_PIN - #define X_MAX_PIN 81 // X+ + #define X_OTHR_PIN 81 // X+ #else - #define X_MIN_PIN 12 // X- - #define X_MAX_PIN X_DIAG_PIN + #define X_OTHR_PIN 12 // X- #endif + #define Y_STOP_PIN Y_DIAG_PIN #if Y_HOME_TO_MIN - #define Y_MIN_PIN Y_DIAG_PIN - #define Y_MAX_PIN 57 // Y+ + #define Y_OTHR_PIN 57 // Y+ #else - #define Y_MIN_PIN 11 // Y- - #define Y_MAX_PIN Y_DIAG_PIN + #define Y_OTHR_PIN 11 // Y- #endif #if ENABLED(BLTOUCH) @@ -83,9 +74,16 @@ #define SERVO0_PIN 10 // Z- #endif +#else + + #define X_MIN_PIN 12 // X- + #define Y_MIN_PIN 11 // Y- + #define X_MAX_PIN 81 // X+ + #define Y_MAX_PIN 57 // Y+ + #endif -#define Z_MAX_PIN 7 +#define Z_MAX_PIN 7 // Z+ #ifndef Z_MIN_PIN #define Z_MIN_PIN 10 // Z- #endif @@ -94,7 +92,7 @@ // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 10 + #define Z_MIN_PROBE_PIN 10 // Z- #endif // diff --git a/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h b/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h index d3c921a5f6..7c01c8aba8 100644 --- a/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h +++ b/Marlin/src/pins/ramps/pins_TRIGORILLA_14.h @@ -120,7 +120,7 @@ #define Y_STOP_PIN 42 // AUX (1) #define Z_STOP_PIN 43 // AUX (2) #ifndef Z2_STOP_PIN - #define Z2_STOP_PIN 18 // Z- + #define Z2_STOP_PIN 18 // Z- #endif #ifndef Z_MIN_PROBE_PIN diff --git a/Marlin/src/pins/sam/pins_ARCHIM2.h b/Marlin/src/pins/sam/pins_ARCHIM2.h index 2d0a42c03d..38722326cd 100644 --- a/Marlin/src/pins/sam/pins_ARCHIM2.h +++ b/Marlin/src/pins/sam/pins_ARCHIM2.h @@ -71,20 +71,18 @@ #define E0_DIAG_PIN 78 // PB23 #define E1_DIAG_PIN 25 // PD0 + #define X_STOP_PIN X_DIAG_PIN #if X_HOME_TO_MIN - #define X_MIN_PIN X_DIAG_PIN - #define X_MAX_PIN 32 + #define X_OTHR_PIN 32 // PD10 MAX ES1 #else - #define X_MIN_PIN 14 - #define X_MAX_PIN X_DIAG_PIN + #define X_OTHR_PIN 14 // PD4 MIN ES1 #endif + #define Y_STOP_PIN Y_DIAG_PIN #if Y_HOME_TO_MIN - #define Y_MIN_PIN Y_DIAG_PIN - #define Y_MAX_PIN 15 + #define Y_OTHR_PIN 15 // PD5 MAX ES2 #else - #define Y_MIN_PIN 29 - #define Y_MAX_PIN Y_DIAG_PIN + #define Y_OTHR_PIN 29 // PD6 MIN ES2 #endif #else @@ -103,7 +101,7 @@ // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 32 + #define Z_MIN_PROBE_PIN 32 // PD10 MAX ES1 #endif // diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D_V9.h b/Marlin/src/pins/stm32f1/pins_CHITU3D_V9.h index 0d02e1d5d9..7c6b75a082 100755 --- a/Marlin/src/pins/stm32f1/pins_CHITU3D_V9.h +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D_V9.h @@ -23,11 +23,11 @@ #define BOARD_INFO_NAME "Chitu3D V9" -#define Z_STOP_PIN PA14 - #define Z2_ENABLE_PIN PF3 #define Z2_STEP_PIN PF5 #define Z2_DIR_PIN PF1 + +#define Z_STOP_PIN PA14 #define Z2_STOP_PIN PA13 #ifndef Z_MIN_PROBE_PIN diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V521.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V521.h index 60a0062621..0717506fff 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V521.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V521.h @@ -67,11 +67,11 @@ // // Limit Switches // -#define X_STOP_PIN PD10 // X -#define X2_STOP_PIN PE15 // X2 +#define X_MIN_PIN PD10 // X +#define X_MAX_PIN PE15 // X2 #define Y_STOP_PIN PE0 // Y -#define Z_STOP_PIN PE1 // Z -#define Z2_STOP_PIN PE2 // Z2 +#define Z_MIN_PIN PE1 // Z +#define Z_MAX_PIN PE2 // Z2 #ifndef Z_MIN_PROBE_PIN #define Z_MIN_PROBE_PIN PD12 // BLTouch IN diff --git a/Marlin/src/pins/stm32f4/pins_ARTILLERY_RUBY.h b/Marlin/src/pins/stm32f4/pins_ARTILLERY_RUBY.h index 8b60b234cd..6dd25ad464 100644 --- a/Marlin/src/pins/stm32f4/pins_ARTILLERY_RUBY.h +++ b/Marlin/src/pins/stm32f4/pins_ARTILLERY_RUBY.h @@ -40,27 +40,10 @@ // // Limit Switches // -#if (X_HOME_DIR == 1) - #define X_MIN_PIN -1 - #define X_MAX_PIN PA2 -#else - #define X_MIN_PIN PA2 - #define X_MAX_PIN -1 -#endif -#if (Y_HOME_DIR == 1) - #define Y_MIN_PIN -1 - #define Y_MAX_PIN PA1 -#else - #define Y_MIN_PIN PA1 - #define Y_MAX_PIN -1 -#endif -#if (Z_HOME_DIR == 1) - #define Z_MIN_PIN PC2 - #define Z_MAX_PIN PA0 -#else - #define Z_MIN_PIN PA0 - #define Z_MAX_PIN PC2 -#endif +#define X_STOP_PIN PA2 +#define Y_STOP_PIN PA1 +#define Z_STOP_PIN PA0 +#define Z_OTHR_PIN PC2 // // Steppers diff --git a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h index be98edd605..1d3975ab8f 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h @@ -68,38 +68,24 @@ // #ifdef X_STALL_SENSITIVITY #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_TO_MIN - #define X_MAX_PIN E0_DIAG_PIN // X+ - #else - #define X_MIN_PIN E0_DIAG_PIN // X+ - #endif + #define X_OTHR_PIN PG14 // X+ #else - #define X_MIN_PIN X_DIAG_PIN // X- - #define X_MAX_PIN E0_DIAG_PIN // X+ + #define X_MIN_PIN PF2 // X- + #define X_MAX_PIN PG14 // X+ #endif - #ifdef Y_STALL_SENSITIVITY #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_TO_MIN - #define Y_MAX_PIN E1_DIAG_PIN // Y+ - #else - #define Y_MIN_PIN E1_DIAG_PIN // Y+ - #endif + #define Y_OTHR_PIN PG9 // Y+ #else - #define Y_MIN_PIN Y_DIAG_PIN // Y- - #define Y_MAX_PIN E1_DIAG_PIN // Y+ + #define Y_MIN_PIN PC13 // Y- + #define Y_MAX_PIN PG9 // Y+ #endif - #ifdef Z_STALL_SENSITIVITY #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_TO_MIN - #define Z_MAX_PIN E2_DIAG_PIN // Z+ - #else - #define Z_MIN_PIN E2_DIAG_PIN // Z+ - #endif + #define Z_OTHR_PIN PD3 // Z+ #else - #define Z_MIN_PIN Z_DIAG_PIN // Z- - #define Z_MAX_PIN E2_DIAG_PIN // Z+ + #define Z_MIN_PIN PE0 // Z- + #define Z_MAX_PIN PD3 // Z+ #endif // diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h index ac96042b23..9388c8a1f4 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h @@ -65,59 +65,12 @@ // // Limit Switches // -#ifdef X_STALL_SENSITIVITY - #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_TO_MIN - #define X_MAX_PIN E0_DIAG_PIN // E0DET - #else - #define X_MIN_PIN E0_DIAG_PIN // E0DET - #endif -#elif NEEDS_X_MINMAX - #ifndef X_MIN_PIN - #define X_MIN_PIN X_DIAG_PIN // X-STOP - #endif - #ifndef X_MAX_PIN - #define X_MAX_PIN E0_DIAG_PIN // E0DET - #endif -#else - #define X_STOP_PIN X_DIAG_PIN // X-STOP -#endif - -#ifdef Y_STALL_SENSITIVITY - #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_TO_MIN - #define Y_MAX_PIN E1_DIAG_PIN // E1DET - #else - #define Y_MIN_PIN E1_DIAG_PIN // E1DET - #endif -#elif NEEDS_Y_MINMAX - #ifndef Y_MIN_PIN - #define Y_MIN_PIN Y_DIAG_PIN // Y-STOP - #endif - #ifndef Y_MAX_PIN - #define Y_MAX_PIN E1_DIAG_PIN // E1DET - #endif -#else - #define Y_STOP_PIN Y_DIAG_PIN // Y-STOP -#endif - -#ifdef Z_STALL_SENSITIVITY - #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_TO_MIN - #define Z_MAX_PIN E2_DIAG_PIN // PWRDET - #else - #define Z_MIN_PIN E2_DIAG_PIN // PWRDET - #endif -#elif NEEDS_Z_MINMAX - #ifndef Z_MIN_PIN - #define Z_MIN_PIN Z_DIAG_PIN // Z-STOP - #endif - #ifndef Z_MAX_PIN - #define Z_MAX_PIN E2_DIAG_PIN // PWRDET - #endif -#else - #define Z_STOP_PIN Z_DIAG_PIN // Z-STOP -#endif +#define X_STOP_PIN X_DIAG_PIN // X-STOP +#define Y_STOP_PIN Y_DIAG_PIN // Y-STOP +#define Z_STOP_PIN Z_DIAG_PIN // Z-STOP +#define X_OTHR_PIN E0_DIAG_PIN // E0DET +#define Y_OTHR_PIN E1_DIAG_PIN // E1DET +#define Z_OTHR_PIN E2_DIAG_PIN // E2DET // // Z Probe (when not Z_MIN_PIN) diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h index 943c0ed761..5b42a05c70 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_PRO_common.h @@ -70,41 +70,12 @@ // // Limit Switches // -#ifdef X_STALL_SENSITIVITY - #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_TO_MIN - #define X_MAX_PIN PE15 // E0 - #else - #define X_MIN_PIN PE15 // E0 - #endif -#else - #define X_MIN_PIN PB10 // X- - #define X_MAX_PIN PE15 // E0 -#endif - -#ifdef Y_STALL_SENSITIVITY - #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_TO_MIN - #define Y_MAX_PIN PE10 // E1 - #else - #define Y_MIN_PIN PE10 // E1 - #endif -#else - #define Y_MIN_PIN PE12 // Y- - #define Y_MAX_PIN PE10 // E1 -#endif - -#ifdef Z_STALL_SENSITIVITY - #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_TO_MIN - #define Z_MAX_PIN PG5 // E2 - #else - #define Z_MIN_PIN PG5 // E2 - #endif -#else - #define Z_MIN_PIN PG8 // Z- - #define Z_MAX_PIN PG5 // E2 -#endif +#define X_STOP_PIN X_DIAG_PIN // X- +#define Y_STOP_PIN Y_DIAG_PIN // Y- +#define Z_STOP_PIN Z_DIAG_PIN // Z- +#define X_OTHR_PIN PE15 // E0 +#define Y_OTHR_PIN PE10 // E1 +#define Z_OTHR_PIN PG5 // E2 // // Z Probe must be this pin diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h index 51b27efa39..fa0e1ed516 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h @@ -71,61 +71,12 @@ // // Limit Switches // -#ifdef X_STALL_SENSITIVITY - #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_TO_MIN - #define X_MAX_PIN PC2 // E0DET - #else - #define X_MIN_PIN PC2 // E0DET - #endif -#elif ENABLED(X_DUAL_ENDSTOPS) - #ifndef X_MIN_PIN - #define X_MIN_PIN PC1 // X-STOP - #endif - #ifndef X_MAX_PIN - #define X_MAX_PIN PC2 // E0DET - #endif -#else - #define X_STOP_PIN PC1 // X-STOP -#endif - -#ifdef Y_STALL_SENSITIVITY - #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_TO_MIN - #define Y_MAX_PIN PA0 // E1DET - #else - #define Y_MIN_PIN PA0 // E1DET - #endif -#elif ENABLED(Y_DUAL_ENDSTOPS) - #ifndef Y_MIN_PIN - #define Y_MIN_PIN PC3 // Y-STOP - #endif - #ifndef Y_MAX_PIN - #define Y_MAX_PIN PA0 // E1DET - #endif -#else - #define Y_STOP_PIN PC3 // Y-STOP -#endif - -#ifdef Z_STALL_SENSITIVITY - #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_TO_MIN - #define Z_MAX_PIN PC15 // PWRDET - #else - #define Z_MIN_PIN PC15 // PWRDET - #endif -#elif ENABLED(Z_MULTI_ENDSTOPS) - #ifndef Z_MIN_PIN - #define Z_MIN_PIN PC0 // Z-STOP - #endif - #ifndef Z_MAX_PIN - #define Z_MAX_PIN PC15 // PWRDET - #endif -#else - #ifndef Z_STOP_PIN - #define Z_STOP_PIN PC0 // Z-STOP - #endif -#endif +#define X_STOP_PIN X_DIAG_PIN // X-STOP +#define Y_STOP_PIN Y_DIAG_PIN // Y-STOP +#define Z_STOP_PIN Z_DIAG_PIN // Z-STOP +#define X_OTHR_PIN PC2 // E0DET +#define Y_OTHR_PIN PA0 // E1DET +#define Z_OTHR_PIN PC15 // PWRDET // // Z Probe (when not Z_MIN_PIN) diff --git a/Marlin/src/pins/stm32f4/pins_I3DBEEZ9.h b/Marlin/src/pins/stm32f4/pins_I3DBEEZ9.h index 1620c86bed..13dc536cfa 100644 --- a/Marlin/src/pins/stm32f4/pins_I3DBEEZ9.h +++ b/Marlin/src/pins/stm32f4/pins_I3DBEEZ9.h @@ -77,53 +77,12 @@ // // Limit Switches // -#ifdef X_STALL_SENSITIVITY - #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_TO_MIN - #define X_MAX_PIN PE15 // E0 - #else - #define X_MIN_PIN PE15 // E0 - #endif -#else - #define X_MIN_PIN PB10 // X- - #define X_MAX_PIN PE15 // E0 -#endif - -#ifdef Y_STALL_SENSITIVITY - #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_TO_MIN - #define Y_MAX_PIN PE10 // E1 - #else - #define Y_MIN_PIN PE10 // E1 - #endif -#else - #define Y_MIN_PIN PE12 // Y- - #define Y_MAX_PIN PE10 // E1 -#endif - -#ifdef Z_STALL_SENSITIVITY - #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_TO_MIN - #define Z_MAX_PIN PG5 // E2 - #else - #define Z_MIN_PIN PG5 // E2 - #endif -#else - #define Z_MIN_PIN PG8 // Z- - #define Z_MAX_PIN PG5 // E2 -#endif - -#ifdef Z2_STALL_SENSITIVITY - #define Z2_STOP_PIN E1_DIAG_PIN - #if Z2_HOME_TO_MIN - #define Z2_MAX_PIN PD0 // E3 - #else - #define Z2_MIN_PIN PD0 // E3 - #endif -#else - #define Z2_MIN_PIN PD0 // Z2- [E3] - #define Z2_MAX_PIN PD6 // E4 -#endif +#define X_STOP_PIN X_DIAG_PIN // X- +#define Y_STOP_PIN Y_DIAG_PIN // Y- +#define Z_STOP_PIN Z_DIAG_PIN // Z- +#define X_OTHR_PIN PE15 // E0 +#define Y_OTHR_PIN PE10 // E1 +#define Z_OTHR_PIN PG5 // E2 // // Z Probe must be this pin diff --git a/Marlin/src/pins/stm32f4/pins_MELLOW_FLY_E3_V2.h b/Marlin/src/pins/stm32f4/pins_MELLOW_FLY_E3_V2.h index 4626176a99..d6b5c31bbf 100644 --- a/Marlin/src/pins/stm32f4/pins_MELLOW_FLY_E3_V2.h +++ b/Marlin/src/pins/stm32f4/pins_MELLOW_FLY_E3_V2.h @@ -66,24 +66,14 @@ // // Limit Switches // -#ifdef X_STALL_SENSITIVITY - #define X_STOP_PIN X_DIAG_PIN -#else - #define X_STOP_PIN PE7 // X-STOP +#ifndef X_STOP_PIN + #define X_STOP_PIN X_DIAG_PIN // X-STOP #endif - -#ifdef Y_STALL_SENSITIVITY - #define Y_STOP_PIN Y_DIAG_PIN -#else - #define Y_STOP_PIN PE8 // Y-STOP +#ifndef Y_STOP_PIN + #define Y_STOP_PIN Y_DIAG_PIN // Y-STOP #endif - -#ifdef Z_STALL_SENSITIVITY - #define Z_STOP_PIN Z_DIAG_PIN -#else - #ifndef Z_STOP_PIN - #define Z_STOP_PIN PE9 // Z-STOP - #endif +#ifndef Z_STOP_PIN + #define Z_STOP_PIN Z_DIAG_PIN // Z-STOP #endif // diff --git a/Marlin/src/pins/stm32f4/pins_MKS_SKIPR_V1_0.h b/Marlin/src/pins/stm32f4/pins_MKS_SKIPR_V1_0.h index b0eb8bf24f..b060ac56e5 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_SKIPR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_SKIPR_V1_0.h @@ -56,49 +56,15 @@ // // Limit Switches // -#ifdef X_STALL_SENSITIVITY - #define X_STOP_PIN X_DIAG_PIN // X- -#elif NEEDS_X_MINMAX - #ifndef X_MIN_PIN - #define X_MIN_PIN X_DIAG_PIN // X- - #endif - #ifndef X_MAX_PIN - #define X_MAX_PIN E0_DIAG_PIN // MT-DET - #endif -#else - #define X_STOP_PIN X_DIAG_PIN // X- -#endif +#define X_STOP_PIN X_DIAG_PIN // X- +#define Y_STOP_PIN Y_DIAG_PIN // Y- +#define Z_STOP_PIN Z_DIAG_PIN // Z+ +#define X_OTHR_PIN E0_DIAG_PIN // MT-DET +#define Y_OTHR_PIN E1_DIAG_PIN // NEOPIXEL +#define Z_OTHR_PIN E2_DIAG_PIN // PWRDET -#ifdef Y_STALL_SENSITIVITY - #define Y_STOP_PIN Y_DIAG_PIN // Y- -#elif NEEDS_Y_MINMAX - #ifndef Y_MIN_PIN - #define Y_MIN_PIN Y_DIAG_PIN // Y- - #endif - #ifndef Y_MAX_PIN - #define Y_MAX_PIN E1_DIAG_PIN // NEOPIXEL - #endif -#else - #define Y_STOP_PIN Y_DIAG_PIN // Y- -#endif - -#ifdef Z_STALL_SENSITIVITY - #define Z_STOP_PIN Z_DIAG_PIN // Z- -#elif NEEDS_Z_MINMAX - #ifndef Z_MIN_PIN - #define Z_MIN_PIN Z_DIAG_PIN // Z- - #endif - #ifndef Z_MAX_PIN - #define Z_MAX_PIN E2_DIAG_PIN // Z+ - #endif -#else - #define Z_STOP_PIN Z_DIAG_PIN // Z- -#endif - -#if DISABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) || ENABLED(USE_PROBE_FOR_Z_HOMING) - #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN E2_DIAG_PIN // defaults to 'Z+' connector - #endif +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN E2_DIAG_PIN // Z+ #endif // diff --git a/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h b/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h index 7cf8d813a0..8aeec7bc95 100644 --- a/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h +++ b/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h @@ -36,21 +36,44 @@ #error "RemRam only supports 1 hotend / E stepper." #endif +// +// Timers +// +#define STEP_TIMER 2 + +// +// Servos +// +#define SERVO0_PIN 26 // PWM_EXT1 +#define SERVO1_PIN 27 // PWM_EXT2 + // // Limit Switches // -#if DISABLED(SENSORLESS_HOMING) - #define X_MIN_PIN 58 - #define X_MAX_PIN 59 - #define Y_MIN_PIN 60 - #define Y_MAX_PIN 61 - #define Z_MAX_PIN 63 +#define X_DIAG_PIN 36 +#define Y_DIAG_PIN 39 +#define Z_DIAG_PIN 42 + +// Direct endstop pin references +#define _X_MIN_PIN 58 +#define _X_MAX_PIN 59 +#define _Y_MIN_PIN 60 +#define _Y_MAX_PIN 61 +#define _Z_MIN_PIN 62 +#define _Z_MAX_PIN 63 + +#if ENABLED(SENSORLESS_HOMING) + #define X_STOP_PIN X_DIAG_PIN + #define Y_STOP_PIN Y_DIAG_PIN + #define Z_STOP_PIN Z_DIAG_PIN #else - #define X_STOP_PIN 36 - #define Y_STOP_PIN 39 - #define Z_MAX_PIN 42 + #define X_MIN_PIN _X_MIN_PIN + #define X_MAX_PIN _X_MAX_PIN + #define Y_MIN_PIN _Y_MIN_PIN + #define Y_MAX_PIN _Y_MAX_PIN + #define Z_MIN_PIN _Z_MIN_PIN + #define Z_MAX_PIN _Z_MAX_PIN #endif -#define Z_MIN_PIN 62 // // Z Probe (when not Z_MIN_PIN) @@ -105,19 +128,17 @@ #endif // -// Servos +// SD Card // -#define SERVO0_PIN 26 // PWM_EXT1 -#define SERVO1_PIN 27 // PWM_EXT2 - +#define SD_DETECT_PIN 56 // SD_CARD_DET #define SD_SS_PIN 57 // Onboard SD card reader //#define SD_SS_PIN 9 // LCD SD card reader + #define LED_PIN 21 // STATUS_LED // // LCD / Controller // -#define SD_DETECT_PIN 56 // SD_CARD_DET #define BEEPER_PIN 46 // LCD_BEEPER #define LCD_PINS_RS 49 // LCD_RS #define LCD_PINS_EN 48 // LCD_EN @@ -128,9 +149,3 @@ #define BTN_EN1 54 // BTN_EN1 #define BTN_EN2 55 // BTN_EN2 #define BTN_ENC 47 // BTN_ENC - -// -// Timers -// - -#define STEP_TIMER 2 diff --git a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M8P_common.h b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M8P_common.h index 0af45e6645..901f1c8919 100644 --- a/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M8P_common.h +++ b/Marlin/src/pins/stm32g0/pins_BTT_MANTA_M8P_common.h @@ -76,43 +76,11 @@ // // Limit Switches // -#ifdef X_STALL_SENSITIVITY - #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_TO_MIN - #define X_MAX_PIN E0_DIAG_PIN // MIN5 - #else - #define X_MIN_PIN E0_DIAG_PIN // MIN5 - #endif -#elif NEEDS_X_MINMAX - #ifndef X_MIN_PIN - #define X_MIN_PIN X_DIAG_PIN // MIN1 - #endif - #ifndef X_MAX_PIN - #define X_MAX_PIN E0_DIAG_PIN // MIN5 - #endif -#else - #define X_STOP_PIN X_DIAG_PIN // MIN1 -#endif - -#ifdef Y_STALL_SENSITIVITY - #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_TO_MIN - #define Y_MAX_PIN E1_DIAG_PIN // MIN6 - #else - #define Y_MIN_PIN E1_DIAG_PIN // MIN6 - #endif -#elif NEEDS_Y_MINMAX - #ifndef Y_MIN_PIN - #define Y_MIN_PIN Y_DIAG_PIN // MIN2 - #endif - #ifndef Y_MAX_PIN - #define Y_MAX_PIN E1_DIAG_PIN // MIN6 - #endif -#else - #define Y_STOP_PIN Y_DIAG_PIN // MIN2 -#endif - +#define X_STOP_PIN X_DIAG_PIN // MIN1 +#define Y_STOP_PIN Y_DIAG_PIN // MIN2 #define Z_STOP_PIN Z_DIAG_PIN // MIN3 +#define X_OTHR_PIN E0_DIAG_PIN // MIN5 +#define Y_OTHR_PIN E1_DIAG_PIN // MIN6 // // Filament Runout Sensors diff --git a/Marlin/src/pins/stm32g0/pins_BTT_SKRAT_V1_0.h b/Marlin/src/pins/stm32g0/pins_BTT_SKRAT_V1_0.h index 2a112f34b1..e760306780 100644 --- a/Marlin/src/pins/stm32g0/pins_BTT_SKRAT_V1_0.h +++ b/Marlin/src/pins/stm32g0/pins_BTT_SKRAT_V1_0.h @@ -79,61 +79,18 @@ // // Limit Switches // -#ifdef X_STALL_SENSITIVITY - #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_TO_MIN - #define X_MAX_PIN PF4 // E0_DET - #else - #define X_MIN_PIN PF4 // E0_DET - #endif -#elif ENABLED(X_DUAL_ENDSTOPS) - #ifndef X_MIN_PIN - #define X_MIN_PIN PB5 // X-STOP - #endif - #ifndef X_MAX_PIN - #define X_MAX_PIN PF4 // E0_DET - #endif -#else - #define X_STOP_PIN PB5 // X-STOP +#ifndef X_STOP_PIN + #define X_STOP_PIN X_DIAG_PIN // X-STOP #endif - -#ifdef Y_STALL_SENSITIVITY - #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_TO_MIN - #define Y_MAX_PIN PF5 // E1_DET - #else - #define Y_MIN_PIN PF5 // E1_DET - #endif -#elif ENABLED(Y_DUAL_ENDSTOPS) - #ifndef Y_MIN_PIN - #define Y_MIN_PIN PC1 // Y-STOP - #endif - #ifndef Y_MAX_PIN - #define Y_MAX_PIN PF5 // E1_DET - #endif -#else - #define Y_STOP_PIN PC1 // Y-STOP +#ifndef Y_STOP_PIN + #define Y_STOP_PIN Y_DIAG_PIN // Y-STOP #endif - -#ifdef Z_STALL_SENSITIVITY - #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_TO_MIN - #define Z_MAX_PIN PE12 // PWR_DET - #else - #define Z_MIN_PIN PE12 // PWR_DET - #endif -#elif ENABLED(Z_MULTI_ENDSTOPS) - #ifndef Z_MIN_PIN - #define Z_MIN_PIN PC0 // Z-STOP - #endif - #ifndef Z_MAX_PIN - #define Z_MAX_PIN PE12 // PWR_DET - #endif -#else - #ifndef Z_STOP_PIN - #define Z_STOP_PIN PC0 // Z-STOP - #endif +#ifndef Z_STOP_PIN + #define Z_STOP_PIN Z_DIAG_PIN // Z-STOP #endif +#define X_OTHR_PIN PF4 // E0_DET +#define Y_OTHR_PIN E1_DIAG_PIN // E1_DET +#define Z_OTHR_PIN PE12 // PWR_DET // // Z Probe (when not Z_MIN_PIN) diff --git a/Marlin/src/pins/stm32h7/pins_BTT_KRAKEN_V1_0.h b/Marlin/src/pins/stm32h7/pins_BTT_KRAKEN_V1_0.h index 3a0cc346e5..8ed780b6c7 100644 --- a/Marlin/src/pins/stm32h7/pins_BTT_KRAKEN_V1_0.h +++ b/Marlin/src/pins/stm32h7/pins_BTT_KRAKEN_V1_0.h @@ -65,59 +65,12 @@ // // Limit Switches // -#ifdef X_STALL_SENSITIVITY - #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_TO_MIN - #define X_MAX_PIN E0_DIAG_PIN // MIN4 - #else - #define X_MIN_PIN E0_DIAG_PIN // MIN4 - #endif -#elif NEEDS_X_MINMAX - #ifndef X_MIN_PIN - #define X_MIN_PIN X_DIAG_PIN // MIN1 - #endif - #ifndef X_MAX_PIN - #define X_MAX_PIN E0_DIAG_PIN // MIN4 - #endif -#else - #define X_STOP_PIN X_DIAG_PIN // MIN1 -#endif - -#ifdef Y_STALL_SENSITIVITY - #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_TO_MIN - #define Y_MAX_PIN E1_DIAG_PIN // MIN5 - #else - #define Y_MIN_PIN E1_DIAG_PIN // MIN5 - #endif -#elif NEEDS_Y_MINMAX - #ifndef Y_MIN_PIN - #define Y_MIN_PIN Y_DIAG_PIN // MIN2 - #endif - #ifndef Y_MAX_PIN - #define Y_MAX_PIN E1_DIAG_PIN // MIN5 - #endif -#else - #define Y_STOP_PIN Y_DIAG_PIN // MIN2 -#endif - -#ifdef Z_STALL_SENSITIVITY - #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_TO_MIN - #define Z_MAX_PIN E2_DIAG_PIN // MIN6 - #else - #define Z_MIN_PIN E2_DIAG_PIN // MIN6 - #endif -#elif NEEDS_Z_MINMAX - #ifndef Z_MIN_PIN - #define Z_MIN_PIN Z_DIAG_PIN // MIN3 - #endif - #ifndef Z_MAX_PIN - #define Z_MAX_PIN E2_DIAG_PIN // MIN6 - #endif -#else - #define Z_STOP_PIN Z_DIAG_PIN // MIN3 -#endif +#define X_STOP_PIN X_DIAG_PIN // MIN1 +#define Y_STOP_PIN Y_DIAG_PIN // MIN2 +#define Z_STOP_PIN Z_DIAG_PIN // MIN3 +#define X_OTHR_PIN E0_DIAG_PIN // MIN4 +#define Y_OTHR_PIN E1_DIAG_PIN // MIN5 +#define Z_OTHR_PIN E2_DIAG_PIN // MIN6 // // Z Probe (when not Z_MIN_PIN) diff --git a/Marlin/src/pins/stm32h7/pins_BTT_MANTA_M8P_V2_0.h b/Marlin/src/pins/stm32h7/pins_BTT_MANTA_M8P_V2_0.h index 941d6ab068..29e57b42a2 100644 --- a/Marlin/src/pins/stm32h7/pins_BTT_MANTA_M8P_V2_0.h +++ b/Marlin/src/pins/stm32h7/pins_BTT_MANTA_M8P_V2_0.h @@ -64,59 +64,12 @@ // // Limit Switches // -#ifdef X_STALL_SENSITIVITY - #define X_STOP_PIN X_DIAG_PIN // M1-STOP - #if X_HOME_TO_MIN - #define X_MAX_PIN E0_DIAG_PIN // M4-STOP - #else - #define X_MIN_PIN E0_DIAG_PIN // M4-STOP - #endif -#elif NEEDS_X_MINMAX - #ifndef X_MIN_PIN - #define X_MIN_PIN X_DIAG_PIN // M1-STOP - #endif - #ifndef X_MAX_PIN - #define X_MAX_PIN E0_DIAG_PIN // M4-STOP - #endif -#else - #define X_STOP_PIN X_DIAG_PIN // M1-STOP -#endif - -#ifdef Y_STALL_SENSITIVITY - #define Y_STOP_PIN Y_DIAG_PIN // M2-STOP - #if Y_HOME_TO_MIN - #define Y_MAX_PIN E1_DIAG_PIN // M5-STOP - #else - #define Y_MIN_PIN E1_DIAG_PIN // M5-STOP - #endif -#elif NEEDS_Y_MINMAX - #ifndef Y_MIN_PIN - #define Y_MIN_PIN Y_DIAG_PIN // M2-STOP - #endif - #ifndef Y_MAX_PIN - #define Y_MAX_PIN E1_DIAG_PIN // M5-STOP - #endif -#else - #define Y_STOP_PIN Y_DIAG_PIN // M2-STOP -#endif - -#ifdef Z_STALL_SENSITIVITY - #define Z_STOP_PIN Z_DIAG_PIN // M3-STOP - #if Z_HOME_TO_MIN - #define Z_MAX_PIN E2_DIAG_PIN // M6-STOP - #else - #define Z_MIN_PIN E2_DIAG_PIN // M6-STOP - #endif -#elif NEEDS_Z_MINMAX - #ifndef Z_MIN_PIN - #define Z_MIN_PIN Z_DIAG_PIN // M3-STOP - #endif - #ifndef Z_MAX_PIN - #define Z_MAX_PIN E2_DIAG_PIN // M6-STOP - #endif -#else - #define Z_STOP_PIN Z_DIAG_PIN // M3-STOP -#endif +#define X_STOP_PIN X_DIAG_PIN // M1-STOP +#define Y_STOP_PIN Y_DIAG_PIN // M2-STOP +#define Z_STOP_PIN Z_DIAG_PIN // M3-STOP +#define X_OTHR_PIN E0_DIAG_PIN // M4-STOP +#define Y_OTHR_PIN E1_DIAG_PIN // M5-STOP +#define Z_OTHR_PIN E2_DIAG_PIN // M6-STOP // // Z Probe (when not Z_MIN_PIN) diff --git a/Marlin/src/pins/stm32h7/pins_BTT_OCTOPUS_MAX_EZ.h b/Marlin/src/pins/stm32h7/pins_BTT_OCTOPUS_MAX_EZ.h index b995b2269e..a60b3bdf43 100644 --- a/Marlin/src/pins/stm32h7/pins_BTT_OCTOPUS_MAX_EZ.h +++ b/Marlin/src/pins/stm32h7/pins_BTT_OCTOPUS_MAX_EZ.h @@ -59,59 +59,12 @@ // // Limit Switches // -#ifdef X_STALL_SENSITIVITY - #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_TO_MIN - #define X_MAX_PIN E0_DIAG_PIN // M4-DET - #else - #define X_MIN_PIN E0_DIAG_PIN // M4-DET - #endif -#elif NEEDS_X_MINMAX - #ifndef X_MIN_PIN - #define X_MIN_PIN X_DIAG_PIN // X-STOP - #endif - #ifndef X_MAX_PIN - #define X_MAX_PIN E0_DIAG_PIN // M4-DET - #endif -#else - #define X_STOP_PIN X_DIAG_PIN // X-STOP -#endif - -#ifdef Y_STALL_SENSITIVITY - #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_TO_MIN - #define Y_MAX_PIN E1_DIAG_PIN // M5-DET - #else - #define Y_MIN_PIN E1_DIAG_PIN // M5-DET - #endif -#elif NEEDS_Y_MINMAX - #ifndef Y_MIN_PIN - #define Y_MIN_PIN Y_DIAG_PIN // Y-STOP - #endif - #ifndef Y_MAX_PIN - #define Y_MAX_PIN E1_DIAG_PIN // M5-DET - #endif -#else - #define Y_STOP_PIN Y_DIAG_PIN // Y-STOP -#endif - -#ifdef Z_STALL_SENSITIVITY - #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_TO_MIN - #define Z_MAX_PIN E2_DIAG_PIN // PWRDET - #else - #define Z_MIN_PIN E2_DIAG_PIN // PWRDET - #endif -#elif NEEDS_Z_MINMAX - #ifndef Z_MIN_PIN - #define Z_MIN_PIN Z_DIAG_PIN // Z-STOP - #endif - #ifndef Z_MAX_PIN - #define Z_MAX_PIN E2_DIAG_PIN // PWRDET - #endif -#else - #define Z_STOP_PIN Z_DIAG_PIN // Z-STOP -#endif +#define X_STOP_PIN X_DIAG_PIN // M1-STOP +#define Y_STOP_PIN Y_DIAG_PIN // M2-STOP +#define Z_STOP_PIN Z_DIAG_PIN // M3-STOP +#define X_OTHR_PIN E0_DIAG_PIN // M5-STOP +#define Y_OTHR_PIN E1_DIAG_PIN // M6-STOP +#define Z_OTHR_PIN E2_DIAG_PIN // M7-STOP // // Z Probe (when not Z_MIN_PIN) diff --git a/Marlin/src/pins/stm32h7/pins_BTT_OCTOPUS_PRO_V1_common.h b/Marlin/src/pins/stm32h7/pins_BTT_OCTOPUS_PRO_V1_common.h index 8c8cd1d8a1..7339d74376 100644 --- a/Marlin/src/pins/stm32h7/pins_BTT_OCTOPUS_PRO_V1_common.h +++ b/Marlin/src/pins/stm32h7/pins_BTT_OCTOPUS_PRO_V1_common.h @@ -59,59 +59,12 @@ // // Limit Switches // -#ifdef X_STALL_SENSITIVITY - #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_TO_MIN - #define X_MAX_PIN E0_DIAG_PIN // E0DET - #else - #define X_MIN_PIN E0_DIAG_PIN // E0DET - #endif -#elif NEEDS_X_MINMAX - #ifndef X_MIN_PIN - #define X_MIN_PIN X_DIAG_PIN // X-STOP - #endif - #ifndef X_MAX_PIN - #define X_MAX_PIN E0_DIAG_PIN // E0DET - #endif -#else - #define X_STOP_PIN X_DIAG_PIN // X-STOP -#endif - -#ifdef Y_STALL_SENSITIVITY - #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_TO_MIN - #define Y_MAX_PIN E1_DIAG_PIN // E1DET - #else - #define Y_MIN_PIN E1_DIAG_PIN // E1DET - #endif -#elif NEEDS_Y_MINMAX - #ifndef Y_MIN_PIN - #define Y_MIN_PIN Y_DIAG_PIN // Y-STOP - #endif - #ifndef Y_MAX_PIN - #define Y_MAX_PIN E1_DIAG_PIN // E1DET - #endif -#else - #define Y_STOP_PIN Y_DIAG_PIN // Y-STOP -#endif - -#ifdef Z_STALL_SENSITIVITY - #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_TO_MIN - #define Z_MAX_PIN E2_DIAG_PIN // PWRDET - #else - #define Z_MIN_PIN E2_DIAG_PIN // PWRDET - #endif -#elif NEEDS_Z_MINMAX - #ifndef Z_MIN_PIN - #define Z_MIN_PIN Z_DIAG_PIN // Z-STOP - #endif - #ifndef Z_MAX_PIN - #define Z_MAX_PIN E2_DIAG_PIN // PWRDET - #endif -#else - #define Z_STOP_PIN Z_DIAG_PIN // Z-STOP -#endif +#define X_STOP_PIN X_DIAG_PIN // X-STOP +#define Y_STOP_PIN Y_DIAG_PIN // Y-STOP +#define Z_STOP_PIN Z_DIAG_PIN // Z-STOP +#define X_OTHR_PIN E0_DIAG_PIN // E0DET +#define Y_OTHR_PIN E1_DIAG_PIN // E1DET +#define Z_OTHR_PIN E2_DIAG_PIN // E2DET // // Z Probe (when not Z_MIN_PIN) diff --git a/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_common.h b/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_common.h index 7456236669..320d396d76 100644 --- a/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_common.h +++ b/Marlin/src/pins/stm32h7/pins_BTT_SKR_V3_0_common.h @@ -70,61 +70,19 @@ // // Limit Switches // -#ifdef X_STALL_SENSITIVITY - #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_TO_MIN - #define X_MAX_PIN PC2 // E0DET - #else - #define X_MIN_PIN PC2 // E0DET - #endif -#elif ENABLED(X_DUAL_ENDSTOPS) - #ifndef X_MIN_PIN - #define X_MIN_PIN PC1 // X-STOP - #endif - #ifndef X_MAX_PIN - #define X_MAX_PIN PC2 // E0DET - #endif -#else - #define X_STOP_PIN PC1 // X-STOP +#ifndef X_STOP_PIN + #define X_STOP_PIN X_DIAG_PIN // X-STOP #endif +#ifndef Y_STOP_PIN + #define Y_STOP_PIN Y_DIAG_PIN // Y-STOP +#endif +#ifndef Z_STOP_PIN + #define Z_STOP_PIN Z_DIAG_PIN // Z-STOP +#endif +#define X_OTHR_PIN PC2 // E0DET +#define Y_OTHR_PIN PA0 // E1DET +#define Z_OTHR_PIN PC15 // PWRDET -#ifdef Y_STALL_SENSITIVITY - #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_TO_MIN - #define Y_MAX_PIN PA0 // E1DET - #else - #define Y_MIN_PIN PA0 // E1DET - #endif -#elif ENABLED(Y_DUAL_ENDSTOPS) - #ifndef Y_MIN_PIN - #define Y_MIN_PIN PC3 // Y-STOP - #endif - #ifndef Y_MAX_PIN - #define Y_MAX_PIN PA0 // E1DET - #endif -#else - #define Y_STOP_PIN PC3 // Y-STOP -#endif - -#ifdef Z_STALL_SENSITIVITY - #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_TO_MIN - #define Z_MAX_PIN PC15 // PWRDET - #else - #define Z_MIN_PIN PC15 // PWRDET - #endif -#elif ENABLED(Z_MULTI_ENDSTOPS) - #ifndef Z_MIN_PIN - #define Z_MIN_PIN PC0 // Z-STOP - #endif - #ifndef Z_MAX_PIN - #define Z_MAX_PIN PC15 // PWRDET - #endif -#else - #ifndef Z_STOP_PIN - #define Z_STOP_PIN PC0 // Z-STOP - #endif -#endif #define ONBOARD_ENDSTOPPULLUPS // Board has built-in pullups // From fbea4c604812dd5f7ee0f3066c4bcd34fafad4ab Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Wed, 14 May 2025 13:18:53 -0700 Subject: [PATCH 033/102] =?UTF-8?q?=E2=9C=8F=EF=B8=8F=20Fix=20variant=20do?= =?UTF-8?q?cs=20typo=20(#27850)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/share/PlatformIO/variants/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/buildroot/share/PlatformIO/variants/README.md b/buildroot/share/PlatformIO/variants/README.md index ae64b1b439..0217e2ebd9 100644 --- a/buildroot/share/PlatformIO/variants/README.md +++ b/buildroot/share/PlatformIO/variants/README.md @@ -3,7 +3,7 @@ This `buildroot/share/PlatformIO/variants` folder contains Marlin custom variants for both generic and custom boards. Marlin specifies board variants in PlatformIO INI files in one of two ways: -- The `board_build.variant = VARIANT_MAME` field specifies the variant subfolder name directly. +- The `board_build.variant = VARIANT_NAME` field specifies the variant subfolder name directly. - The `board = board_name` field names a custom board JSON file that contains a `build.variant` field. ## Variant File Naming From 0927e49756ca41587088adffdf84ec5a1c87328f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Matheus=20M=C3=B6sken=20Diegues?= Date: Wed, 14 May 2025 17:23:04 -0300 Subject: [PATCH 034/102] =?UTF-8?q?=F0=9F=8C=90=20README=20in=20Portuguese?= =?UTF-8?q?=20(Brazil)=20(#27854)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- README-PT-BR.md | 81 +++++++++++++++++++++++++++++++++++++++++++++++++ README.md | 4 +++ 2 files changed, 85 insertions(+) create mode 100644 README-PT-BR.md diff --git a/README-PT-BR.md b/README-PT-BR.md new file mode 100644 index 0000000000..8d8b18828f --- /dev/null +++ b/README-PT-BR.md @@ -0,0 +1,81 @@ + +

Logo do MarlinFirmware

+ +

Firmware de Impressora 3D Marlin

+ +

+ Licença GPL-V3.0 + Contribuidores + Data do Último Lançamento + Status do CI + Patrocínios no GitHub +
+ Siga marlinfw.org no Bluesky + Siga MarlinFirmware no Mastodon +

+ +Documentação adicional pode ser encontrada na [Página Inicial do Marlin](//marlinfw.org/). +Por favor, teste este firmware e nos avise se encontrar algum problema. Voluntários estão prontos para ajudar! + +## Branch de Correções do Marlin 2.1 + +__Não é para uso em produção. Use com cautela!__ + +O Marlin 2.1 continua oferecendo suporte a placas ARM 32 bits e AVR 8 bits, além de adicionar suporte para até 9 eixos coordenados e até 8 extrusoras. + +Este branch é para correções da versão mais recente 2.1.x. Periodicamente, ele servirá de base para o próximo lançamento menor da linha 2.1.x. + +Versões anteriores do Marlin podem ser baixadas na [página de lançamentos](//github.com/MarlinFirmware/Marlin/releases). + +## Configurações de Exemplo + +Antes de compilar o Marlin para sua máquina, você precisará de uma configuração específica para o seu hardware. Ao solicitar, seu fornecedor deve fornecer o código-fonte completo e as configurações da sua máquina. No entanto, se quiser instalar uma versão mais recente do Marlin, você precisará de arquivos de configuração atualizados. Felizmente, a comunidade do Marlin já contribuiu com dezenas de configurações testadas para ajudar no início. Visite o repositório [MarlinFirmware/Configurations](//github.com/MarlinFirmware/Configurations) para encontrar a configuração mais próxima da sua impressora. + +## Compilando o Marlin 2.1 + +Para compilar e enviar o Marlin você pode usar uma destas ferramentas: + +- O [Visual Studio Code](//code.visualstudio.com/download) com a extensão [Auto Build Marlin](//marlinfw.org/docs/basics/auto_build_marlin.html). +- A [IDE do Arduino](//www.arduino.cc/en/main/software): Veja [Compilando Marlin com Arduino](//marlinfw.org/docs/basics/install_arduino.html). +- Também é possível usar VSCode com devcontainer: Veja [Instalando Marlin (VSCode devcontainer)](http://marlinfw.org/docs/basics/install_devcontainer_vscode.html). + +O Marlin é otimizado para ser compilado com a extensão **PlatformIO IDE** no **Visual Studio Code**. Ainda é possível compilar com a **IDE do Arduino**, e temos planos para melhorar essa experiência, mas por enquanto o PlatformIO é a melhor escolha. + +## Placas AVR 8 Bits + +Pretendemos continuar oferecendo suporte às placas AVR 8 bits indefinidamente, mantendo uma base de código única que possa ser aplicada a todas as máquinas. Queremos que hobbystas, experimentadores e donos de máquinas antigas também se beneficiem das inovações da comunidade tanto quanto os donos de equipamentos mais modernos. Além disso, essas máquinas baseadas em AVR costumam ser ideais para testes e feedbacks! + +## Camada de Abstração de Hardware (HAL) + +O Marlin inclui uma camada de abstração de hardware para portar o firmware para uma grande variedade de chips. Essa camada trata das diferenças entre chips de forma modular, permitindo que as funcionalidades do Marlin sejam aproveitadas ao máximo. + +## Licença + +Marlin é publicado sob a licença GPL, então você pode usar, redistribuir e modificar o código-fonte, desde que o código derivado também seja publicado sob a mesma licença. Consulte o arquivo [LICENSE](https://github.com/MarlinFirmware/Marlin/blob/bugfix-2.1.x/LICENSE) para mais detalhes. + +## Ajude o Marlin! + +Você pode ajudar o projeto Marlin contribuindo com código, traduções, testes ou apoiando financeiramente no [GitHub Sponsors](https://github.com/sponsors/thinkyhead). + +...Marlin para diferentes plataformas de hardware. O HAL define as interfaces entre o núcleo do Marlin e o hardware da plataforma. O Marlin suporta atualmente as seguintes arquiteturas: + +- AVR +- SAM (Arduino Due) +- SAMD (Arduino Zero, etc.) +- STM32F1, STM32F4, STM32F7, STM32H7 +- LPC176x (Smoothieboard, ReARM, Archim, MKS Sbase, etc.) +- Teensy 3.5 e 3.6 (ARM Cortex-M4) +- ESP32 (experimental) + +## Comunicação Serial + +- **Baudrates suportados:** 250000, 115200, 57600, 38400, 19200, 9600 +- O baudrate padrão é 250000 para maior velocidade e estabilidade + +## Atualizações e Contribuições + +Aceitamos correções de bugs, melhorias de desempenho e novas funcionalidades. Veja as instruções de contribuição na [Wiki do Marlin](https://github.com/MarlinFirmware/Marlin/wiki/Contributing). + +## Licença + +Marlin é um software livre licenciado sob a [GNU General Public License v3.0](https://www.gnu.org/licenses/gpl-3.0.html). Você pode redistribuí-lo e/ou modificá-lo sob os termos da GPL. Para mais detalhes, veja o arquivo [LICENSE](LICENSE). diff --git a/README.md b/README.md index 50b86d3213..50dfddda9a 100644 --- a/README.md +++ b/README.md @@ -16,6 +16,10 @@ Additional 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! +--- +This README is available in other languages +> **Versão em português:** [README-PT-BR.md](README-PT-BR.md) + ## Marlin 2.1 Bugfix Branch __Not for production use. Use with caution!__ From b79f7f203ab3335c8b2d01d4ab1ab058530785cb Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 15 May 2025 00:30:52 +0000 Subject: [PATCH 035/102] [cron] Bump distribution date (2025-05-15) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index bc68976ee3..5e346f4260 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-05-14" +//#define STRING_DISTRIBUTION_DATE "2025-05-15" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 75995aa92a..0390d41cfc 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-05-14" + #define STRING_DISTRIBUTION_DATE "2025-05-15" #endif /** From 487542083b7920a797e1df8c288fa05b40c73bf3 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 15 May 2025 14:08:32 -0500 Subject: [PATCH 036/102] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Upd?= =?UTF-8?q?ate=20Sim,=20fix=20Mac=20native=20gcc?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/bin/mac_gcc | 45 ++++++++++++++++++++++++------------------- ini/native.ini | 4 ++-- 2 files changed, 27 insertions(+), 22 deletions(-) diff --git a/buildroot/bin/mac_gcc b/buildroot/bin/mac_gcc index 6c5d7ea24a..14ae3c4500 100755 --- a/buildroot/bin/mac_gcc +++ b/buildroot/bin/mac_gcc @@ -10,30 +10,29 @@ which port >/dev/null && HAS_MACPORTS=1 which brew >/dev/null && HAS_HOMEBREW=1 -MACPORTS_PATH=$(dirname "$(which port)") +if ((HAS_MACPORTS)); then + MACPORTS_PATH=$(dirname "$(which port)") + cd $MACPORTS_PATH + sudo rm -f cpp gcc g++ cc ld + cd - +fi + if ((HAS_HOMEBREW)); then HOMEBREW_PATH="$(brew --prefix)/bin" + cd $HOMEBREW_PATH + rm -f cpp gcc g++ cc ld + cd - fi if [[ $1 == "apple" || $1 == "darwin" || $1 == "system" ]]; then - if ((HAS_MACPORTS)); then - cd $MACPORTS_PATH - sudo rm -f gcc g++ cc ld - cd - - fi - - if ((HAS_HOMEBREW)); then - cd $HOMEBREW_PATH - sudo rm -f gcc g++ cc - cd - - fi + # Nothing to do elif [[ $1 =~ ".*ports" ]]; then ((HAS_MACPORTS)) || { echo "MacPorts is not installed"; exit 1; } - GCCV=$( find $MACPORTS_PATH -name "gcc-mp-*" | sort -r | head -1 | sed 's/.*gcc-mp-//' ) + GCCV=$( find $MACPORTS_PATH -name "cpp-mp-*" | sort -r | head -1 | sed 's/.*cpp-mp-//' ) [[ $GCCV -ge 11 ]] || GCCV=14 getport() { port installed $1 | grep $1 || sudo port install $1; } @@ -42,7 +41,7 @@ elif [[ $1 =~ ".*ports" ]]; then getports "gcc$GCCV" glm mesa libsdl2 libsdl2_net cd $MACPORTS_PATH - sudo rm -f gcc g++ cc ld + sudo ln -s "cpp-mp-$GCCV" cpp sudo ln -s "gcc-mp-$GCCV" gcc sudo ln -s "g++-mp-$GCCV" g++ sudo ln -s g++ cc @@ -53,16 +52,22 @@ elif [[ $1 =~ ".*brew" ]]; then ((HAS_HOMEBREW)) || { echo "Homebrew is not installed"; exit 1; } - GCCV=$( find $HOMEBREW_PATH -name "gcc-*" | sort -r | head -1 | sed 's/.*gcc-//' ) - [[ $GCCV -ge 11 ]] || { brew install gcc@14 ; GCCV=14 } + GCCV=$( find $HOMEBREW_PATH -name "cpp-*" | sort -r | head -1 | sed 's/.*cpp-//' ) + [[ $GCCV -ge 11 ]] || brew install gcc + GCCV=$( find $HOMEBREW_PATH -name "cpp-*" | sort -r | head -1 | sed 's/.*cpp-//' ) brew install glm mesa sdl2 sdl2_net cd $HOMEBREW_PATH - sudo rm -f gcc g++ cc - sudo ln -s "gcc-$GCCV" gcc - sudo ln -s "g++-$GCCV" g++ - sudo ln -s g++ cc + ln -s "cpp-$GCCV" cpp + ln -s "gcc-$GCCV" gcc + ln -s "g++-$GCCV" g++ + ln -s g++ cc + if [[ -f "$MACPORTS_PATH/ld-classic" ]]; then + ln -s "$MACPORTS_PATH/ld-classic" ld + else + echo "MacPorts may be required for a compatible 'ld' linker!" + fi cd - else diff --git a/ini/native.ini b/ini/native.ini index f27285e83a..5f56b1c843 100644 --- a/ini/native.ini +++ b/ini/native.ini @@ -58,7 +58,7 @@ debug_build_flags = -fstack-protector-strong -g -g3 -ggdb lib_compat_mode = off build_src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} - MarlinSimUI=https://github.com/p3p/MarlinSimUI/archive/dd9c41f1b2.zip + MarlinSimUI=https://github.com/p3p/MarlinSimUI/archive/af62611296.zip Adafruit NeoPixel=https://github.com/p3p/Adafruit_NeoPixel/archive/c6b319f447.zip LiquidCrystal=https://github.com/p3p/LiquidCrystal/archive/322fb5fc23.zip extra_scripts = ${common.extra_scripts} @@ -115,7 +115,7 @@ build_flags = -g2 -DHAS_LIBBSD -I/opt/local/include -I/opt/local/include/freetype2 - -I/opt/local/include/SDL2/ + -I/opt/local/include/SDL2 -L/opt/local/lib -Wl,-framework,OpenGl -Wl,-framework,CoreFoundation From 8643fa0afb6498ac9eb111a5f6a4cf0481bb95db Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 16 May 2025 00:32:02 +0000 Subject: [PATCH 037/102] [cron] Bump distribution date (2025-05-16) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 5e346f4260..5c920216d1 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-05-15" +//#define STRING_DISTRIBUTION_DATE "2025-05-16" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 0390d41cfc..570a8c03d8 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-05-15" + #define STRING_DISTRIBUTION_DATE "2025-05-16" #endif /** From bd4900d6cd0074f3d709bbd93d30db5375a4def9 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 18 May 2025 16:35:23 -0500 Subject: [PATCH 038/102] =?UTF-8?q?=E2=9C=85=20Pre-fetch=20configs=20for?= =?UTF-8?q?=20CI=20tests?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .github/workflows/ci-build-tests.yml | 10 +++++ buildroot/bin/use_example_configs | 65 +++++++++++++++++++++++----- 2 files changed, 64 insertions(+), 11 deletions(-) diff --git a/.github/workflows/ci-build-tests.yml b/.github/workflows/ci-build-tests.yml index f80417c0fe..b65a71ab56 100644 --- a/.github/workflows/ci-build-tests.yml +++ b/.github/workflows/ci-build-tests.yml @@ -36,6 +36,9 @@ jobs: runs-on: ubuntu-22.04 + env: + CONFIG_BRANCH: ${{ github.base_ref || github.ref_name }} + strategy: fail-fast: true matrix: @@ -205,6 +208,13 @@ jobs: sudo apt-get install libsdl2-net-dev sudo apt-get install libglm-dev + - name: Checkout Configurations + uses: actions/checkout@v4 + with: + repository: MarlinFirmware/Configurations + ref: ${{ env.CONFIG_BRANCH }} + path: ConfigurationsRepo + - name: Run ${{ matrix.test-platform }} Tests run: | make tests-single-ci TEST_TARGET=${{ matrix.test-platform }} diff --git a/buildroot/bin/use_example_configs b/buildroot/bin/use_example_configs index 193da74901..9a3a7a34d4 100755 --- a/buildroot/bin/use_example_configs +++ b/buildroot/bin/use_example_configs @@ -15,6 +15,9 @@ # import os, subprocess, sys, urllib.request +from pathlib import Path + +CONFIG_FILES = ("Configuration.h", "Configuration_adv.h", "_Bootscreen.h", "_Statusscreen.h") def get_current_branch(): try: @@ -25,19 +28,45 @@ def get_current_branch(): except subprocess.CalledProcessError: return None -def fetch_configs(branch, config_path): - print(f"Fetching {config_path} configurations from {branch}...") - base_url = f"https://raw.githubusercontent.com/MarlinFirmware/Configurations/{branch}/config/{config_path}" - files = ["Configuration.h", "Configuration_adv.h", "_Bootscreen.h", "_Statusscreen.h"] - marlin_dir = os.path.join(os.getcwd(), "Marlin") - if not os.path.exists(marlin_dir): - print(f"Directory {marlin_dir} does not exist.") - sys.exit(1) - for file in files: +def sparse_checkout(branch, config_path, repo_url="https://github.com/MarlinFirmware/Configurations.git"): + 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) + + # 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) + + 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 + print(f"Copying {src_file} to {dest_file}") + dest_file.write_bytes(src_file.read_bytes()) + else: + 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}" + + for file in CONFIG_FILES: url = f"{base_url}/{file}" - dest_file = os.path.join(marlin_dir, file) + dest_file = dest_dir / file if os.getenv('DEBUG', '0') == '1': print(f"Fetching {file} from {url} to {dest_file}") + try: urllib.request.urlretrieve(url, dest_file) except urllib.error.HTTPError as e: @@ -47,6 +76,19 @@ def fetch_configs(branch, config_path): else: raise +def fetch_configs(branch, config_path): + 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) + + 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: @@ -74,7 +116,7 @@ def main(): branch = part1 else: config_path = arg - config_path = 'examples/'+config_path.replace(' ', '%20') + config_path = 'examples/'+config_path else: config_path = "default" @@ -82,6 +124,7 @@ def main(): subprocess.run(['restore_configs'], check=True) except FileNotFoundError: print("restore_configs not found, skipping.") + fetch_configs(branch, config_path) if __name__ == "__main__": From fe747ae4bf4173e5947bbf41b6bc77ad9be571e0 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 19 May 2025 00:37:46 +0000 Subject: [PATCH 039/102] [cron] Bump distribution date (2025-05-19) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 5c920216d1..1deb2d2109 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-05-16" +//#define STRING_DISTRIBUTION_DATE "2025-05-19" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 570a8c03d8..8c62809731 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-05-16" + #define STRING_DISTRIBUTION_DATE "2025-05-19" #endif /** From 88a8e2127d80abb46a11261073cd11a80e17c476 Mon Sep 17 00:00:00 2001 From: Fly3DTeam Date: Mon, 19 May 2025 10:12:07 +0800 Subject: [PATCH 040/102] =?UTF-8?q?=F0=9F=94=A7=20TMC=20Baud=20Rate=20for?= =?UTF-8?q?=20FLY=20D5/D7=20(#27860)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f0/pins_FLY_D5.h | 6 ++++++ Marlin/src/pins/stm32f0/pins_FLY_D7.h | 6 ++++++ 2 files changed, 12 insertions(+) diff --git a/Marlin/src/pins/stm32f0/pins_FLY_D5.h b/Marlin/src/pins/stm32f0/pins_FLY_D5.h index c98dcb0b7e..b3b51f6bde 100644 --- a/Marlin/src/pins/stm32f0/pins_FLY_D5.h +++ b/Marlin/src/pins/stm32f0/pins_FLY_D5.h @@ -114,6 +114,12 @@ #define Z_SERIAL_TX_PIN PA3 #define E0_SERIAL_TX_PIN PA7 #define E1_SERIAL_TX_PIN PB1 + +// Reduce baud rate to improve software serial reliability +#ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 9600 +#endif + #endif // diff --git a/Marlin/src/pins/stm32f0/pins_FLY_D7.h b/Marlin/src/pins/stm32f0/pins_FLY_D7.h index 78ce01d385..136b2c5f9c 100644 --- a/Marlin/src/pins/stm32f0/pins_FLY_D7.h +++ b/Marlin/src/pins/stm32f0/pins_FLY_D7.h @@ -133,6 +133,12 @@ #define E1_SERIAL_TX_PIN PB1 #define E2_SERIAL_TX_PIN PB6 #define E3_SERIAL_TX_PIN PC10 + +// Reduce baud rate to improve software serial reliability +#ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 9600 +#endif + #endif // From ade6dbf01eb2c1d58bf526e0f7bc993f190f38ef Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 18 May 2025 21:13:30 -0500 Subject: [PATCH 041/102] =?UTF-8?q?=F0=9F=94=A7=20Fix=20Speed/Flow=20edit?= =?UTF-8?q?=20options=20(#27863)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Fixes #27849 --- Marlin/Configuration_adv.h | 5 +++-- Marlin/src/inc/Conditionals-2-LCD.h | 3 --- Marlin/src/inc/Conditionals-3-etc.h | 5 ----- Marlin/src/inc/Conditionals-4-adv.h | 4 ++++ Marlin/src/lcd/extui/ui_api.cpp | 4 ++-- Marlin/src/lcd/menu/menu_bed_tramming.cpp | 15 ++++++++------- Marlin/src/module/motion.cpp | 2 +- Marlin/src/module/motion.h | 5 ++++- Marlin/src/module/probe.cpp | 2 +- 9 files changed, 23 insertions(+), 22 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 762ae2aa81..60e5378c30 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1673,11 +1673,12 @@ #endif // HAS_DISPLAY -#if HAS_FEEDRATE_EDIT +// Some displays offer Feedrate / Flow editing. +#if ANY(HAS_MARLINUI_MENU, DWIN_CREALITY_LCD, DWIN_LCD_PROUI, MALYAN_LCD, TOUCH_SCREEN, ULTIPANEL_FEEDMULTIPLY) #define SPEED_EDIT_MIN 10 // (%) Feedrate percentage edit range minimum #define SPEED_EDIT_MAX 999 // (%) Feedrate percentage edit range maximum #endif -#if HAS_FLOW_EDIT +#if ANY(HAS_MARLINUI_MENU, DWIN_CREALITY_LCD, DWIN_LCD_PROUI, MALYAN_LCD, TOUCH_SCREEN) #define FLOW_EDIT_MIN 10 // (%) Flow percentage edit range minimum #define FLOW_EDIT_MAX 999 // (%) Flow percentage edit range maximum #endif diff --git a/Marlin/src/inc/Conditionals-2-LCD.h b/Marlin/src/inc/Conditionals-2-LCD.h index 2bf663b6f0..362ca7a714 100644 --- a/Marlin/src/inc/Conditionals-2-LCD.h +++ b/Marlin/src/inc/Conditionals-2-LCD.h @@ -667,9 +667,6 @@ #if HAS_EXTRUDERS && ANY(HAS_MARLINUI_MENU, DWIN_CREALITY_LCD, DWIN_LCD_PROUI, MALYAN_LCD, TOUCH_SCREEN) #define HAS_FLOW_EDIT 1 #endif -#if ANY(HAS_MARLINUI_MENU, ULTIPANEL_FEEDMULTIPLY, DWIN_CREALITY_LCD, DWIN_LCD_PROUI, MALYAN_LCD, TOUCH_SCREEN) - #define HAS_FEEDRATE_EDIT 1 -#endif /** * TFT Displays diff --git a/Marlin/src/inc/Conditionals-3-etc.h b/Marlin/src/inc/Conditionals-3-etc.h index b361a50a58..00bff0e072 100644 --- a/Marlin/src/inc/Conditionals-3-etc.h +++ b/Marlin/src/inc/Conditionals-3-etc.h @@ -560,11 +560,6 @@ #undef Z_CLEARANCE_DEPLOY_PROBE #endif -#if !(ANY(HAS_BED_PROBE, BACKLASH_GCODE) || (ENABLED(EXTENSIBLE_UI) && ANY(MESH_BED_LEVELING, AUTO_BED_LEVELING_UBL))) - #undef Z_PROBE_FEEDRATE_FAST - #undef Z_PROBE_FEEDRATE_SLOW -#endif - /** * Z_CLEARANCE_FOR_HOMING */ diff --git a/Marlin/src/inc/Conditionals-4-adv.h b/Marlin/src/inc/Conditionals-4-adv.h index 629ee98273..a0eaa7081c 100644 --- a/Marlin/src/inc/Conditionals-4-adv.h +++ b/Marlin/src/inc/Conditionals-4-adv.h @@ -105,6 +105,10 @@ #endif #endif +#if !(ANY(HAS_BED_PROBE, BACKLASH_GCODE) || (ENABLED(EXTENSIBLE_UI) && ANY(MESH_BED_LEVELING, AUTO_BED_LEVELING_UBL))) + #undef Z_PROBE_FEEDRATE_FAST + #undef Z_PROBE_FEEDRATE_SLOW +#endif #if !HAS_BED_PROBE #undef BABYSTEP_ZPROBE_OFFSET #undef PROBING_USE_CURRENT_HOME diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index 5380b05596..badb3335a3 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -887,14 +887,14 @@ namespace ExtUI { y_target = MESH_MIN_Y + pos.y * (MESH_Y_DIST); if (x_target != current_position.x || y_target != current_position.y) { // If moving across bed, raise nozzle to safe height over bed - feedrate_mm_s = MMM_TO_MMS(Z_PROBE_FEEDRATE_FAST); + feedrate_mm_s = z_probe_fast_mm_s; destination.set(current_position.x, current_position.y, Z_CLEARANCE_BETWEEN_PROBES); prepare_line_to_destination(); if (XY_PROBE_FEEDRATE_MM_S) feedrate_mm_s = XY_PROBE_FEEDRATE_MM_S; destination.set(x_target, y_target); prepare_line_to_destination(); } - feedrate_mm_s = MMM_TO_MMS(Z_PROBE_FEEDRATE_FAST); + feedrate_mm_s = z_probe_fast_mm_s; destination.z = z; prepare_line_to_destination(); #else diff --git a/Marlin/src/lcd/menu/menu_bed_tramming.cpp b/Marlin/src/lcd/menu/menu_bed_tramming.cpp index d749763808..0d5feddce6 100644 --- a/Marlin/src/lcd/menu/menu_bed_tramming.cpp +++ b/Marlin/src/lcd/menu/menu_bed_tramming.cpp @@ -230,11 +230,12 @@ static void _lcd_goto_next_corner() { ); } + // Probe down and return 'true' if the probe triggered bool _lcd_bed_tramming_probe(const bool verify=false) { - if (verify) line_to_z(current_position.z + (BED_TRAMMING_Z_HOP)); // do clearance if needed - TERN_(BLTOUCH, if (!bltouch.high_speed_mode) bltouch.deploy()); // Deploy in LOW SPEED MODE on every probe action - do_blocking_move_to_z(last_z - BED_TRAMMING_PROBE_TOLERANCE, MMM_TO_MMS(Z_PROBE_FEEDRATE_SLOW)); // Move down to lower tolerance - if (TEST(endstops.trigger_state(), Z_MIN_PROBE)) { // check if probe triggered + if (verify) line_to_z(current_position.z + (BED_TRAMMING_Z_HOP)); // Do clearance if needed + TERN_(BLTOUCH, if (!bltouch.high_speed_mode) bltouch.deploy()); // Deploy in LOW SPEED MODE on every probe action + do_blocking_move_to_z(last_z - BED_TRAMMING_PROBE_TOLERANCE, z_probe_slow_mm_s); // Move down to lower tolerance + if (TEST(endstops.trigger_state(), Z_MIN_PROBE)) { // Probe triggered? endstops.hit_on_purpose(); set_current_from_steppers_for_axis(Z_AXIS); sync_plan_position(); @@ -251,10 +252,10 @@ static void _lcd_goto_next_corner() { if (TERN0(NEEDS_PROBE_DEPLOY, good_points == nr_edge_points - 1)) do_z_clearance(BED_TRAMMING_Z_HOP); - return true; // probe triggered + return true; // Triggered } - line_to_z(last_z); // go back to tolerance middle point before raise - return false; // probe not triggered + line_to_z(last_z); // Go back to tolerance middle point before raise + return false; // Not triggered } bool _lcd_bed_tramming_raise() { diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index fcaaf613e4..f2f27ee6a9 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -1990,7 +1990,7 @@ void prepare_line_to_destination() { */ feedRate_t get_homing_bump_feedrate(const AxisEnum axis) { #if HOMING_Z_WITH_PROBE - if (axis == Z_AXIS) return MMM_TO_MMS(Z_PROBE_FEEDRATE_SLOW); + if (axis == Z_AXIS) return z_probe_slow_mm_s; #endif static const uint8_t homing_bump_divisor[] PROGMEM = HOMING_BUMP_DIVISOR; uint8_t hbd = pgm_read_byte(&homing_bump_divisor[axis]); diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index 4245331010..edee41a903 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -71,7 +71,10 @@ extern xyz_pos_t cartes; #define XY_PROBE_FEEDRATE_MM_S PLANNER_XY_FEEDRATE_MM_S #endif -#if HAS_BED_PROBE +#ifdef Z_PROBE_FEEDRATE_SLOW + constexpr feedRate_t z_probe_slow_mm_s = MMM_TO_MMS(Z_PROBE_FEEDRATE_SLOW); +#endif +#ifdef Z_PROBE_FEEDRATE_FAST constexpr feedRate_t z_probe_fast_mm_s = MMM_TO_MMS(Z_PROBE_FEEDRATE_FAST); #endif diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index 9a998ec569..b1f1f2cf40 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -854,7 +854,7 @@ float Probe::run_z_probe(const bool sanity_check/*=true*/, const_float_t z_min_p // Probe downward slowly to find the bed if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Slow Probe:"); - if (try_to_probe(PSTR("SLOW"), z_probe_low_point, MMM_TO_MMS(Z_PROBE_FEEDRATE_SLOW), sanity_check)) return NAN; + if (try_to_probe(PSTR("SLOW"), z_probe_low_point, z_probe_slow_mm_s, sanity_check)) return NAN; TERN_(MEASURE_BACKLASH_WHEN_PROBING, backlash.measure_with_probe()); From 3cd945ab5dd9d4adcb2a130328f700f3f553ff4e Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 20 May 2025 00:32:44 +0000 Subject: [PATCH 042/102] [cron] Bump distribution date (2025-05-20) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 1deb2d2109..61232e769a 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-05-19" +//#define STRING_DISTRIBUTION_DATE "2025-05-20" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 8c62809731..8f8c30dbfa 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-05-19" + #define STRING_DISTRIBUTION_DATE "2025-05-20" #endif /** From af553d5fbd1e4217d38f5e0f629682d79570e438 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 19 May 2025 19:36:20 -0500 Subject: [PATCH 043/102] =?UTF-8?q?=F0=9F=94=A8=20Solve=20a=20linker=20err?= =?UTF-8?q?or?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Fixes #27864 --- Marlin/src/lcd/marlinui.cpp | 11 ++++++----- Marlin/src/lcd/marlinui.h | 6 +++++- 2 files changed, 11 insertions(+), 6 deletions(-) diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 991a4f549c..ab932adfcd 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -62,6 +62,10 @@ MarlinUI ui; #include "../module/printcounter.h" #endif +#if HAS_WIRED_LCD || HAS_PREHEAT + #include "../module/temperature.h" +#endif + #if LCD_HAS_WAIT_FOR_MOVE bool MarlinUI::wait_for_move; // = false #endif @@ -136,8 +140,6 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; #endif #if HAS_PREHEAT - #include "../module/temperature.h" - preheat_t MarlinUI::material_preset[PREHEAT_COUNT]; // Initialized by settings.load void MarlinUI::reset_material_presets() { @@ -331,7 +333,6 @@ void MarlinUI::init() { #include "lcdprint.h" - #include "../module/temperature.h" #include "../module/planner.h" #include "../module/motion.h" @@ -1883,7 +1884,7 @@ uint8_t expand_u8str_P(char * const outstr, PGM_P const ptpl, const int8_t ind, ); } - #if LCD_WITH_BLINK && HAS_EXTRA_PROGRESS + #if HAS_ROTATE_PROGRESS // Renew and redraw all enabled progress strings void MarlinUI::rotate_progress() { @@ -1903,7 +1904,7 @@ uint8_t expand_u8str_P(char * const outstr, PGM_P const ptpl, const int8_t ind, } } - #endif // LCD_WITH_BLINK && HAS_EXTRA_PROGRESS + #endif // HAS_ROTATE_PROGRESS #endif // HAS_PRINT_PROGRESS diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index 578d143d96..adfecdbaf5 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -95,6 +95,10 @@ typedef bool (*statusResetFunc_t)(); #define LCD_UPDATE_INTERVAL DIV_TERN(DOUBLE_LCD_FRAMERATE, TERN(HAS_TOUCH_BUTTONS, 50, 100), 2) #endif +#if LCD_WITH_BLINK && HAS_EXTRA_PROGRESS && !IS_DWIN_MARLINUI + #define HAS_ROTATE_PROGRESS 1 +#endif + #if HAS_MARLINUI_U8GLIB enum MarlinFont : uint8_t { FONT_STATUSMENU = 1, @@ -347,7 +351,7 @@ public: FORCE_INLINE static uint16_t get_progress_permyriad() { return _get_progress(); } #endif static uint8_t get_progress_percent() { return uint8_t(_get_progress() / (PROGRESS_SCALE)); } - #if LCD_WITH_BLINK && HAS_EXTRA_PROGRESS + #if HAS_ROTATE_PROGRESS #if ENABLED(SHOW_PROGRESS_PERCENT) static void drawPercent(); #endif From d5723fcafd200a55fcc1fc1c37aab39da7fde12d Mon Sep 17 00:00:00 2001 From: Vovodroid Date: Tue, 20 May 2025 22:52:51 +0300 Subject: [PATCH 044/102] =?UTF-8?q?=F0=9F=94=A7=20Allow=20SMOOTH=5FLIN=5FA?= =?UTF-8?q?DVANCE=20+=20NONLINEAR=5FEXTRUSION=20(#27861)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/GD32_MFL/timers.h | 6 +- Marlin/src/gcode/feature/nonlinear/M592.cpp | 6 ++ Marlin/src/inc/SanityCheck.h | 2 - Marlin/src/module/planner.cpp | 4 ++ Marlin/src/module/planner.h | 4 +- Marlin/src/module/stepper.cpp | 73 ++++++++++++--------- Marlin/src/module/stepper.h | 25 +++++-- README-PT-BR.md | 2 +- 8 files changed, 74 insertions(+), 48 deletions(-) diff --git a/Marlin/src/HAL/GD32_MFL/timers.h b/Marlin/src/HAL/GD32_MFL/timers.h index 49d005b8cd..a5d36d9eca 100644 --- a/Marlin/src/HAL/GD32_MFL/timers.h +++ b/Marlin/src/HAL/GD32_MFL/timers.h @@ -44,9 +44,9 @@ extern uint32_t GetStepperTimerClkFreq(); // Timer prescaler calculations -#define STEPPER_TIMER_PRESCALE (GetStepperTimerClkFreq() / STEPPER_TIMER_RATE) // Prescaler = 30 +#define STEPPER_TIMER_PRESCALE (GetStepperTimerClkFreq() / STEPPER_TIMER_RATE) // Prescaler = 30 #define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE -#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // Stepper timer ticks per µs +#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // Stepper timer ticks per µs #define PULSE_TIMER_RATE STEPPER_TIMER_RATE #define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US @@ -57,7 +57,7 @@ extern uint32_t GetStepperTimerClkFreq(); #define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) #define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP) #define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) -#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP) extern void Step_Handler(); diff --git a/Marlin/src/gcode/feature/nonlinear/M592.cpp b/Marlin/src/gcode/feature/nonlinear/M592.cpp index 77a6258ddc..78c15443f8 100644 --- a/Marlin/src/gcode/feature/nonlinear/M592.cpp +++ b/Marlin/src/gcode/feature/nonlinear/M592.cpp @@ -49,6 +49,12 @@ void GcodeSuite::M592() { if (parser.seenval('A')) stepper.ne.A = parser.value_float(); if (parser.seenval('B')) stepper.ne.B = parser.value_float(); if (parser.seenval('C')) stepper.ne.C = parser.value_float(); + + #if ENABLED(SMOOTH_LIN_ADVANCE) + stepper.ne_q30.A = _BV32(30) * (stepper.ne.A * planner.mm_per_step[E_AXIS_N(0)] * planner.mm_per_step[E_AXIS_N(0)]); + stepper.ne_q30.B = _BV32(30) * (stepper.ne.B * planner.mm_per_step[E_AXIS_N(0)]); + stepper.ne_q30.C = _BV32(30) * stepper.ne.C; + #endif } #endif // NONLINEAR_EXTRUSION diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 97cc2ed198..c70c5ce0ec 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -868,8 +868,6 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L #error "SMOOTH_LIN_ADVANCE requires a 32-bit CPU." #elif ENABLED(S_CURVE_ACCELERATION) #error "SMOOTH_LIN_ADVANCE is not compatible with S_CURVE_ACCELERATION." - #elif ENABLED(NONLINEAR_EXTRUSION) - #error "SMOOTH_LIN_ADVANCE doesn't currently support NONLINEAR_EXTRUSION." #elif ENABLED(INPUT_SHAPING_E_SYNC) && NONE(INPUT_SHAPING_X, INPUT_SHAPING_Y) #error "INPUT_SHAPING_E_SYNC requires INPUT_SHAPING_X or INPUT_SHAPING_Y." #endif diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index fe497058d9..5e1c08f863 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -3252,6 +3252,10 @@ void Planner::refresh_acceleration_rates() { void Planner::refresh_positioning() { #if ENABLED(EDITABLE_STEPS_PER_UNIT) LOOP_DISTINCT_AXES(i) mm_per_step[i] = 1.0f / settings.axis_steps_per_mm[i]; + #if ALL(NONLINEAR_EXTRUSION, SMOOTH_LIN_ADVANCE) + stepper.ne_q30.A = _BV32(30) * (stepper.ne.A * mm_per_step[E_AXIS_N(0)] * mm_per_step[E_AXIS_N(0)]); + stepper.ne_q30.B = _BV32(30) * (stepper.ne.B * mm_per_step[E_AXIS_N(0)]); + #endif #endif set_position_mm(current_position); refresh_acceleration_rates(); diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 0a3a35d922..c71a73c5be 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -531,9 +531,7 @@ class Planner { static void set_advance_k(const_float_t k, const uint8_t e=active_extruder) { UNUSED(e); extruder_advance_K[E_INDEX_N(e)] = k; - #if ENABLED(SMOOTH_LIN_ADVANCE) - extruder_advance_K_q27[E_INDEX_N(e)] = k * (1UL << 27); - #endif + TERN_(SMOOTH_LIN_ADVANCE, extruder_advance_K_q27[E_INDEX_N(e)] = k * _BV32(27)); } static float get_advance_k(const uint8_t e=active_extruder) { UNUSED(e); diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 04c796acb3..a6931c8d0d 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -257,9 +257,16 @@ uint32_t Stepper::advance_divisor = 0, #if ENABLED(NONLINEAR_EXTRUSION) ne_coeff_t Stepper::ne; - ne_fix_t Stepper::ne_fix; - int32_t Stepper::ne_edividend; - uint32_t Stepper::ne_scale; + #if NONLINEAR_EXTRUSION_Q24 + ne_q24_t Stepper::ne_q24; + #else + ne_q30_t Stepper::ne_q30; + #endif + // private: + #if NONLINEAR_EXTRUSION_Q24 + int32_t Stepper::ne_edividend; + uint32_t Stepper::ne_scale_q24; + #endif #endif #if HAS_ZV_SHAPING @@ -2241,13 +2248,13 @@ hal_timer_t Stepper::calc_timer_interval(uint32_t step_rate) { #endif // !CPU_32_BIT } -#if ENABLED(NONLINEAR_EXTRUSION) - void Stepper::calc_nonlinear_e(uint32_t step_rate) { - const uint32_t velocity = ne_scale * step_rate; // Scale step_rate first so all intermediate values stay in range of 8.24 fixed point math - int32_t vd = (((((int64_t)ne_fix.A * velocity) >> 24) * velocity) >> 24) + (((int64_t)ne_fix.B * velocity) >> 24); - NOLESS(vd, 0); +#if NONLINEAR_EXTRUSION_Q24 + void Stepper::calc_nonlinear_e(const uint32_t step_rate) { + const uint32_t velocity_q24 = ne_scale_q24 * step_rate; // Scale step_rate first so all intermediate values stay in range of 8.24 fixed point math + int32_t vd_q24 = (((((int64_t)ne_q24.A * velocity_q24) >> 24) * velocity_q24) >> 24) + (((int64_t)ne_q24.B * velocity_q24) >> 24); + NOLESS(vd_q24, 0); - advance_dividend.e = (uint64_t(ne_fix.C + vd) * ne_edividend) >> 24; + advance_dividend.e = (uint64_t(ne_q24.C + vd_q24) * ne_edividend) >> 24; } #endif @@ -2463,9 +2470,7 @@ hal_timer_t Stepper::block_phase_isr() { acceleration_time += interval; deceleration_time = 0; // Reset since we're doing acceleration first. - #if ENABLED(NONLINEAR_EXTRUSION) - calc_nonlinear_e(acc_step_rate << oversampling_factor); - #endif + calc_nonlinear_e(acc_step_rate << oversampling_factor); #if HAS_ROUGH_LIN_ADVANCE if (la_active) { @@ -2529,9 +2534,7 @@ hal_timer_t Stepper::block_phase_isr() { interval = calc_multistep_timer_interval(step_rate << oversampling_factor); deceleration_time += interval; - #if ENABLED(NONLINEAR_EXTRUSION) - calc_nonlinear_e(step_rate << oversampling_factor); - #endif + calc_nonlinear_e(step_rate << oversampling_factor); #if HAS_ROUGH_LIN_ADVANCE if (la_active) { @@ -2584,9 +2587,7 @@ hal_timer_t Stepper::block_phase_isr() { TERN_(SMOOTH_LIN_ADVANCE, curr_step_rate = current_block->nominal_rate;) deceleration_time = ticks_nominal / 2; - #if ENABLED(NONLINEAR_EXTRUSION) - calc_nonlinear_e(current_block->nominal_rate << oversampling_factor); - #endif + calc_nonlinear_e(current_block->nominal_rate << oversampling_factor); #if HAS_ROUGH_LIN_ADVANCE if (la_active) @@ -2836,18 +2837,18 @@ hal_timer_t Stepper::block_phase_isr() { acc_step_rate = current_block->initial_rate; #endif - #if ENABLED(NONLINEAR_EXTRUSION) + #if NONLINEAR_EXTRUSION_Q24 ne_edividend = advance_dividend.e; const float scale = (float(ne_edividend) / advance_divisor) * planner.mm_per_step[E_AXIS_N(current_block->extruder)]; - ne_scale = (1L << 24) * scale; + ne_scale_q24 = _BV32(24) * scale; if (current_block->direction_bits.e && ANY_AXIS_MOVES(current_block)) { - ne_fix.A = (1L << 24) * ne.A; - ne_fix.B = (1L << 24) * ne.B; - ne_fix.C = (1L << 24) * ne.C; + ne_q24.A = _BV32(24) * ne.A; + ne_q24.B = _BV32(24) * ne.B; + ne_q24.C = _BV32(24) * ne.C; } else { - ne_fix.A = ne_fix.B = 0; - ne_fix.C = (1L << 24); + ne_q24.A = ne_q24.B = 0; + ne_q24.C = _BV32(24); } #endif @@ -2856,9 +2857,7 @@ hal_timer_t Stepper::block_phase_isr() { // Initialize ac/deceleration time as if half the time passed. acceleration_time = deceleration_time = interval / 2; - #if ENABLED(NONLINEAR_EXTRUSION) - calc_nonlinear_e(current_block->initial_rate << oversampling_factor); - #endif + calc_nonlinear_e(current_block->initial_rate << oversampling_factor); #if ENABLED(LIN_ADVANCE) #if ENABLED(SMOOTH_LIN_ADVANCE) @@ -2885,13 +2884,23 @@ hal_timer_t Stepper::block_phase_isr() { uint32_t Stepper::extruder_advance_tau_ticks[DISTINCT_E], Stepper::extruder_advance_alpha_q30[DISTINCT_E]; - void Stepper::set_la_interval(const int32_t rate) { - if (rate == 0) { + void Stepper::set_la_interval(int32_t step_rate) { + if (step_rate == 0) { la_interval = LA_ADV_NEVER; } else { - const bool forward_e = rate > 0; - la_interval = calc_timer_interval(uint32_t(ABS(rate))); + const bool forward_e = step_rate > 0; + + #if ENABLED(NONLINEAR_EXTRUSION) + if (forward_e && ANY_AXIS_MOVES(current_block)) { + // Maximum polynomial value is just above 1, like 1.05..1.2, less than 2 anyway, so we can use 30 bits for fractional part + int32_t vd_q30 = ne_q30.A*step_rate*step_rate + ne_q30.B*step_rate; + NOLESS(vd_q30, 0); + step_rate = (int64_t(step_rate) * (ne_q30.C + vd_q30)) >> 30; + } + #endif + + 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; diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index 3fb0b44884..9495a18139 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -285,7 +285,12 @@ constexpr ena_mask_t enable_overlap[] = { #if ENABLED(NONLINEAR_EXTRUSION) typedef struct { float A, B, C; void reset() { A = B = 0.0f; C = 1.0f; } } ne_coeff_t; - typedef struct { int32_t A, B, C; } ne_fix_t; + #if DISABLED(SMOOTH_LIN_ADVANCE) + #define NONLINEAR_EXTRUSION_Q24 1 + typedef struct { int32_t A, B, C; } ne_q24_t; + #else + typedef struct { int32_t A, B, C; } ne_q30_t; + #endif #endif // @@ -343,6 +348,11 @@ class Stepper { #if ENABLED(NONLINEAR_EXTRUSION) static ne_coeff_t ne; + #if NONLINEAR_EXTRUSION_Q24 + static ne_q24_t ne_q24; + #else + static ne_q30_t ne_q30; + #endif #endif #if ENABLED(ADAPTIVE_STEP_SMOOTHING_TOGGLE) @@ -467,10 +477,9 @@ class Stepper { #endif #endif - #if ENABLED(NONLINEAR_EXTRUSION) + #if NONLINEAR_EXTRUSION_Q24 static int32_t ne_edividend; - static uint32_t ne_scale; - static ne_fix_t ne_fix; + static uint32_t ne_scale_q24; #endif #if ENABLED(BABYSTEPPING) @@ -531,7 +540,7 @@ class Stepper { // The Linear advance ISR phase static void advance_isr(); #if ENABLED(SMOOTH_LIN_ADVANCE) - static void set_la_interval(const int32_t rate); + static void set_la_interval(int32_t step_rate); static hal_timer_t smooth_lin_adv_isr(); #endif #endif @@ -738,8 +747,10 @@ class Stepper { // Evaluate axis motions and set bits in axis_did_move static void set_axis_moved_for_current_block(); - #if ENABLED(NONLINEAR_EXTRUSION) - static void calc_nonlinear_e(uint32_t step_rate); + #if NONLINEAR_EXTRUSION_Q24 + static void calc_nonlinear_e(const uint32_t step_rate); + #else + static void calc_nonlinear_e(const uint32_t) {} #endif #if ENABLED(S_CURVE_ACCELERATION) diff --git a/README-PT-BR.md b/README-PT-BR.md index 8d8b18828f..3c730967ae 100644 --- a/README-PT-BR.md +++ b/README-PT-BR.md @@ -14,7 +14,7 @@ Siga MarlinFirmware no Mastodon

-Documentação adicional pode ser encontrada na [Página Inicial do Marlin](//marlinfw.org/). +Documentação adicional pode ser encontrada na [Página Inicial do Marlin](//marlinfw.org/). Por favor, teste este firmware e nos avise se encontrar algum problema. Voluntários estão prontos para ajudar! ## Branch de Correções do Marlin 2.1 From a4382b4dcdcf136908b1bc739fd310f9c4f4c9c5 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 20 May 2025 16:24:13 -0500 Subject: [PATCH 045/102] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Fix?= =?UTF-8?q?=20max=5Fisr=5Frate=20sign=20warnings?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/stepper.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index 9495a18139..73fd28fe85 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -147,7 +147,7 @@ constexpr ena_mask_t enable_overlap[] = { TERN0(INPUT_SHAPING_Z, _ISDMF[Z_AXIS] * _ISDASU[Z_AXIS]); #if defined(__AVR__) || !defined(ADAPTIVE_STEP_SMOOTHING) // min_step_isr_frequency is known at compile time on AVRs and any reduction in SRAM is welcome - template constexpr float max_isr_rate() { + template constexpr float max_isr_rate() { return _MAX(_ISDMF[ALIM(INDEX - 1, _ISDMF)] * _ISDASU[ALIM(INDEX - 1, _ISDASU)], max_isr_rate()); } template<> constexpr float max_isr_rate<0>() { From 9c9ed690f787395e3dc464e9b1c8a22239dfcf8b Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 21 May 2025 00:32:16 +0000 Subject: [PATCH 046/102] [cron] Bump distribution date (2025-05-21) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 61232e769a..98e9fc410e 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-05-20" +//#define STRING_DISTRIBUTION_DATE "2025-05-21" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 8f8c30dbfa..a987b6d9ae 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-05-20" + #define STRING_DISTRIBUTION_DATE "2025-05-21" #endif /** From e7662920a621961254a681eaa732f01ebdd17cc8 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 22 May 2025 13:41:28 -0500 Subject: [PATCH 047/102] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20delay=20=C2=B5s=20?= =?UTF-8?q?>=2032767?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Fixes #27753 --- Marlin/src/HAL/shared/Delay.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/src/HAL/shared/Delay.h b/Marlin/src/HAL/shared/Delay.h index 4751d7a5e2..eeaf4c59fc 100644 --- a/Marlin/src/HAL/shared/Delay.h +++ b/Marlin/src/HAL/shared/Delay.h @@ -100,7 +100,7 @@ void calibrate_delay_loop(); // For delay in microseconds, no smart delay selection is required, directly call the delay function // Teensy compiler is too old and does not accept smart delay compile-time / run-time selection correctly - #define DELAY_US(x) DelayCycleFnc((x) * ((F_CPU) / 1000000UL)) + #define DELAY_US(x) DelayCycleFnc((unsigned long)(x) * ((F_CPU) / 1000000UL)) #elif defined(__AVR__) FORCE_INLINE static void __delay_up_to_3c(uint8_t cycles) { @@ -164,7 +164,7 @@ void calibrate_delay_loop(); } // Delay in microseconds - #define DELAY_US(x) DELAY_CYCLES((x) * ((F_CPU) / 1000000UL)) + #define DELAY_US(x) DELAY_CYCLES((unsigned long)(x) * ((F_CPU) / 1000000UL)) #define DELAY_CYCLES_VAR DELAY_CYCLES @@ -173,7 +173,7 @@ void calibrate_delay_loop(); // DELAY_CYCLES specified inside platform // Delay in microseconds - #define DELAY_US(x) DELAY_CYCLES((x) * ((F_CPU) / 1000000UL)) + #define DELAY_US(x) DELAY_CYCLES((unsigned long)(x) * ((F_CPU) / 1000000UL)) #define DELAY_CYCLES_VAR DELAY_CYCLES From aa02bb05d3e28d3a38008d12784bab68611e92e6 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 23 May 2025 00:32:07 +0000 Subject: [PATCH 048/102] [cron] Bump distribution date (2025-05-23) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 98e9fc410e..71c2b31b6b 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-05-21" +//#define STRING_DISTRIBUTION_DATE "2025-05-23" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index a987b6d9ae..fabb554890 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-05-21" + #define STRING_DISTRIBUTION_DATE "2025-05-23" #endif /** From f49e730b23f4bcfc6162dad9dae03b164d4df198 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 24 Nov 2024 22:17:34 -0600 Subject: [PATCH 049/102] =?UTF-8?q?=F0=9F=94=A7=20Allow=20TMCStepper=20wit?= =?UTF-8?q?h=20Zonestar=20ZM3=20E2xx?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ini/stm32f1-maple.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ini/stm32f1-maple.ini b/ini/stm32f1-maple.ini index ddd75549c8..17bcb2eb60 100644 --- a/ini/stm32f1-maple.ini +++ b/ini/stm32f1-maple.ini @@ -389,7 +389,7 @@ build_flags = ${STM32F1_maple.build_flags} -D__STM32F1__=1 -DDEBUG_LEVEL=0 -DSS_TIMER=4 -DSERIAL_USB lib_deps = ${STM32F1_maple.lib_deps} USBComposite for STM32F1@0.91 -lib_ignore = Adafruit NeoPixel, SPI, SailfishLCD, SailfishRGB_LED, SlowSoftI2CMaster, TMCStepper +lib_ignore = Adafruit NeoPixel, SPI, SailfishLCD, SailfishRGB_LED, SlowSoftI2CMaster [env:STM32F103RC_ZM3E2_USB_maple] extends = ZONESTAR_ZM3E_maple From 1258657b8d428f2e28463b6bc46f551193c31bb1 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 24 May 2025 00:30:50 +0000 Subject: [PATCH 050/102] [cron] Bump distribution date (2025-05-24) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 71c2b31b6b..cb96070cc4 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-05-23" +//#define STRING_DISTRIBUTION_DATE "2025-05-24" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index fabb554890..51a13f1947 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-05-23" + #define STRING_DISTRIBUTION_DATE "2025-05-24" #endif /** From 202ec4b58f76edfff0376306c46ca8529971340a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 23 May 2025 21:11:50 -0500 Subject: [PATCH 051/102] =?UTF-8?q?=E2=9C=A8=20Trinamic=20TMC2240=20(SPI)?= =?UTF-8?q?=20(#25974)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-Authored-By: David Buezas Co-Authored-By: z1996xm <102506464+z1996xm@users.noreply.github.com> --- Marlin/Configuration.h | 6 +- Marlin/Configuration_adv.h | 23 ++-- Marlin/src/core/drivers.h | 34 ++++-- Marlin/src/feature/tmc_util.cpp | 76 ++++++++++++ Marlin/src/feature/tmc_util.h | 77 +++++++++++- .../src/gcode/feature/trinamic/M911-M914.cpp | 6 +- Marlin/src/gcode/gcode.h | 12 +- Marlin/src/inc/SanityCheck.h | 64 +++++----- Marlin/src/module/stepper/trinamic.cpp | 114 +++++++++++++++--- Marlin/src/module/stepper/trinamic.h | 1 + buildroot/tests/BTT_BTT002 | 3 +- 11 files changed, 335 insertions(+), 81 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index dc042ff1cb..859f0bbd33 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -148,9 +148,9 @@ * Options: A4988, A5984, DRV8825, LV8729, TB6560, TB6600, TMC2100, * TMC2130, TMC2130_STANDALONE, TMC2160, TMC2160_STANDALONE, * TMC2208, TMC2208_STANDALONE, TMC2209, TMC2209_STANDALONE, - * TMC2660, TMC2660_STANDALONE, TMC5130, TMC5130_STANDALONE, - * TMC5160, TMC5160_STANDALONE - * :['A4988', 'A5984', 'DRV8825', 'LV8729', 'TB6560', 'TB6600', 'TMC2100', 'TMC2130', 'TMC2130_STANDALONE', 'TMC2160', 'TMC2160_STANDALONE', 'TMC2208', 'TMC2208_STANDALONE', 'TMC2209', 'TMC2209_STANDALONE', 'TMC2660', 'TMC2660_STANDALONE', 'TMC5130', 'TMC5130_STANDALONE', 'TMC5160', 'TMC5160_STANDALONE'] + * TMC2240, TMC2240_STANDALONE, TMC2660, TMC2660_STANDALONE, + * TMC5130, TMC5130_STANDALONE, TMC5160, TMC5160_STANDALONE + * :['A4988', 'A5984', 'DRV8825', 'LV8729', 'TB6560', 'TB6600', 'TMC2100', 'TMC2130', 'TMC2130_STANDALONE', 'TMC2160', 'TMC2160_STANDALONE', 'TMC2208', 'TMC2208_STANDALONE', 'TMC2209', 'TMC2209_STANDALONE', 'TMC2240', 'TMC2240_STANDALONE', 'TMC2660', 'TMC2660_STANDALONE', 'TMC5130', 'TMC5130_STANDALONE', 'TMC5160', 'TMC5160_STANDALONE'] */ #define X_DRIVER_TYPE A4988 #define Y_DRIVER_TYPE A4988 diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 60e5378c30..93d84d8d9c 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -3027,6 +3027,15 @@ */ #define INTERPOLATE true + #if HAS_DRIVER(TMC2240) + #define TMC2240_CURRENT_RANGE 1 // RMS: { 0:'690mA', 1:'1410mA', 2:'2120mA', 3:'2110mA' } + // PEAK:{ 0:'1A', 1:'2A', 2:'3A', 3:'3A' } + // Determines max current. Lower is more internal current resolution. Higher runs cooler. + #define TMC2240_Rref 12000 // ('rref', 12000, minval=12000, maxval=60000) + #define TMC2240_SLOPE_CONTROL 0 // :{ 0:'100V/us', 1:'200V/us', 2:'400V/us', 3:'800V/us' } + // Lower is more silent. Higher runs cooler. + #endif + #if AXIS_IS_TMC_CONFIG(X) #define X_CURRENT 800 // (mA) RMS current. Multiply by 1.414 for peak current. #define X_CURRENT_HOME X_CURRENT // (mA) RMS current for homing. (Typically lower than *_CURRENT.) @@ -3335,7 +3344,7 @@ // @section tmc/stealthchop /** - * TMC2130, TMC2160, TMC2208, TMC2209, TMC5130 and TMC5160 only + * TMC2130, TMC2160, TMC2208, TMC2209, TMC2240, TMC5130 and TMC5160 only * Use Trinamic's ultra quiet stepping mode. * When disabled, Marlin will use spreadCycle stepping mode. */ @@ -3414,7 +3423,7 @@ // @section tmc/hybrid /** - * TMC2130, TMC2160, TMC2208, TMC2209, TMC5130 and TMC5160 only + * TMC2130, TMC2160, TMC2208, TMC2209, TMC2240, TMC5130 and TMC5160 only * The driver will switch to spreadCycle when stepper speed is over HYBRID_THRESHOLD. * This mode allows for faster movements at the expense of higher noise levels. * STEALTHCHOP_(XY|Z|E) must be enabled to use HYBRID_THRESHOLD. @@ -3448,16 +3457,16 @@ /** * Use StallGuard to home / probe X, Y, Z. * - * TMC2130, TMC2160, TMC2209, TMC2660, TMC5130, and TMC5160 only + * TMC2130, TMC2160, TMC2209, TMC2240, TMC2660, TMC5130, and TMC5160 only * Connect the stepper driver's DIAG1 pin to the X/Y endstop pin. * X, Y, and Z homing will always be done in spreadCycle mode. * * X/Y/Z_STALL_SENSITIVITY is the default stall threshold. * Use M914 X Y Z to set the stall threshold at runtime: * - * Sensitivity TMC2209 Others - * HIGHEST 255 -64 (Too sensitive => False positive) - * LOWEST 0 63 (Too insensitive => No trigger) + * Sensitivity TMC2209/2240 Others + * HIGHEST 255 -64 (Too sensitive => False positive) + * LOWEST 0 63 (Too insensitive => No trigger) * * It is recommended to set HOMING_BUMP_MM to { 0, 0, 0 }. * @@ -3474,7 +3483,7 @@ //#define SENSORLESS_HOMING // StallGuard capable drivers only #if ANY(SENSORLESS_HOMING, SENSORLESS_PROBING) - // TMC2209: 0...255. TMC2130: -64...63 + // TMC2209/2240: 0...255. TMC2130: -64...63 #define X_STALL_SENSITIVITY 8 #define X2_STALL_SENSITIVITY X_STALL_SENSITIVITY #define Y_STALL_SENSITIVITY 8 diff --git a/Marlin/src/core/drivers.h b/Marlin/src/core/drivers.h index c54e42c8fe..6b1a70202c 100644 --- a/Marlin/src/core/drivers.h +++ b/Marlin/src/core/drivers.h @@ -41,6 +41,8 @@ #define _TMC2208_STANDALONE 0x2208B #define _TMC2209 0x2209A #define _TMC2209_STANDALONE 0x2209B +#define _TMC2240 0x2240A +#define _TMC2240_STANDALONE 0x2240B #define _TMC2660 0x2660A #define _TMC2660_STANDALONE 0x2660B #define _TMC5130 0x5130A @@ -96,7 +98,7 @@ // Does not match standalone configurations #if ( HAS_DRIVER(TMC2130) || HAS_DRIVER(TMC2160) \ || HAS_DRIVER(TMC2208) || HAS_DRIVER(TMC2209) \ - || HAS_DRIVER(TMC2660) \ + || HAS_DRIVER(TMC2240) || HAS_DRIVER(TMC2660) \ || HAS_DRIVER(TMC5130) || HAS_DRIVER(TMC5160) ) #define HAS_TRINAMIC_CONFIG 1 #endif @@ -106,22 +108,30 @@ #if ( HAS_DRIVER(TMC2100) \ || HAS_DRIVER(TMC2130_STANDALONE) || HAS_DRIVER(TMC2160_STANDALONE) \ || HAS_DRIVER(TMC2208_STANDALONE) || HAS_DRIVER(TMC2209_STANDALONE) \ - || HAS_DRIVER(TMC2660_STANDALONE) || HAS_DRIVER(TMC5130_STANDALONE) \ - || HAS_DRIVER(TMC5160_STANDALONE) ) + || HAS_DRIVER(TMC2240_STANDALONE) || HAS_DRIVER(TMC2660_STANDALONE) \ + || HAS_DRIVER(TMC5130_STANDALONE) || HAS_DRIVER(TMC5160_STANDALONE) ) #define HAS_TRINAMIC_STANDALONE 1 #endif -#if HAS_DRIVER(TMC2130) || HAS_DRIVER(TMC2160) || HAS_DRIVER(TMC5130) || HAS_DRIVER(TMC5160) +#if HAS_DRIVER(TMC2130) || HAS_DRIVER(TMC2160) || HAS_DRIVER(TMC5130) || HAS_DRIVER(TMC5160) || HAS_DRIVER(TMC2240) #define HAS_TMCX1X0 1 #endif - #if HAS_DRIVER(TMC2208) || HAS_DRIVER(TMC2209) #define HAS_TMC220x 1 #endif +//#if HAS_TMC_220x || HAS_DRIVER(TMC2240) +// #define HAS_TMC22xx 1 +//#endif +//#if HAS_TMCX1X0 || HAS_TMC220x +// #define HAS_TMC_CS_ACTUAL 1 +//#endif +//#if HAS_TMCX1X0 || HAS_DRIVER(TMC2209) +// #define HAS_TMC_SG_RESULT 1 +//#endif #define AXIS_IS_TMC(A) ( AXIS_DRIVER_TYPE(A,TMC2130) || AXIS_DRIVER_TYPE(A,TMC2160) \ || AXIS_DRIVER_TYPE(A,TMC2208) || AXIS_DRIVER_TYPE(A,TMC2209) \ - || AXIS_DRIVER_TYPE(A,TMC2660) \ + || AXIS_DRIVER_TYPE(A,TMC2240) || AXIS_DRIVER_TYPE(A,TMC2660) \ || AXIS_DRIVER_TYPE(A,TMC5130) || AXIS_DRIVER_TYPE(A,TMC5160) ) #define AXIS_IS_TMC_CONFIG AXIS_IS_TMC @@ -129,8 +139,8 @@ // Test for a driver that uses SPI - this allows checking whether a _CS_ pin // is considered sensitive #define AXIS_HAS_SPI(A) ( AXIS_DRIVER_TYPE(A,TMC2130) || AXIS_DRIVER_TYPE(A,TMC2160) \ - || AXIS_DRIVER_TYPE(A,TMC2660) || AXIS_DRIVER_TYPE(A,TMC5130) \ - || AXIS_DRIVER_TYPE(A,TMC5160) ) + || AXIS_DRIVER_TYPE(A,TMC2240) || AXIS_DRIVER_TYPE(A,TMC2660) \ + || AXIS_DRIVER_TYPE(A,TMC5130) || AXIS_DRIVER_TYPE(A,TMC5160) ) #define AXIS_HAS_UART(A) ( AXIS_DRIVER_TYPE(A,TMC2208) || AXIS_DRIVER_TYPE(A,TMC2209) ) @@ -140,19 +150,21 @@ #define AXIS_HAS_SW_SERIAL(A) ( AXIS_HAS_UART(A) && !defined(A##_HARDWARE_SERIAL) ) #define AXIS_HAS_STALLGUARD(A) ( AXIS_DRIVER_TYPE(A,TMC2130) || AXIS_DRIVER_TYPE(A,TMC2160) \ - || AXIS_DRIVER_TYPE(A,TMC2209) \ + || AXIS_DRIVER_TYPE(A,TMC2209) || AXIS_DRIVER_TYPE(A,TMC2240) \ || AXIS_DRIVER_TYPE(A,TMC2660) \ || AXIS_DRIVER_TYPE(A,TMC5130) || AXIS_DRIVER_TYPE(A,TMC5160) ) #define AXIS_HAS_STEALTHCHOP(A) ( AXIS_DRIVER_TYPE(A,TMC2130) || AXIS_DRIVER_TYPE(A,TMC2160) \ || AXIS_DRIVER_TYPE(A,TMC2208) || AXIS_DRIVER_TYPE(A,TMC2209) \ + || AXIS_DRIVER_TYPE(A,TMC2240) \ || AXIS_DRIVER_TYPE(A,TMC5130) || AXIS_DRIVER_TYPE(A,TMC5160) ) #define AXIS_HAS_SG_RESULT(A) ( AXIS_DRIVER_TYPE(A,TMC2130) || AXIS_DRIVER_TYPE(A,TMC2160) \ - || AXIS_DRIVER_TYPE(A,TMC2208) || AXIS_DRIVER_TYPE(A,TMC2209) ) + || AXIS_DRIVER_TYPE(A,TMC2208) || AXIS_DRIVER_TYPE(A,TMC2209) \ + || AXIS_DRIVER_TYPE(A,TMC2240) ) #define AXIS_HAS_COOLSTEP(A) ( AXIS_DRIVER_TYPE(A,TMC2130) \ - || AXIS_DRIVER_TYPE(A,TMC2209) \ + || AXIS_DRIVER_TYPE(A,TMC2209) || AXIS_DRIVER_TYPE(A,TMC2240) \ || AXIS_DRIVER_TYPE(A,TMC5130) || AXIS_DRIVER_TYPE(A,TMC5160) ) #define _OR_EAH(N,T) || AXIS_HAS_##T(E##N) diff --git a/Marlin/src/feature/tmc_util.cpp b/Marlin/src/feature/tmc_util.cpp index 753cb003ff..d920c3a604 100644 --- a/Marlin/src/feature/tmc_util.cpp +++ b/Marlin/src/feature/tmc_util.cpp @@ -142,6 +142,67 @@ #endif // HAS_TMCX1X0 + #if HAS_DRIVER(TMC2240) + + #if ENABLED(TMC_DEBUG) + static uint32_t get_pwm_scale(TMC2240Stepper &st) { return st.PWM_SCALE(); } + #endif + + static TMC_driver_data get_driver_data(TMC2240Stepper &st) { + constexpr uint8_t OT_bp = 25, OTPW_bp = 26; + constexpr uint32_t S2G_bm = 0x18000000; + #if ENABLED(TMC_DEBUG) + constexpr uint16_t SG_RESULT_bm = 0x3FF; // 0:9 + constexpr uint8_t STEALTH_bp = 14; + constexpr uint32_t CS_ACTUAL_bm = 0x1F0000; // 16:20 + constexpr uint8_t STALL_GUARD_bp = 24; + constexpr uint8_t STST_bp = 31; + #endif + TMC_driver_data data; + const auto ds = data.drv_status = st.DRV_STATUS(); + #ifdef __AVR__ + + // 8-bit optimization saves up to 70 bytes of PROGMEM per axis + uint8_t spart; + #if ENABLED(TMC_DEBUG) + data.sg_result = ds & SG_RESULT_bm; + spart = ds >> 8; + data.is_stealth = TEST(spart, STEALTH_bp - 8); + spart = ds >> 16; + data.cs_actual = spart & (CS_ACTUAL_bm >> 16); + #endif + spart = ds >> 24; + data.is_ot = TEST(spart, OT_bp - 24); + data.is_otpw = TEST(spart, OTPW_bp - 24); + data.is_s2g = !!(spart & (S2G_bm >> 24)); + #if ENABLED(TMC_DEBUG) + data.is_stall = TEST(spart, STALL_GUARD_bp - 24); + data.is_standstill = TEST(spart, STST_bp - 24); + data.sg_result_reasonable = !data.is_standstill; // sg_result has no reasonable meaning while standstill + #endif + + #else // !__AVR__ + + data.is_ot = TEST(ds, OT_bp); + data.is_otpw = TEST(ds, OTPW_bp); + data.is_s2g = !!(ds & S2G_bm); + #if ENABLED(TMC_DEBUG) + constexpr uint8_t CS_ACTUAL_sb = 16; + data.sg_result = ds & SG_RESULT_bm; + data.is_stealth = TEST(ds, STEALTH_bp); + data.cs_actual = (ds & CS_ACTUAL_bm) >> CS_ACTUAL_sb; + data.is_stall = TEST(ds, STALL_GUARD_bp); + data.is_standstill = TEST(ds, STST_bp); + data.sg_result_reasonable = !data.is_standstill; // sg_result has no reasonable meaning while standstill + #endif + + #endif // !__AVR__ + + return data; + } + + #endif // TMC2240 + #if HAS_TMC220x #if ENABLED(TMC_DEBUG) @@ -1025,6 +1086,21 @@ st.TCOOLTHRS(0); } + bool tmc_enable_stallguard(TMC2240Stepper &st) { + const bool stealthchop_was_enabled = st.en_pwm_mode(); + + st.TCOOLTHRS(0xFFFFF); + st.en_pwm_mode(false); + st.diag0_stall(true); + + return stealthchop_was_enabled; + } + void tmc_disable_stallguard(TMC2240Stepper &st, const bool restore_stealth) { + st.TCOOLTHRS(0); + st.en_pwm_mode(restore_stealth); + st.diag0_stall(false); + } + bool tmc_enable_stallguard(TMC2660Stepper) { // TODO return false; diff --git a/Marlin/src/feature/tmc_util.h b/Marlin/src/feature/tmc_util.h index 4cac2969a7..55a4eb02aa 100644 --- a/Marlin/src/feature/tmc_util.h +++ b/Marlin/src/feature/tmc_util.h @@ -95,7 +95,7 @@ class TMCMarlin : public TMC, public TMCStorage { TMC(CS, RS, pinMOSI, pinMISO, pinSCK) {} TMCMarlin(const uint16_t CS, const float RS, const uint16_t pinMOSI, const uint16_t pinMISO, const uint16_t pinSCK, const uint8_t axis_chain_index) : - TMC(CS, RS, pinMOSI, pinMISO, pinSCK, axis_chain_index) + TMC(CS, RS, pinMOSI, pinMISO, pinSCK, axis_chain_index) {} uint16_t rms_current() { return TMC::rms_current(); } void rms_current(uint16_t mA) { @@ -124,7 +124,7 @@ class TMCMarlin : public TMC, public TMCStorage { #if ENABLED(HYBRID_THRESHOLD) uint32_t get_pwm_thrs() { - return _tmc_thrs(this->microsteps(), this->TPWMTHRS(), planner.settings.axis_steps_per_mm[AXIS_ID]); + return _tmc_thrs(this->microsteps(), TMC::TPWMTHRS(), planner.settings.axis_steps_per_mm[AXIS_ID]); } void set_pwm_thrs(const uint32_t thrs) { TMC::TPWMTHRS(_tmc_thrs(this->microsteps(), thrs, planner.settings.axis_steps_per_mm[AXIS_ID])); @@ -197,7 +197,7 @@ class TMCMarlin : public TMC220 #if ENABLED(HYBRID_THRESHOLD) uint32_t get_pwm_thrs() { - return _tmc_thrs(this->microsteps(), this->TPWMTHRS(), planner.settings.axis_steps_per_mm[AXIS_ID]); + return _tmc_thrs(this->microsteps(), TMC2208Stepper::TPWMTHRS(), planner.settings.axis_steps_per_mm[AXIS_ID]); } void set_pwm_thrs(const uint32_t thrs) { TMC2208Stepper::TPWMTHRS(_tmc_thrs(this->microsteps(), thrs, planner.settings.axis_steps_per_mm[AXIS_ID])); @@ -249,13 +249,14 @@ class TMCMarlin : public TMC220 #if ENABLED(HYBRID_THRESHOLD) uint32_t get_pwm_thrs() { - return _tmc_thrs(this->microsteps(), this->TPWMTHRS(), planner.settings.axis_steps_per_mm[AXIS_ID]); + return _tmc_thrs(this->microsteps(), TMC2209Stepper::TPWMTHRS(), planner.settings.axis_steps_per_mm[AXIS_ID]); } void set_pwm_thrs(const uint32_t thrs) { TMC2209Stepper::TPWMTHRS(_tmc_thrs(this->microsteps(), thrs, planner.settings.axis_steps_per_mm[AXIS_ID])); TERN_(HAS_MARLINUI_MENU, this->stored.hybrid_thrs = thrs); } #endif + #if USE_SENSORLESS int16_t homing_threshold() { return TMC2209Stepper::SGTHRS(); } void homing_threshold(int16_t sgt_val) { @@ -278,6 +279,74 @@ class TMCMarlin : public TMC220 sgt_max = 255; }; +template +class TMCMarlin : public TMC2240Stepper, public TMCStorage { + public: + TMCMarlin(const uint16_t cs_pin, const uint8_t axis_chain_index) : + TMC2240Stepper(cs_pin, axis_chain_index) + {} + TMCMarlin(const uint16_t CS, const uint16_t pinMOSI, const uint16_t pinMISO, const uint16_t pinSCK, const uint8_t axis_chain_index) : + TMC2240Stepper(CS, pinMOSI, pinMISO, pinSCK, axis_chain_index ) + {} + + //uint8_t get_address() { return slave_address; } + uint16_t get_microstep_counter() { return microsteps(); } + + uint16_t rms_current() { return TMC2240Stepper::rms_current(); } + void rms_current(const uint16_t mA) { + this->val_mA = mA; + TMC2240Stepper::rms_current(mA); + } + void rms_current(const uint16_t mA, const float mult) { + this->val_mA = mA; + TMC2240Stepper::rms_current(mA, mult); + } + + #if HAS_STEALTHCHOP + bool get_stealthChop() { return this->en_pwm_mode(); } + bool get_stored_stealthChop() { return this->stored.stealthChop_enabled; } + void refresh_stepping_mode() { this->en_pwm_mode(this->stored.stealthChop_enabled); } + void set_stealthChop(const bool stch) { this->stored.stealthChop_enabled = stch; refresh_stepping_mode(); } + bool toggle_stepping_mode() { set_stealthChop(!this->stored.stealthChop_enabled); return get_stealthChop(); } + #endif + + void set_chopper_times(const chopper_timing_t &ct) { + TMC2240Stepper::toff(ct.toff); + TMC2240Stepper::hysteresis_end(ct.hend); + TMC2240Stepper::hysteresis_start(ct.hstrt); + } + + #if ENABLED(HYBRID_THRESHOLD) + uint32_t get_pwm_thrs() { + return _tmc_thrs(this->microsteps(), TMC2240Stepper::TPWMTHRS(), planner.settings.axis_steps_per_mm[AXIS_ID]); + } + void set_pwm_thrs(const uint32_t thrs) { + TMC2240Stepper::TPWMTHRS(_tmc_thrs(this->microsteps(), thrs, planner.settings.axis_steps_per_mm[AXIS_ID])); + TERN_(HAS_MARLINUI_MENU, this->stored.hybrid_thrs = thrs); + } + #endif + + #if USE_SENSORLESS + int16_t homing_threshold() { return TMC2240Stepper::sgt(); } + void homing_threshold(int16_t sgt_val) { + sgt_val = (int16_t)constrain(sgt_val, sgt_min, sgt_max); + TMC2240Stepper::sgt(sgt_val); + TERN_(HAS_MARLINUI_MENU, this->stored.homing_thrs = sgt_val); + } + #endif + + void refresh_stepper_current() { rms_current(this->val_mA); } + #if ENABLED(HYBRID_THRESHOLD) + void refresh_hybrid_thrs() { set_pwm_thrs(this->stored.hybrid_thrs); } + #endif + #if USE_SENSORLESS + void refresh_homing_thrs() { homing_threshold(this->stored.homing_thrs); } + #endif + + static constexpr int8_t sgt_min = -64, + sgt_max = 63; +}; + template class TMCMarlin : public TMC2660Stepper, public TMCStorage { public: diff --git a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp index f4b0ac3670..52622a5e7e 100644 --- a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp +++ b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp @@ -32,7 +32,9 @@ #if ENABLED(MONITOR_DRIVER_STATUS) - #define M91x_USE(ST) (AXIS_DRIVER_TYPE(ST, TMC2130) || AXIS_DRIVER_TYPE(ST, TMC2160) || AXIS_DRIVER_TYPE(ST, TMC2208) || AXIS_DRIVER_TYPE(ST, TMC2209) || AXIS_DRIVER_TYPE(ST, TMC2660) || AXIS_DRIVER_TYPE(ST, TMC5130) || AXIS_DRIVER_TYPE(ST, TMC5160)) + #define M91x_USE(ST) (AXIS_DRIVER_TYPE(ST, TMC2130) || AXIS_DRIVER_TYPE(ST, TMC2160) \ + || AXIS_DRIVER_TYPE(ST, TMC2208) || AXIS_DRIVER_TYPE(ST, TMC2209) || AXIS_DRIVER_TYPE(ST, TMC2240) \ + || AXIS_DRIVER_TYPE(ST, TMC2660) || AXIS_DRIVER_TYPE(ST, TMC5130) || AXIS_DRIVER_TYPE(ST, TMC5160)) #define M91x_USE_E(N) (E_STEPPERS > N && M91x_USE(E##N)) #if HAS_X_AXIS && (M91x_USE(X) || M91x_USE(X2)) @@ -68,7 +70,7 @@ #endif #if !M91x_SOME_X && !M91x_SOME_Y && !M91x_SOME_Z && !M91x_USE_I && !M91x_USE_J && !M91x_USE_K && !M91x_USE_U && !M91x_USE_V && !M91x_USE_W && !M91x_SOME_E - #error "MONITOR_DRIVER_STATUS requires at least one TMC2130, 2160, 2208, 2209, 2660, 5130, or 5160." + #error "MONITOR_DRIVER_STATUS requires at least one TMC2130, 2160, 2208, 2209, 2240, 2660, 5130, or 5160." #endif template diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 706a7387db..cfe0ec056f 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -159,7 +159,7 @@ * M120 - Enable endstops detection. * M121 - Disable endstops detection. * - * M122 - Debug stepper (Requires *_DRIVER_TYPE TMC(2130|2160|5130|5160|2208|2209|2660)) + * M122 - Debug stepper (Requires *_DRIVER_TYPE TMC(2130|2160|5130|5160|2208|2209|2240|2660)) * M123 - Report fan tachometers. (Requires En_FAN_TACHO_PIN) Optionally set auto-report interval. (Requires AUTO_REPORT_FANS) * M125 - Save current position and move to filament change position. (Requires PARK_HEAD_ON_PAUSE) * @@ -265,7 +265,7 @@ * M552 - Get or set IP address. Enable/disable network interface. (Requires enabled Ethernet port) * M553 - Get or set IP netmask. (Requires enabled Ethernet port) * M554 - Get or set IP gateway. (Requires enabled Ethernet port) - * M569 - Enable stealthChop on an axis. (Requires *_DRIVER_TYPE TMC(2130|2160|2208|2209|5130|5160)) + * M569 - Enable stealthChop on an axis. (Requires *_DRIVER_TYPE TMC(2130|2160|2208|2209|2240|5130|5160)) * M575 - Change the serial baud rate. (Requires BAUD_RATE_GCODE) * M592 - Get or set Nonlinear Extrusion parameters. (Requires NONLINEAR_EXTRUSION) * M593 - Get or set input shaping parameters. (Requires INPUT_SHAPING_[XY]) @@ -309,17 +309,17 @@ * M871 - Print/reset/clear first layer temperature offset values. (Requires PTC_PROBE, PTC_BED, or PTC_HOTEND) * M876 - Handle Prompt Response. (Requires HOST_PROMPT_SUPPORT and not EMERGENCY_PARSER) * M900 - Set or Report Linear Advance K-factor. (Requires LIN_ADVANCE) - * M906 - Set or Report motor current in milliamps using axis codes XYZE, etc. Report values if no axis codes given. (Requires *_DRIVER_TYPE TMC(2130|2160|5130|5160|2208|2209|2660)) + * M906 - Set or Report motor current in milliamps using axis codes XYZE, etc. Report values if no axis codes given. (Requires *_DRIVER_TYPE TMC(2130|2160|5130|5160|2208|2209|2240|2660)) * M907 - Set digital trimpot motor current using axis codes. (Requires a board with digital trimpots) * M908 - Control digital trimpot directly. (Requires HAS_MOTOR_CURRENT_DAC or DIGIPOTSS_PIN) * M909 - Print digipot/DAC current value. (Requires HAS_MOTOR_CURRENT_DAC) * M910 - Commit digipot/DAC value to external EEPROM via I2C. (Requires HAS_MOTOR_CURRENT_DAC) - * M911 - Report stepper driver overtemperature pre-warn condition. (Requires *_DRIVER_TYPE TMC(2130|2160|5130|5160|2208|2209|2660)) - * M912 - Clear stepper driver overtemperature pre-warn condition flag. (Requires *_DRIVER_TYPE TMC(2130|2160|5130|5160|2208|2209|2660)) + * M911 - Report stepper driver overtemperature pre-warn condition. (Requires *_DRIVER_TYPE TMC(2130|2160|5130|5160|2208|2209|2240|2660)) + * M912 - Clear stepper driver overtemperature pre-warn condition flag. (Requires *_DRIVER_TYPE TMC(2130|2160|5130|5160|2208|2209|2240|2660)) * M913 - Set HYBRID_THRESHOLD speed. (Requires HYBRID_THRESHOLD) * M914 - Set StallGuard sensitivity. (Requires SENSORLESS_HOMING or SENSORLESS_PROBING) * M919 - Set or Report motor Chopper Times (time_off, hysteresis_end, hysteresis_start) using axis codes XYZE, etc. - * If no parameters are given, report. (Requires *_DRIVER_TYPE TMC(2130|2160|5130|5160|2208|2209|2660)) + * If no parameters are given, report. (Requires *_DRIVER_TYPE TMC(2130|2160|5130|5160|2208|2209|2240|2660)) * M920 - Set Homing Current. (Requires distinct *_CURRENT_HOME settings) * M936 - OTA update firmware. (Requires OTA_FIRMWARE_UPDATE) * M951 - Set Magnetic Parking Extruder parameters. (Requires MAGNETIC_PARKING_EXTRUDER) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index c70c5ce0ec..5d427e7e08 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -3378,19 +3378,19 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i #error "SPI_ENDSTOPS requires stepper drivers with SPI support." #endif #else // !SPI_ENDSTOPS - // Stall detection DIAG = HIGH : TMC2209 - // Stall detection DIAG = LOW : TMC2130/TMC2160/TMC2660/TMC5130/TMC5160 + // Stall detection DIAG = HIGH : TMC2209/2240 + // Stall detection DIAG = LOW : TMC2130/2160/2660/5130/5160 #if X_SENSORLESS - #define _HIT_STATE AXIS_DRIVER_TYPE(X,TMC2209) + #define _HIT_STATE AXIS_DRIVER_TYPE(X,TMC2209) || AXIS_DRIVER_TYPE(X,TMC2240) #if X_HOME_TO_MIN && X_MIN_ENDSTOP_HIT_STATE != _HIT_STATE #if _HIT_STATE - #error "SENSORLESS_HOMING requires X_MIN_ENDSTOP_HIT_STATE HIGH for X MIN homing with TMC2209." + #error "SENSORLESS_HOMING requires X_MIN_ENDSTOP_HIT_STATE HIGH for X MIN homing with TMC2209/2240." #else #error "SENSORLESS_HOMING requires X_MIN_ENDSTOP_HIT_STATE LOW for X MIN homing." #endif #elif X_HOME_TO_MAX && X_MAX_ENDSTOP_HIT_STATE != _HIT_STATE #if _HIT_STATE - #error "SENSORLESS_HOMING requires X_MAX_ENDSTOP_HIT_STATE HIGH for X MAX homing with TMC2209." + #error "SENSORLESS_HOMING requires X_MAX_ENDSTOP_HIT_STATE HIGH for X MAX homing with TMC2209/2240." #else #error "SENSORLESS_HOMING requires X_MAX_ENDSTOP_HIT_STATE LOW for X MAX homing." #endif @@ -3399,16 +3399,16 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i #endif #if Y_SENSORLESS - #define _HIT_STATE AXIS_DRIVER_TYPE(Y,TMC2209) + #define _HIT_STATE AXIS_DRIVER_TYPE(Y,TMC2209) || AXIS_DRIVER_TYPE(Y,TMC2240) #if Y_HOME_TO_MIN && Y_MIN_ENDSTOP_HIT_STATE != _HIT_STATE #if _HIT_STATE - #error "SENSORLESS_HOMING requires Y_MIN_ENDSTOP_HIT_STATE HIGH for Y MIN homing with TMC2209." + #error "SENSORLESS_HOMING requires Y_MIN_ENDSTOP_HIT_STATE HIGH for Y MIN homing with TMC2209/2240." #else #error "SENSORLESS_HOMING requires Y_MIN_ENDSTOP_HIT_STATE LOW for Y MIN homing." #endif #elif Y_HOME_TO_MAX && Y_MAX_ENDSTOP_HIT_STATE != _HIT_STATE #if _HIT_STATE - #error "SENSORLESS_HOMING requires Y_MAX_ENDSTOP_HIT_STATE HIGH for Y MAX homing with TMC2209." + #error "SENSORLESS_HOMING requires Y_MAX_ENDSTOP_HIT_STATE HIGH for Y MAX homing with TMC2209/2240." #else #error "SENSORLESS_HOMING requires Y_MAX_ENDSTOP_HIT_STATE LOW for Y MAX homing." #endif @@ -3417,16 +3417,16 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i #endif #if Z_SENSORLESS - #define _HIT_STATE AXIS_DRIVER_TYPE(Z,TMC2209) + #define _HIT_STATE AXIS_DRIVER_TYPE(Z,TMC2209) || AXIS_DRIVER_TYPE(Z,TMC2240) #if Z_HOME_TO_MIN && Z_MIN_ENDSTOP_HIT_STATE != _HIT_STATE #if _HIT_STATE - #error "SENSORLESS_HOMING requires Z_MIN_ENDSTOP_HIT_STATE HIGH for Z MIN homing with TMC2209." + #error "SENSORLESS_HOMING requires Z_MIN_ENDSTOP_HIT_STATE HIGH for Z MIN homing with TMC2209/2240." #else #error "SENSORLESS_HOMING requires Z_MIN_ENDSTOP_HIT_STATE LOW for Z MIN homing." #endif #elif Z_HOME_TO_MAX && Z_MAX_ENDSTOP_HIT_STATE != _HIT_STATE #if _HIT_STATE - #error "SENSORLESS_HOMING requires Z_MAX_ENDSTOP_HIT_STATE HIGH for Z MAX homing with TMC2209." + #error "SENSORLESS_HOMING requires Z_MAX_ENDSTOP_HIT_STATE HIGH for Z MAX homing with TMC2209/2240." #else #error "SENSORLESS_HOMING requires Z_MAX_ENDSTOP_HIT_STATE LOW for Z MAX homing." #endif @@ -3435,16 +3435,16 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i #endif #if I_SENSORLESS - #define _HIT_STATE AXIS_DRIVER_TYPE(I,TMC2209) + #define _HIT_STATE AXIS_DRIVER_TYPE(I,TMC2209) || AXIS_DRIVER_TYPE(I,TMC2240) #if I_HOME_TO_MIN && I_MIN_ENDSTOP_HIT_STATE != _HIT_STATE #if _HIT_STATE - #error "SENSORLESS_HOMING requires I_MIN_ENDSTOP_HIT_STATE HIGH for I MIN homing with TMC2209." + #error "SENSORLESS_HOMING requires I_MIN_ENDSTOP_HIT_STATE HIGH for I MIN homing with TMC2209/2240." #else #error "SENSORLESS_HOMING requires I_MIN_ENDSTOP_HIT_STATE LOW for I MIN homing." #endif #elif I_HOME_TO_MAX && I_MAX_ENDSTOP_HIT_STATE != _HIT_STATE #if _HIT_STATE - #error "SENSORLESS_HOMING requires I_MAX_ENDSTOP_HIT_STATE HIGH for I MAX homing with TMC2209." + #error "SENSORLESS_HOMING requires I_MAX_ENDSTOP_HIT_STATE HIGH for I MAX homing with TMC2209/2240." #else #error "SENSORLESS_HOMING requires I_MAX_ENDSTOP_HIT_STATE LOW for I MAX homing." #endif @@ -3453,16 +3453,16 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i #endif #if J_SENSORLESS - #define _HIT_STATE AXIS_DRIVER_TYPE(J,TMC2209) + #define _HIT_STATE AXIS_DRIVER_TYPE(J,TMC2209) || AXIS_DRIVER_TYPE(J,TMC2240) #if J_HOME_TO_MIN && J_MIN_ENDSTOP_HIT_STATE != _HIT_STATE #if _HIT_STATE - #error "SENSORLESS_HOMING requires J_MIN_ENDSTOP_HIT_STATE HIGH for J MIN homing with TMC2209." + #error "SENSORLESS_HOMING requires J_MIN_ENDSTOP_HIT_STATE HIGH for J MIN homing with TMC2209/2240." #else #error "SENSORLESS_HOMING requires J_MIN_ENDSTOP_HIT_STATE LOW for J MIN homing." #endif #elif J_HOME_TO_MAX && J_MAX_ENDSTOP_HIT_STATE != _HIT_STATE #if _HIT_STATE - #error "SENSORLESS_HOMING requires J_MAX_ENDSTOP_HIT_STATE HIGH for J MAX homing with TMC2209." + #error "SENSORLESS_HOMING requires J_MAX_ENDSTOP_HIT_STATE HIGH for J MAX homing with TMC2209/2240." #else #error "SENSORLESS_HOMING requires J_MAX_ENDSTOP_HIT_STATE LOW for J MAX homing." #endif @@ -3471,16 +3471,16 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i #endif #if K_SENSORLESS - #define _HIT_STATE AXIS_DRIVER_TYPE(K,TMC2209) + #define _HIT_STATE AXIS_DRIVER_TYPE(K,TMC2209) || AXIS_DRIVER_TYPE(K,TMC2240) #if K_HOME_TO_MIN && K_MIN_ENDSTOP_HIT_STATE != _HIT_STATE #if _HIT_STATE - #error "SENSORLESS_HOMING requires K_MIN_ENDSTOP_HIT_STATE HIGH for K MIN homing with TMC2209." + #error "SENSORLESS_HOMING requires K_MIN_ENDSTOP_HIT_STATE HIGH for K MIN homing with TMC2209/2240." #else #error "SENSORLESS_HOMING requires K_MIN_ENDSTOP_HIT_STATE LOW for K MIN homing." #endif #elif K_HOME_TO_MAX && K_MAX_ENDSTOP_HIT_STATE != _HIT_STATE #if _HIT_STATE - #error "SENSORLESS_HOMING requires K_MAX_ENDSTOP_HIT_STATE HIGH for K MAX homing with TMC2209." + #error "SENSORLESS_HOMING requires K_MAX_ENDSTOP_HIT_STATE HIGH for K MAX homing with TMC2209/2240." #else #error "SENSORLESS_HOMING requires K_MAX_ENDSTOP_HIT_STATE LOW for K MAX homing." #endif @@ -3489,16 +3489,16 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i #endif #if U_SENSORLESS - #define _HIT_STATE AXIS_DRIVER_TYPE(U,TMC2209) + #define _HIT_STATE AXIS_DRIVER_TYPE(U,TMC2209) || AXIS_DRIVER_TYPE(U,TMC2240) #if U_HOME_TO_MIN && U_MIN_ENDSTOP_HIT_STATE != _HIT_STATE #if _HIT_STATE - #error "SENSORLESS_HOMING requires U_MIN_ENDSTOP_HIT_STATE HIGH for U MIN homing with TMC2209." + #error "SENSORLESS_HOMING requires U_MIN_ENDSTOP_HIT_STATE HIGH for U MIN homing with TMC2209/2240." #else #error "SENSORLESS_HOMING requires U_MIN_ENDSTOP_HIT_STATE LOW for U MIN homing." #endif #elif U_HOME_TO_MAX && U_MAX_ENDSTOP_HIT_STATE != _HIT_STATE #if _HIT_STATE - #error "SENSORLESS_HOMING requires U_MAX_ENDSTOP_HIT_STATE HIGH for U MAX homing with TMC2209." + #error "SENSORLESS_HOMING requires U_MAX_ENDSTOP_HIT_STATE HIGH for U MAX homing with TMC2209/2240." #else #error "SENSORLESS_HOMING requires U_MAX_ENDSTOP_HIT_STATE LOW for U MAX homing." #endif @@ -3507,16 +3507,16 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i #endif #if V_SENSORLESS - #define _HIT_STATE AXIS_DRIVER_TYPE(V,TMC2209) + #define _HIT_STATE AXIS_DRIVER_TYPE(V,TMC2209) || AXIS_DRIVER_TYPE(V,TMC2240) #if V_HOME_TO_MIN && V_MIN_ENDSTOP_HIT_STATE != _HIT_STATE #if _HIT_STATE - #error "SENSORLESS_HOMING requires V_MIN_ENDSTOP_HIT_STATE HIGH for V MIN homing with TMC2209." + #error "SENSORLESS_HOMING requires V_MIN_ENDSTOP_HIT_STATE HIGH for V MIN homing with TMC2209/2240." #else #error "SENSORLESS_HOMING requires V_MIN_ENDSTOP_HIT_STATE LOW for V MIN homing." #endif #elif V_HOME_TO_MAX && V_MAX_ENDSTOP_HIT_STATE != _HIT_STATE #if _HIT_STATE - #error "SENSORLESS_HOMING requires V_MAX_ENDSTOP_HIT_STATE HIGH for V MAX homing with TMC2209." + #error "SENSORLESS_HOMING requires V_MAX_ENDSTOP_HIT_STATE HIGH for V MAX homing with TMC2209/2240." #else #error "SENSORLESS_HOMING requires V_MAX_ENDSTOP_HIT_STATE LOW for V MAX homing." #endif @@ -3525,16 +3525,16 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i #endif #if W_SENSORLESS - #define _HIT_STATE AXIS_DRIVER_TYPE(W,TMC2209) + #define _HIT_STATE AXIS_DRIVER_TYPE(W,TMC2209) || AXIS_DRIVER_TYPE(W,TMC2240) #if W_HOME_TO_MIN && W_MIN_ENDSTOP_HIT_STATE != _HIT_STATE #if _HIT_STATE - #error "SENSORLESS_HOMING requires W_MIN_ENDSTOP_HIT_STATE HIGH for W MIN homing with TMC2209." + #error "SENSORLESS_HOMING requires W_MIN_ENDSTOP_HIT_STATE HIGH for W MIN homing with TMC2209/2240." #else #error "SENSORLESS_HOMING requires W_MIN_ENDSTOP_HIT_STATE LOW for W MIN homing." #endif #elif W_HOME_TO_MAX && W_MAX_ENDSTOP_HIT_STATE != _HIT_STATE #if _HIT_STATE - #error "SENSORLESS_HOMING requires W_MAX_ENDSTOP_HIT_STATE HIGH for W MAX homing with TMC2209." + #error "SENSORLESS_HOMING requires W_MAX_ENDSTOP_HIT_STATE HIGH for W MAX homing with TMC2209/2240." #else #error "SENSORLESS_HOMING requires W_MAX_ENDSTOP_HIT_STATE LOW for W MAX homing." #endif @@ -3631,11 +3631,11 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i // Other TMC feature requirements #if ENABLED(SENSORLESS_HOMING) && !HAS_STALLGUARD - #error "SENSORLESS_HOMING requires TMC2130, TMC2160, TMC2209, TMC2660, or TMC5160 stepper drivers." + #error "SENSORLESS_HOMING requires TMC2130, TMC2160, TMC2209, TMC2240, TMC2660, or TMC5160 stepper drivers." #elif ENABLED(SENSORLESS_PROBING) && !HAS_STALLGUARD - #error "SENSORLESS_PROBING requires TMC2130, TMC2160, TMC2209, TMC2660, or TMC5160 stepper drivers." + #error "SENSORLESS_PROBING requires TMC2130, TMC2160, TMC2209, TMC2240, TMC2660, or TMC5160 stepper drivers." #elif STEALTHCHOP_ENABLED && !HAS_STEALTHCHOP - #error "STEALTHCHOP requires TMC2130, TMC2160, TMC2208, TMC2209, or TMC5160 stepper drivers." + #error "STEALTHCHOP requires TMC2130, TMC2160, TMC2208, TMC2209, TMC2240, or TMC5160 stepper drivers." #endif /** diff --git a/Marlin/src/module/stepper/trinamic.cpp b/Marlin/src/module/stepper/trinamic.cpp index 3ec8ff4325..0f4a8aa89c 100644 --- a/Marlin/src/module/stepper/trinamic.cpp +++ b/Marlin/src/module/stepper/trinamic.cpp @@ -40,15 +40,37 @@ enum StealthIndex : uint8_t { }; #define TMC_INIT(ST, STEALTH_INDEX) tmc_init(stepper##ST, ST##_CURRENT, ST##_MICROSTEPS, ST##_HYBRID_THRESHOLD, stealthchop_by_axis[STEALTH_INDEX], chopper_timing_##ST, ST##_INTERPOLATE, ST##_HOLD_MULTIPLIER) +// // IC = TMC model number // ST = Stepper object letter // L = Label characters // AI = Axis Enum Index // SWHW = SW/SH UART selection +// + #if ENABLED(TMC_USE_SW_SPI) - #define __TMC_SPI_DEFINE(IC, ST, L, AI) TMCMarlin stepper##ST(ST##_CS_PIN, float(ST##_RSENSE), TMC_SPI_MOSI, TMC_SPI_MISO, TMC_SPI_SCK, ST##_CHAIN_POS) + #define __TMC_SPI_RSENSE_DEFINE(IC, ST, L, LI, AI) TMCMarlin stepper##ST(ST##_CS_PIN, float(ST##_RSENSE), TMC_SPI_MOSI, TMC_SPI_MISO, TMC_SPI_SCK, ST##_CHAIN_POS) + #define __TMC_SPI_DEFINE_TMC2240(IC, ST, L, LI, AI) TMCMarlin stepper##ST(ST##_CS_PIN, TMC_SPI_MOSI, TMC_SPI_MISO, TMC_SPI_SCK, ST##_CHAIN_POS) #else - #define __TMC_SPI_DEFINE(IC, ST, L, AI) TMCMarlin stepper##ST(ST##_CS_PIN, float(ST##_RSENSE), ST##_CHAIN_POS) + #define __TMC_SPI_RSENSE_DEFINE(IC, ST, L, LI, AI) TMCMarlin stepper##ST(ST##_CS_PIN, float(ST##_RSENSE), ST##_CHAIN_POS) + #define __TMC_SPI_DEFINE_TMC2240(IC, ST, L, LI, AI) TMCMarlin stepper##ST(ST##_CS_PIN, ST##_CHAIN_POS) +#endif +#define __TMC_SPI_DEFINE_TMC2100 __TMC_SPI_RSENSE_DEFINE +#define __TMC_SPI_DEFINE_TMC2130 __TMC_SPI_RSENSE_DEFINE +#define __TMC_SPI_DEFINE_TMC2160 __TMC_SPI_RSENSE_DEFINE +#define __TMC_SPI_DEFINE_TMC2208 __TMC_SPI_RSENSE_DEFINE +#define __TMC_SPI_DEFINE_TMC2209 __TMC_SPI_RSENSE_DEFINE +#define __TMC_SPI_DEFINE_TMC2660 __TMC_SPI_RSENSE_DEFINE +#define __TMC_SPI_DEFINE_TMC5130 __TMC_SPI_RSENSE_DEFINE +#define __TMC_SPI_DEFINE_TMC5160 __TMC_SPI_RSENSE_DEFINE + +#define __TMC_SPI_DEFINE(IC, ST, LandI, AI) __TMC_SPI_DEFINE_##IC(IC, ST, LandI, AI) +#define _TMC_SPI_DEFINE(IC, ST, AI) __TMC_SPI_DEFINE(IC, ST, TMC_##ST##_LABEL, AI) +#define TMC_SPI_DEFINE(ST, AI) _TMC_SPI_DEFINE(ST##_DRIVER_TYPE, ST, AI##_AXIS) +#if ENABLED(DISTINCT_E_FACTORS) + #define TMC_SPI_DEFINE_E(AI) TMC_SPI_DEFINE(E##AI, E##AI) +#else + #define TMC_SPI_DEFINE_E(AI) TMC_SPI_DEFINE(E##AI, E) #endif #if ENABLED(TMC_SERIAL_MULTIPLEXER) @@ -59,17 +81,11 @@ enum StealthIndex : uint8_t { #define TMC_UART_SW_DEFINE(IC, ST, L, AI) TMCMarlin stepper##ST(ST##_SERIAL_RX_PIN, ST##_SERIAL_TX_PIN, float(ST##_RSENSE), ST##_SLAVE_ADDRESS) -#define _TMC_SPI_DEFINE(IC, ST, AI) __TMC_SPI_DEFINE(IC, ST, TMC_##ST##_LABEL, AI) -#define TMC_SPI_DEFINE(ST, AI) _TMC_SPI_DEFINE(ST##_DRIVER_TYPE, ST, AI##_AXIS) - #define _TMC_UART_DEFINE(SWHW, IC, ST, AI) TMC_UART_##SWHW##_DEFINE(IC, ST, TMC_##ST##_LABEL, AI) #define TMC_UART_DEFINE(SWHW, ST, AI) _TMC_UART_DEFINE(SWHW, ST##_DRIVER_TYPE, ST, AI##_AXIS) - #if ENABLED(DISTINCT_E_FACTORS) - #define TMC_SPI_DEFINE_E(AI) TMC_SPI_DEFINE(E##AI, E##AI) #define TMC_UART_DEFINE_E(SWHW, AI) TMC_UART_DEFINE(SWHW, E##AI, E##AI) #else - #define TMC_SPI_DEFINE_E(AI) TMC_SPI_DEFINE(E##AI, E) #define TMC_UART_DEFINE_E(SWHW, AI) TMC_UART_DEFINE(SWHW, E##AI, E) #endif @@ -219,7 +235,10 @@ enum StealthIndex : uint8_t { #if HAS_DRIVER(TMC2130) template - void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate, float hold_multiplier) { + void tmc_init(TMCMarlin &st, + const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, + const chopper_timing_t &chop_init, const bool interpolate, float hold_multiplier + ) { st.begin(); CHOPCONF_t chopconf{0}; @@ -254,7 +273,10 @@ enum StealthIndex : uint8_t { #if HAS_DRIVER(TMC2160) template - void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate, float hold_multiplier) { + void tmc_init(TMCMarlin &st, + const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, + const chopper_timing_t &chop_init, const bool interpolate, float hold_multiplier + ) { st.begin(); CHOPCONF_t chopconf{0}; @@ -670,7 +692,10 @@ enum StealthIndex : uint8_t { #if HAS_DRIVER(TMC2208) template - void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate, float hold_multiplier) { + void tmc_init(TMCMarlin &st, + const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, + const chopper_timing_t &chop_init, const bool interpolate, float hold_multiplier + ) { TMC2208_n::GCONF_t gconf{0}; gconf.pdn_disable = true; // Use UART gconf.mstep_reg_select = true; // Select microsteps with UART @@ -712,7 +737,10 @@ enum StealthIndex : uint8_t { #if HAS_DRIVER(TMC2209) template - void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate, float hold_multiplier) { + void tmc_init(TMCMarlin &st, + const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, + const chopper_timing_t &chop_init, const bool interpolate, float hold_multiplier + ) { TMC2208_n::GCONF_t gconf{0}; gconf.pdn_disable = true; // Use UART gconf.mstep_reg_select = true; // Select microsteps with UART @@ -752,9 +780,58 @@ enum StealthIndex : uint8_t { } #endif // TMC2209 +#if HAS_DRIVER(TMC2240) + template + void tmc_init(TMCMarlin &st, + const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, + const chopper_timing_t &chop_init, const bool interpolate, float hold_multiplier + ) { + st.begin(); + + st.Rref = TMC2240_Rref; + TMC2240_n::DRV_CONF_t drv_conf{0}; + drv_conf.current_range = TMC2240_CURRENT_RANGE; + drv_conf.slope_control = TMC2240_SLOPE_CONTROL; + st.DRV_CONF(drv_conf.sr); + + CHOPCONF_t chopconf{0}; + chopconf.tbl = 0b01; + chopconf.toff = chop_init.toff; + chopconf.intpol = interpolate; + chopconf.hend = chop_init.hend + 3; + chopconf.hstrt = chop_init.hstrt - 1; + TERN_(EDGE_STEPPING, chopconf.dedge = true); + st.CHOPCONF(chopconf.sr); + + st.rms_current(mA, hold_multiplier); + st.microsteps(microsteps); + st.iholddelay(10); + st.TPOWERDOWN(128); // ~2s until driver lowers to hold current + + st.en_pwm_mode(stealth); + st.stored.stealthChop_enabled = stealth; + + TMC2240_n::PWMCONF_t pwmconf{0}; + pwmconf.pwm_lim = 12; + pwmconf.pwm_reg = 8; + pwmconf.pwm_autograd = true; + pwmconf.pwm_autoscale = true; + pwmconf.pwm_freq = 0b01; + pwmconf.pwm_grad = 14; + pwmconf.pwm_ofs = 36; + st.PWMCONF(pwmconf.sr); + + TERN(HYBRID_THRESHOLD, st.set_pwm_thrs(hyb_thrs), UNUSED(hyb_thrs)); + st.GSTAT(); // Clear GSTAT + } +#endif // TMC2240 + #if HAS_DRIVER(TMC2660) template - void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t, const bool, const chopper_timing_t &chop_init, const bool interpolate, float hold_multiplier) { + void tmc_init(TMCMarlin &st, + const uint16_t mA, const uint16_t microsteps, const uint32_t, const bool, + const chopper_timing_t &chop_init, const bool interpolate, float hold_multiplier + ) { st.begin(); TMC2660_n::CHOPCONF_t chopconf{0}; @@ -776,7 +853,10 @@ enum StealthIndex : uint8_t { #if HAS_DRIVER(TMC5130) template - void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate, float hold_multiplier) { + void tmc_init(TMCMarlin &st, + const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, + const chopper_timing_t &chop_init, const bool interpolate, float hold_multiplier + ) { st.begin(); CHOPCONF_t chopconf{0}; @@ -811,7 +891,10 @@ enum StealthIndex : uint8_t { #if HAS_DRIVER(TMC5160) template - void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate, float hold_multiplier) { + void tmc_init(TMCMarlin &st, + const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, + const chopper_timing_t &chop_init, const bool interpolate, float hold_multiplier + ) { st.begin(); CHOPCONF_t chopconf{0}; @@ -842,6 +925,7 @@ enum StealthIndex : uint8_t { st.PWMCONF(pwmconf.sr); TERN(HYBRID_THRESHOLD, st.set_pwm_thrs(hyb_thrs), UNUSED(hyb_thrs)); + st.GSTAT(); // Clear GSTAT } #endif // TMC5160 diff --git a/Marlin/src/module/stepper/trinamic.h b/Marlin/src/module/stepper/trinamic.h index 0fd48f18cb..d43a1d231b 100644 --- a/Marlin/src/module/stepper/trinamic.h +++ b/Marlin/src/module/stepper/trinamic.h @@ -38,6 +38,7 @@ #define CLASS_TMC2160 TMC2160Stepper #define CLASS_TMC2208 TMC2208Stepper #define CLASS_TMC2209 TMC2209Stepper +#define CLASS_TMC2240 TMC2240Stepper #define CLASS_TMC2660 TMC2660Stepper #define CLASS_TMC5130 TMC5130Stepper #define CLASS_TMC5160 TMC5160Stepper diff --git a/buildroot/tests/BTT_BTT002 b/buildroot/tests/BTT_BTT002 index 121aace895..054b179bfe 100755 --- a/buildroot/tests/BTT_BTT002 +++ b/buildroot/tests/BTT_BTT002 @@ -12,7 +12,8 @@ set -e restore_configs opt_set MOTHERBOARD BOARD_BTT_BTT002_V1_0 \ SERIAL_PORT 1 \ - X_DRIVER_TYPE TMC2209 Y_DRIVER_TYPE TMC2130 + X_DRIVER_TYPE TMC2209 Y_DRIVER_TYPE TMC2130 Z_DRIVER_TYPE TMC2240 \ + X_CURRENT_HOME '(X_CURRENT - 100)' Y_CURRENT_HOME '(Y_CURRENT - 100)' opt_enable SENSORLESS_HOMING X_STALL_SENSITIVITY Y_STALL_SENSITIVITY SPI_ENDSTOPS exec_test $1 $2 "BigTreeTech BTT002 Default Configuration plus TMC steppers" "$3" From db137df6df5e27dc23d68ef31a6be20ea185bd74 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 24 May 2025 03:12:25 -0500 Subject: [PATCH 052/102] =?UTF-8?q?=F0=9F=94=A8=20TMC2240=20Makefile=20upd?= =?UTF-8?q?ate?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Makefile | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/Makefile b/Marlin/Makefile index ce26bd3572..9acab53673 100644 --- a/Marlin/Makefile +++ b/Marlin/Makefile @@ -798,10 +798,10 @@ endif ifeq ($(TMC), 1) LIB_CXXSRC += TMCStepper.cpp COOLCONF.cpp DRV_STATUS.cpp IHOLD_IRUN.cpp \ - CHOPCONF.cpp GCONF.cpp PWMCONF.cpp DRV_CONF.cpp DRVCONF.cpp DRVCTRL.cpp \ - DRVSTATUS.cpp ENCMODE.cpp RAMP_STAT.cpp SGCSCONF.cpp SHORT_CONF.cpp \ - SMARTEN.cpp SW_MODE.cpp SW_SPI.cpp TMC2130Stepper.cpp TMC2208Stepper.cpp \ - TMC2209Stepper.cpp TMC2660Stepper.cpp TMC5130Stepper.cpp TMC5160Stepper.cpp + CHOPCONF.cpp GCONF.cpp PWMCONF.cpp DRV_CONF.cpp DRVCONF.cpp DRVCTRL.cpp DRVSTATUS.cpp \ + GLOBAL_SCALER.cpp SLAVECONF.cpp IOIN.cpp ENCMODE.cpp RAMP_STAT.cpp SGCSCONF.cpp \ + SHORT_CONF.cpp SMARTEN.cpp SW_MODE.cpp SW_SPI.cpp TMC2130Stepper.cpp TMC2208Stepper.cpp \ + TMC2209Stepper.cpp TMC2240Stepper.cpp TMC2660Stepper.cpp TMC5130Stepper.cpp TMC5160Stepper.cpp endif ifeq ($(RELOC_WORKAROUND), 1) From 86c564121e111c94a9bc4d2488ccbf336ba7184c Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Sat, 24 May 2025 13:38:51 -0700 Subject: [PATCH 053/102] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20Bluesky=20badge=20?= =?UTF-8?q?(#27879)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 50dfddda9a..69979f4884 100644 --- a/README.md +++ b/README.md @@ -9,7 +9,7 @@ CI Status GitHub Sponsors
- Follow marlinfw.org on Bluesky + Follow marlinfw.org on Bluesky Follow MarlinFirmware on Mastodon

From d76c8c1fbd8d1d1e9fd186d6a2f42f3d0b8d76be Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Sun, 25 May 2025 09:49:44 +1200 Subject: [PATCH 054/102] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20ProUI=20Linear=20A?= =?UTF-8?q?dvance=20menu=20(#27878)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to #27818 --- Marlin/src/lcd/e3v2/proui/dwin.cpp | 6 ++++-- buildroot/tests/STM32F103RE_creality | 5 +++-- 2 files changed, 7 insertions(+), 4 deletions(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 7574439051..08782553ba 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -3546,7 +3546,8 @@ void drawTuneMenu() { EDIT_ITEM(ICON_JDmm, MSG_JUNCTION_DEVIATION, onDrawPFloat3Menu, setJDmm, &planner.junction_deviation_mm); #endif #if ENABLED(PROUI_ITEM_ADVK) - EDIT_ITEM(ICON_MaxAccelerated, MSG_ADVANCE_K, onDrawPFloat3Menu, setLA_K, &planner.get_advance_k()); + float editable_decimal = planner.get_advance_k(); + EDIT_ITEM(ICON_MaxAccelerated, MSG_ADVANCE_K, onDrawPFloat3Menu, setLA_K, &editable_decimal); #endif #if HAS_LOCKSCREEN MENU_ITEM(ICON_Lock, MSG_LOCKSCREEN, onDrawMenuItem, dwinLockScreen); @@ -3684,7 +3685,8 @@ void drawMotionMenu() { MENU_ITEM(ICON_Homing, MSG_HOMING_FEEDRATE, onDrawSubMenu, drawHomingFRMenu); #endif #if ENABLED(LIN_ADVANCE) - EDIT_ITEM(ICON_MaxAccelerated, MSG_ADVANCE_K, onDrawPFloat3Menu, setLA_K, &planner.get_advance_k()); + float editable_decimal = planner.get_advance_k(); + EDIT_ITEM(ICON_MaxAccelerated, MSG_ADVANCE_K, onDrawPFloat3Menu, setLA_K, &editable_decimal); #endif #if ENABLED(SHAPING_MENU) MENU_ITEM(ICON_InputShaping, MSG_INPUT_SHAPING, onDrawSubMenu, drawInputShaping_menu); diff --git a/buildroot/tests/STM32F103RE_creality b/buildroot/tests/STM32F103RE_creality index 0a1b1bc79d..5681688929 100755 --- a/buildroot/tests/STM32F103RE_creality +++ b/buildroot/tests/STM32F103RE_creality @@ -26,9 +26,10 @@ exec_test $1 $2 "Ender-3 V2 - MarlinUI (Games, UBL+BLTOUCH, MPCTEMP, LCD_ENDSTOP use_example_configs "Creality/Ender-3 S1/STM32F1" opt_disable DWIN_CREALITY_LCD Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN AUTO_BED_LEVELING_BILINEAR CANCEL_OBJECTS FWRETRACT EVENT_GCODE_SD_ABORT -opt_enable DWIN_LCD_PROUI INDIVIDUAL_AXIS_HOMING_SUBMENU SET_PROGRESS_MANUALLY SET_PROGRESS_PERCENT STATUS_MESSAGE_SCROLLING \ +opt_enable DWIN_LCD_PROUI INDIVIDUAL_AXIS_HOMING_SUBMENU PID_AUTOTUNE_MENU PID_EDIT_MENU \ + SET_PROGRESS_MANUALLY SET_PROGRESS_PERCENT STATUS_MESSAGE_SCROLLING \ SOUND_MENU_ITEM PRINTCOUNTER NOZZLE_PARK_FEATURE ADVANCED_PAUSE_FEATURE FILAMENT_RUNOUT_SENSOR \ - BLTOUCH Z_SAFE_HOMING AUTO_BED_LEVELING_UBL MESH_EDIT_MENU LCD_BED_TRAMMING \ + BLTOUCH Z_SAFE_HOMING AUTO_BED_LEVELING_UBL MESH_EDIT_MENU LCD_BED_TRAMMING LIN_ADVANCE \ LIMITED_MAX_FR_EDITING LIMITED_MAX_ACCEL_EDITING LIMITED_JERK_EDITING BAUD_RATE_GCODE \ CASE_LIGHT_ENABLE CASE_LIGHT_MENU CASE_LIGHT_NO_BRIGHTNESS opt_set PREHEAT_3_LABEL '"CUSTOM"' PREHEAT_3_TEMP_HOTEND 240 PREHEAT_3_TEMP_BED 60 PREHEAT_3_FAN_SPEED 128 BOOTSCREEN_TIMEOUT 1100 CASE_LIGHT_PIN 4 From 4f93f31af0183af5a89d7ceb095d20924ea9b91e Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Sun, 25 May 2025 09:53:52 +1200 Subject: [PATCH 055/102] =?UTF-8?q?=F0=9F=94=A8=20Fix=20Windows/ReARM=20up?= =?UTF-8?q?load=20(#27872)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/LPC1768/upload_extra_script.py | 19 +++++++++++++------ 1 file changed, 13 insertions(+), 6 deletions(-) diff --git a/Marlin/src/HAL/LPC1768/upload_extra_script.py b/Marlin/src/HAL/LPC1768/upload_extra_script.py index ce241c4658..f9be140592 100755 --- a/Marlin/src/HAL/LPC1768/upload_extra_script.py +++ b/Marlin/src/HAL/LPC1768/upload_extra_script.py @@ -54,18 +54,25 @@ if pioutil.is_pio_build(): final_drive_name = drive + ':' # print ('disc check: {}'.format(final_drive_name)) try: - volume_info = str(subprocess.check_output('cmd /C dir ' + final_drive_name, stderr=subprocess.STDOUT)) + volume_info = str(subprocess.check_output('cmd /C vol ' + final_drive_name, stderr=subprocess.STDOUT)) except Exception as e: print ('error:{}'.format(e)) continue else: - if target_drive in volume_info and not target_file_found: # set upload if not found target file yet - target_drive_found = True + if target_drive in volume_info: # set upload upload_disk = PureWindowsPath(final_drive_name) - if target_filename in volume_info: - if not target_file_found: + target_drive_found = True + break + try: + dir_info = str(subprocess.check_output('cmd /C dir ' + final_drive_name, stderr=subprocess.STDOUT)) + except Exception as e: + print ('error:{}'.format(e)) + continue + else: + if target_filename in dir_info: upload_disk = PureWindowsPath(final_drive_name) - target_file_found = True + target_file_found = True + break elif current_OS == 'Linux': # From 2976bb48ede7834512551a921b04e260f73acf07 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 24 May 2025 16:57:03 -0500 Subject: [PATCH 056/102] =?UTF-8?q?=F0=9F=94=A8=20Better=20FT=20Motion=20m?= =?UTF-8?q?enu=20string=20code?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/menu/menu_motion.cpp | 96 ++++++++++++++++++++++------- 1 file changed, 74 insertions(+), 22 deletions(-) diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index e2adbfded2..956b58c633 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -401,19 +401,48 @@ void menu_move() { #endif // HAS_DYNAMIC_FREQ + // Suppress warning about storing a stack address in a static string pointer + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wdangling-pointer" + + #if ALL(__AVR__, HAS_MARLINUI_U8GLIB) && DISABLED(REDUCE_CODE_SIZE_FOR_FT_MOTION_ON_AVR) + #define CACHE_PREV_STRING + #endif + void menu_ft_motion() { // Define stuff ahead of the menu loop - MString<20> shaper_name[NUM_AXES_SHAPED] {}; - #if HAS_X_AXIS - for (uint_fast8_t a = X_AXIS; a < NUM_AXES_SHAPED; ++a) - shaper_name[a] = get_shaper_name(AxisEnum(a)); - #endif - #if HAS_DYNAMIC_FREQ - MString<20> dmode = get_dyn_freq_mode_name(); - #endif - ft_config_t &c = ftMotion.cfg; + #ifdef __AVR__ + // Copy Flash strings to RAM for C-string substitution + // For U8G paged rendering check and skip extra string copy + #if HAS_X_AXIS + MString<20> shaper_name; + TERN_(CACHE_PREV_STRING, int8_t prev_a = -1); + auto _shaper_name = [&](const AxisEnum a) { + if (TERN1(CACHE_PREV_STRING, a != prev_a)) { + TERN_(CACHE_PREV_STRING, prev_a = a); + shaper_name = get_shaper_name(a); + } + return shaper_name; + }; + #endif + #if HAS_DYNAMIC_FREQ + MString<20> dmode; + TERN_(CACHE_PREV_STRING, bool got_d = false); + auto _dmode = [&]{ + if (TERN1(CACHE_PREV_STRING, !got_d)) { + TERN_(CACHE_PREV_STRING, got_d = true); + dmode = get_dyn_freq_mode_name(); + } + return dmode; + }; + #endif + #else + auto _shaper_name = [](const AxisEnum a) { return get_shaper_name(a); }; + auto _dmode = []{ return get_dyn_freq_mode_name(); }; + #endif + START_MENU(); BACK_ITEM(MSG_MOTION); @@ -426,7 +455,7 @@ void menu_move() { // Show only when FT Motion is active (or optionally always show) if (c.active || ENABLED(FT_MOTION_NO_MENU_TOGGLE)) { #if HAS_X_AXIS - SUBMENU_N_S(X_AXIS, shaper_name[X_AXIS], MSG_FTM_CMPN_MODE, menu_ftm_shaper_x); + SUBMENU_N_S(X_AXIS, _shaper_name(X_AXIS), MSG_FTM_CMPN_MODE, menu_ftm_shaper_x); if (AXIS_HAS_SHAPER(X)) { EDIT_ITEM_FAST_N(float42_52, X_AXIS, MSG_FTM_BASE_FREQ_N, &c.baseFreq.x, FTM_MIN_SHAPE_FREQ, (FTM_FS) / 2, ftMotion.update_shaping_params); @@ -436,7 +465,7 @@ void menu_move() { } #endif #if HAS_Y_AXIS - SUBMENU_N_S(Y_AXIS, shaper_name[Y_AXIS], MSG_FTM_CMPN_MODE, menu_ftm_shaper_y); + SUBMENU_N_S(Y_AXIS, _shaper_name(Y_AXIS), MSG_FTM_CMPN_MODE, menu_ftm_shaper_y); if (AXIS_HAS_SHAPER(Y)) { EDIT_ITEM_FAST_N(float42_52, Y_AXIS, MSG_FTM_BASE_FREQ_N, &c.baseFreq.y, FTM_MIN_SHAPE_FREQ, (FTM_FS) / 2, ftMotion.update_shaping_params); @@ -447,7 +476,7 @@ void menu_move() { #endif #if HAS_DYNAMIC_FREQ - SUBMENU_S(dmode, MSG_FTM_DYN_MODE, menu_ftm_dyn_mode); + SUBMENU_S(_dmode(), MSG_FTM_DYN_MODE, menu_ftm_dyn_mode); if (c.dynFreqMode != dynFreqMode_DISABLED) { #if HAS_X_AXIS EDIT_ITEM_FAST_N(float42_52, X_AXIS, MSG_FTM_DFREQ_K_N, &c.dynFreqK.x, 0.0f, 20.0f); @@ -469,13 +498,34 @@ void menu_move() { void menu_tune_ft_motion() { // Define stuff ahead of the menu loop - MString<20> shaper_name[NUM_AXES_SHAPED] {}; - #if HAS_X_AXIS - for (uint_fast8_t a = X_AXIS; a < NUM_AXES_SHAPED; ++a) - shaper_name[a] = get_shaper_name(AxisEnum(a)); - #endif - #if HAS_DYNAMIC_FREQ - MString<20> dmode = get_dyn_freq_mode_name(); + #ifdef __AVR__ + // Copy Flash strings to RAM for C-string substitution + // For U8G paged rendering check and skip extra string copy + #if HAS_X_AXIS + MString<20> shaper_name; + TERN_(CACHE_PREV_STRING, int8_t prev_a = -1); + auto _shaper_name = [&](const AxisEnum a) { + if (TERN1(CACHE_PREV_STRING, a != prev_a)) { + TERN_(CACHE_PREV_STRING, prev_a = a); + shaper_name = get_shaper_name(a); + } + return shaper_name; + }; + #endif + #if HAS_DYNAMIC_FREQ + MString<20> dmode; + TERN_(CACHE_PREV_STRING, bool got_d = false); + auto _dmode = [&]{ + if (TERN1(CACHE_PREV_STRING, !got_d)) { + TERN_(CACHE_PREV_STRING, got_d = true); + dmode = get_dyn_freq_mode_name(); + } + return dmode; + }; + #endif + #else + auto _shaper_name = [](const AxisEnum a) { return get_shaper_name(a); }; + auto _dmode = []{ return get_dyn_freq_mode_name(); }; #endif #if HAS_EXTRUDERS @@ -486,13 +536,13 @@ void menu_move() { BACK_ITEM(MSG_TUNE); #if HAS_X_AXIS - SUBMENU_N_S(X_AXIS, shaper_name[X_AXIS], MSG_FTM_CMPN_MODE, menu_ftm_shaper_x); + SUBMENU_N_S(X_AXIS, _shaper_name(X_AXIS), MSG_FTM_CMPN_MODE, menu_ftm_shaper_x); #endif #if HAS_Y_AXIS - SUBMENU_N_S(Y_AXIS, shaper_name[Y_AXIS], MSG_FTM_CMPN_MODE, menu_ftm_shaper_y); + SUBMENU_N_S(Y_AXIS, _shaper_name(Y_AXIS), MSG_FTM_CMPN_MODE, menu_ftm_shaper_y); #endif #if HAS_DYNAMIC_FREQ - SUBMENU_S(dmode, MSG_FTM_DYN_MODE, menu_ftm_dyn_mode); + SUBMENU_S(_dmode(), MSG_FTM_DYN_MODE, menu_ftm_dyn_mode); #endif #if HAS_EXTRUDERS EDIT_ITEM(bool, MSG_LINEAR_ADVANCE, &c.linearAdvEna); @@ -503,6 +553,8 @@ void menu_move() { END_MENU(); } + #pragma GCC diagnostic pop + #endif // FT_MOTION_MENU void menu_motion() { From bd9d7a3c4d6b5b974e9dcf2ba90180fb91f6502d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 24 May 2025 17:17:49 -0500 Subject: [PATCH 057/102] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20MKS=20UI=20E=20Max?= =?UTF-8?q?=20Feedrate=20items?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/extui/mks_ui/draw_number_key.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/lcd/extui/mks_ui/draw_number_key.cpp b/Marlin/src/lcd/extui/mks_ui/draw_number_key.cpp index c44cabd10a..a117775793 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_number_key.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_number_key.cpp @@ -243,10 +243,10 @@ static void set_value_confirm() { #if HAS_Z_AXIS case ZMaxFeedRate: planner.settings.max_feedrate_mm_s[Z_AXIS] = atof(key_value); break; #endif - #if HAS_E0_AXIS + #if HAS_EXTRUDERS case E0MaxFeedRate: planner.settings.max_feedrate_mm_s[E_AXIS] = atof(key_value); break; #endif - #if HAS_E1_AXIS + #if HAS_MULTI_EXTRUDER case E1MaxFeedRate: planner.settings.max_feedrate_mm_s[E_AXIS_N(1)] = atof(key_value); break; #endif From 6a871b2879131c23581a0fdc086240994837ba33 Mon Sep 17 00:00:00 2001 From: B Date: Sat, 24 May 2025 17:21:06 -0700 Subject: [PATCH 058/102] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Get?= =?UTF-8?q?=20E=20axis=20in=20FTMotion::loadBlockData=20(#27870)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/module/ft_motion.cpp | 27 ++++++++++++++++++--------- Marlin/src/module/ft_motion.h | 6 ++++++ 2 files changed, 24 insertions(+), 9 deletions(-) diff --git a/Marlin/src/module/ft_motion.cpp b/Marlin/src/module/ft_motion.cpp index 88d2fb60b3..cb31525572 100644 --- a/Marlin/src/module/ft_motion.cpp +++ b/Marlin/src/module/ft_motion.cpp @@ -89,6 +89,12 @@ xyze_long_t FTMotion::steps = { 0 }; // Step count accumulator. uint32_t FTMotion::interpIdx = 0; // Index of current data point being interpolated. +#if ENABLED(DISTINCT_E_FACTORS) + uint8_t FTMotion::block_extruder_axis; // Cached E Axis from last-fetched block +#else + constexpr uint8_t FTMotion::block_extruder_axis; +#endif + // Shaping variables. #if HAS_FTM_SHAPING FTMotion::shaping_t FTMotion::shaping = { @@ -143,6 +149,12 @@ void FTMotion::loop() { continue; } loadBlockData(stepper.current_block); + + // If the endstop is already pressed, endstop interrupts won't invoke + // endstop_triggered and the move will grind. So check here for a + // triggered endstop, which shortly marks the block for discard. + endstops.update(); + blockProcRdy = true; // Some kinematics track axis motion in HX, HY, HZ #if ANY(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY, MARKFORGED_YX) @@ -389,6 +401,7 @@ void FTMotion::reset() { #endif TERN_(HAS_EXTRUDERS, e_raw_z1 = e_advanced_z1 = 0.0f); + TERN_(DISTINCT_E_FACTORS, block_extruder_axis = E_AXIS); axis_move_end_ti.reset(); } @@ -453,13 +466,15 @@ void FTMotion::init() { // Load / convert block data from planner to fixed-time control variables. void FTMotion::loadBlockData(block_t * const current_block) { + // Cache the extruder index for this block + TERN_(DISTINCT_E_FACTORS, block_extruder_axis = E_AXIS_N(current_block->extruder)); const float totalLength = current_block->millimeters, oneOverLength = 1.0f / totalLength; startPosn = endPosn_prevBlock; const xyze_pos_t moveDist = LOGICAL_AXIS_ARRAY( - current_block->steps.e * planner.mm_per_step[E_AXIS_N(current_block->extruder)] * (current_block->direction_bits.e ? 1 : -1), + current_block->steps.e * planner.mm_per_step[block_extruder_axis] * (current_block->direction_bits.e ? 1 : -1), current_block->steps.x * planner.mm_per_step[X_AXIS] * (current_block->direction_bits.x ? 1 : -1), current_block->steps.y * planner.mm_per_step[Y_AXIS] * (current_block->direction_bits.y ? 1 : -1), current_block->steps.z * planner.mm_per_step[Z_AXIS] * (current_block->direction_bits.z ? 1 : -1), @@ -568,12 +583,6 @@ void FTMotion::loadBlockData(block_t * const current_block) { #endif TERN_(HAS_Z_AXIS, _SET_MOVE_END(Z)); SECONDARY_AXIS_MAP(_SET_MOVE_END); - - // If the endstop is already pressed, endstop interrupts won't invoke - // endstop_triggered and the move will grind. So check here for a - // triggered endstop, which shortly marks the block for discard. - endstops.update(); - } // Generate data points of the trajectory. @@ -721,7 +730,7 @@ void FTMotion::convertToSteps(const uint32_t idx) { #if ENABLED(STEPS_ROUNDING) #define TOSTEPS(A,B) int32_t(trajMod.A[idx] * planner.settings.axis_steps_per_mm[B] + (trajMod.A[idx] < 0.0f ? -0.5f : 0.5f)) const xyze_long_t steps_tar = LOGICAL_AXIS_ARRAY( - TOSTEPS(e, E_AXIS_N(stepper.current_block->extruder)), // May be eliminated if guaranteed positive. + TOSTEPS(e, block_extruder_axis), // May be eliminated if guaranteed positive. TOSTEPS(x, X_AXIS), TOSTEPS(y, Y_AXIS), TOSTEPS(z, Z_AXIS), TOSTEPS(i, I_AXIS), TOSTEPS(j, J_AXIS), TOSTEPS(k, K_AXIS), TOSTEPS(u, U_AXIS), TOSTEPS(v, V_AXIS), TOSTEPS(w, W_AXIS) @@ -730,7 +739,7 @@ void FTMotion::convertToSteps(const uint32_t idx) { #else #define TOSTEPS(A,B) int32_t(trajMod.A[idx] * planner.settings.axis_steps_per_mm[B]) - steps.A xyze_long_t delta = LOGICAL_AXIS_ARRAY( - TOSTEPS(e, E_AXIS_N(stepper.current_block->extruder)), + TOSTEPS(e, block_extruder_axis), TOSTEPS(x, X_AXIS), TOSTEPS(y, Y_AXIS), TOSTEPS(z, Z_AXIS), TOSTEPS(i, I_AXIS), TOSTEPS(j, J_AXIS), TOSTEPS(k, K_AXIS), TOSTEPS(u, U_AXIS), TOSTEPS(v, V_AXIS), TOSTEPS(w, W_AXIS) diff --git a/Marlin/src/module/ft_motion.h b/Marlin/src/module/ft_motion.h index f6ce81af12..4cf8017083 100644 --- a/Marlin/src/module/ft_motion.h +++ b/Marlin/src/module/ft_motion.h @@ -169,6 +169,12 @@ class FTMotion { static xyze_long_t steps; + #if ENABLED(DISTINCT_E_FACTORS) + static uint8_t block_extruder_axis; // Cached extruder axis index + #else + static constexpr uint8_t block_extruder_axis = E_AXIS; + #endif + // Shaping variables. #if HAS_FTM_SHAPING From dbd60fb38e865fcbd51b886f421390e78b0743cc Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 25 May 2025 00:35:29 +0000 Subject: [PATCH 059/102] [cron] Bump distribution date (2025-05-25) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index cb96070cc4..82979634d4 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-05-24" +//#define STRING_DISTRIBUTION_DATE "2025-05-25" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 51a13f1947..7c80ca1f17 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-05-24" + #define STRING_DISTRIBUTION_DATE "2025-05-25" #endif /** From 7f9eb688adc69ff51c79ecc30acd703643708c21 Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Tue, 27 May 2025 03:50:22 +1200 Subject: [PATCH 060/102] =?UTF-8?q?=F0=9F=90=9B=20TMC2240:=20The=20Sequel?= =?UTF-8?q?=20(#27880)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/Configuration_adv.h | 8 +-- Marlin/src/core/drivers.h | 6 +- Marlin/src/feature/tmc_util.cpp | 113 +++++++++++++++++++++----------- Marlin/src/feature/tmc_util.h | 3 + Marlin/src/inc/SanityCheck.h | 18 ++--- ini/features.ini | 2 +- 6 files changed, 98 insertions(+), 52 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 93d84d8d9c..fee4c452ab 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -2997,7 +2997,7 @@ /** * Trinamic Smart Drivers * - * To use TMC2130, TMC2160, TMC2660, TMC5130, TMC5160 stepper drivers in SPI mode: + * To use TMC2130, TMC2160, TMC2240, TMC2660, TMC5130, TMC5160 stepper drivers in SPI mode: * - Connect your SPI pins to the Hardware SPI interface on the board. * Some boards have simple jumper connections! See your board's documentation. * - Define the required Stepper CS pins in your `pins_MYBOARD.h` file. @@ -3258,7 +3258,7 @@ // @section tmc/spi /** - * Override default SPI pins for TMC2130, TMC2160, TMC2660, TMC5130 and TMC5160 drivers here. + * Override default SPI pins for TMC2130, TMC2160, TMC2240, TMC2660, TMC5130 and TMC5160 drivers here. * The default pins can be found in your board's pins file. */ //#define X_CS_PIN -1 @@ -3285,7 +3285,7 @@ //#define E7_CS_PIN -1 /** - * Software option for SPI driven drivers (TMC2130, TMC2160, TMC2660, TMC5130 and TMC5160). + * Software option for SPI driven drivers (TMC2130, TMC2160, TMC2240, TMC2660, TMC5130 and TMC5160). * The default SW SPI pins are defined the respective pins files, * but you can override or define them here. */ @@ -3498,7 +3498,7 @@ //#define U_STALL_SENSITIVITY 8 //#define V_STALL_SENSITIVITY 8 //#define W_STALL_SENSITIVITY 8 - //#define SPI_ENDSTOPS // TMC2130/TMC5160 only + //#define SPI_ENDSTOPS // TMC2130, TMC2240, and TMC5160 //#define IMPROVE_HOMING_RELIABILITY #endif diff --git a/Marlin/src/core/drivers.h b/Marlin/src/core/drivers.h index 6b1a70202c..3a53360e26 100644 --- a/Marlin/src/core/drivers.h +++ b/Marlin/src/core/drivers.h @@ -113,9 +113,12 @@ #define HAS_TRINAMIC_STANDALONE 1 #endif -#if HAS_DRIVER(TMC2130) || HAS_DRIVER(TMC2160) || HAS_DRIVER(TMC5130) || HAS_DRIVER(TMC5160) || HAS_DRIVER(TMC2240) +#if HAS_DRIVER(TMC2130) || HAS_DRIVER(TMC2160) || HAS_DRIVER(TMC5130) || HAS_DRIVER(TMC5160) #define HAS_TMCX1X0 1 #endif +#if HAS_TMCX1X0 || HAS_DRIVER(TMC2240) + #define HAS_TMCX1X0_OR_2240 1 +#endif #if HAS_DRIVER(TMC2208) || HAS_DRIVER(TMC2209) #define HAS_TMC220x 1 #endif @@ -207,6 +210,7 @@ #define THRS_TMC2160 255 #define THRS_TMC2208 255 #define THRS_TMC2209 255 +#define THRS_TMC2240 255 #define THRS_TMC2660 65535 #define THRS_TMC5130 65535 #define THRS_TMC5160 65535 diff --git a/Marlin/src/feature/tmc_util.cpp b/Marlin/src/feature/tmc_util.cpp index d920c3a604..fb17e562ad 100644 --- a/Marlin/src/feature/tmc_util.cpp +++ b/Marlin/src/feature/tmc_util.cpp @@ -72,7 +72,7 @@ #endif ; #if ENABLED(TMC_DEBUG) - #if HAS_TMCX1X0 || HAS_TMC220x + #if HAS_TMCX1X0_OR_2240 || HAS_TMC220x uint8_t cs_actual; #endif #if HAS_STALLGUARD @@ -298,7 +298,7 @@ st.printLabel(); SString<60> report(':', pwm_scale); #if ENABLED(TMC_DEBUG) - #if HAS_TMCX1X0 || HAS_TMC220x + #if HAS_TMCX1X0_OR_2240 || HAS_TMC220x report.append('/', data.cs_actual); #endif #if HAS_STALLGUARD @@ -575,6 +575,25 @@ template static void print_vsense(TMC &st) { SERIAL_ECHO(st.vsense() ? F("1=.18") : F("0=.325")); } + #if HAS_DRIVER(TMC2160) + template + void print_vsense(TMCMarlin &) { } + #endif + #if HAS_DRIVER(TMC5160) + template + void print_vsense(TMCMarlin &) { } + #endif + #if HAS_DRIVER(TMC2240) + template + void print_vsense(TMCMarlin &) { } + #endif + + template + void print_cs_actual(TMC &st) { SERIAL_ECHO(st.cs_actual(), F("/31")); } + #if HAS_DRIVER(TMC2240) + template + void print_cs_actual(TMCMarlin &) { } + #endif #if HAS_DRIVER(TMC2130) || HAS_DRIVER(TMC5130) static void _tmc_status(TMC2130Stepper &st, const TMC_debug_enum i) { @@ -600,12 +619,6 @@ #endif #if HAS_DRIVER(TMC2160) || HAS_DRIVER(TMC5160) - template - void print_vsense(TMCMarlin &) { } - - template - void print_vsense(TMCMarlin &) { } - static void _tmc_status(TMC2160Stepper &st, const TMC_debug_enum i) { switch (i) { case TMC_PWM_SCALE: SERIAL_ECHO(st.PWM_SCALE()); break; @@ -676,6 +689,21 @@ #endif // HAS_TMC220x + #if HAS_DRIVER(TMC2240) + static void _tmc_parse_drv_status(TMC2240Stepper, const TMC_drv_status_enum) { } + static void _tmc_status(TMC2240Stepper &st, const TMC_debug_enum i) { + switch (i) { + case TMC_PWM_SCALE_SUM: SERIAL_ECHO(st.pwm_scale_sum()); break; + case TMC_PWM_SCALE_AUTO: SERIAL_ECHO(st.pwm_scale_auto()); break; + case TMC_PWM_OFS_AUTO: SERIAL_ECHO(st.pwm_ofs_auto()); break; + case TMC_PWM_GRAD_AUTO: SERIAL_ECHO(st.pwm_grad_auto()); break; + case TMC_STEALTHCHOP: serialprint_truefalse(st.stealth()); break; + case TMC_INTERPOLATE: serialprint_truefalse(st.intpol()); break; + default: break; + } + } + #endif + #if HAS_DRIVER(TMC2660) static void _tmc_parse_drv_status(TMC2660Stepper, const TMC_drv_status_enum) { } static void _tmc_status(TMC2660Stepper &st, const TMC_debug_enum i) { @@ -686,6 +714,21 @@ } #endif + template + void print_tstep(TMC &st) { + const uint32_t tstep_value = st.TSTEP(); + if (tstep_value != 0xFFFFF) + SERIAL_ECHO(tstep_value); + else + SERIAL_ECHOPGM("max"); + } + void print_tstep(TMC2660Stepper &st) { } + + template + void print_blank_time(TMC &st) { SERIAL_ECHO(st.blank_time()); } + template + void print_blank_time(TMCMarlin &) { } + template static void tmc_status(TMC &st, const TMC_debug_enum i) { SERIAL_CHAR('\t'); @@ -703,16 +746,10 @@ SERIAL_ECHO(st.ihold()); SERIAL_ECHOPGM("/31"); break; - case TMC_CS_ACTUAL: - SERIAL_ECHO(st.cs_actual()); - SERIAL_ECHOPGM("/31"); - break; + case TMC_CS_ACTUAL: print_cs_actual(st); break; case TMC_VSENSE: print_vsense(st); break; case TMC_MICROSTEPS: SERIAL_ECHO(st.microsteps()); break; - case TMC_TSTEP: { - const uint32_t tstep_value = st.TSTEP(); - if (tstep_value != 0xFFFFF) SERIAL_ECHO(tstep_value); else SERIAL_ECHOPGM("max"); - } break; + case TMC_TSTEP: print_tstep(st); break; #if ENABLED(HYBRID_THRESHOLD) case TMC_TPWMTHRS: SERIAL_ECHO(uint32_t(st.TPWMTHRS())); break; case TMC_TPWMTHRS_MMS: { @@ -725,7 +762,7 @@ case TMC_OTPW_TRIGGERED: serialprint_truefalse(st.getOTPW()); break; #endif case TMC_TOFF: SERIAL_ECHO(st.toff()); break; - case TMC_TBL: SERIAL_ECHO(st.blank_time()); break; + case TMC_TBL: print_blank_time(st); break; case TMC_HEND: SERIAL_ECHO(st.hysteresis_end()); break; case TMC_HSTRT: SERIAL_ECHO(st.hysteresis_start()); break; case TMC_MSCNT: SERIAL_ECHO(st.get_microstep_counter()); break; @@ -753,10 +790,10 @@ //case TMC_OTPW_TRIGGERED: serialprint_truefalse(st.getOTPW()); break; case TMC_SGT: SERIAL_ECHO(st.sgt()); break; case TMC_TOFF: SERIAL_ECHO(st.toff()); break; - case TMC_TBL: SERIAL_ECHO(st.blank_time()); break; + case TMC_TBL: print_blank_time(st); break; case TMC_HEND: SERIAL_ECHO(st.hysteresis_end()); break; case TMC_HSTRT: SERIAL_ECHO(st.hysteresis_start()); break; - default: break; + default: _tmc_status(st, i); break; } } #endif @@ -916,10 +953,10 @@ TMC_REPORT("Stallguard thrs", TMC_SGT); TMC_REPORT("uStep count", TMC_MSCNT); DRV_REPORT("DRVSTATUS", TMC_DRV_CODES); - #if HAS_TMCX1X0 || HAS_TMC220x + #if HAS_TMCX1X0_OR_2240 || HAS_TMC220x DRV_REPORT("sg_result", TMC_SG_RESULT); #endif - #if HAS_TMCX1X0 + #if HAS_TMCX1X0_OR_2240 DRV_REPORT("stallguard", TMC_STALLGUARD); DRV_REPORT("fsactive", TMC_FSACTIVE); #endif @@ -944,21 +981,22 @@ #define PRINT_TMC_REGISTER(REG_CASE) case TMC_GET_##REG_CASE: print_hex_long(st.REG_CASE(), ':'); break - #if HAS_TMCX1X0 - static void tmc_get_ic_registers(TMC2130Stepper &st, const TMC_get_registers_enum i) { - switch (i) { - PRINT_TMC_REGISTER(TCOOLTHRS); - PRINT_TMC_REGISTER(THIGH); - PRINT_TMC_REGISTER(COOLCONF); - default: SERIAL_CHAR('\t'); break; - } - } - #endif - #if HAS_TMC220x - static void tmc_get_ic_registers(TMC2208Stepper, const TMC_get_registers_enum) { SERIAL_CHAR('\t'); } - #endif - #if HAS_TRINAMIC_CONFIG + + template + static void tmc_get_ic_registers(TMC &, const TMC_get_registers_enum) { SERIAL_CHAR('\t'); } + + #if HAS_TMCX1X0 + static void tmc_get_ic_registers(TMC2130Stepper &st, const TMC_get_registers_enum i) { + switch (i) { + PRINT_TMC_REGISTER(TCOOLTHRS); + PRINT_TMC_REGISTER(THIGH); + PRINT_TMC_REGISTER(COOLCONF); + default: SERIAL_CHAR('\t'); break; + } + } + #endif + template static void tmc_get_registers(TMC &st, const TMC_get_registers_enum i) { switch (i) { @@ -978,7 +1016,8 @@ } SERIAL_CHAR('\t'); } - #endif + #endif // HAS_TRINAMIC_CONFIG + #if HAS_DRIVER(TMC2660) template static void tmc_get_registers(TMCMarlin &st, const TMC_get_registers_enum i) { @@ -1105,7 +1144,7 @@ // TODO return false; } - void tmc_disable_stallguard(TMC2660Stepper, const bool) {}; + void tmc_disable_stallguard(TMC2660Stepper, const bool) { } #endif // USE_SENSORLESS diff --git a/Marlin/src/feature/tmc_util.h b/Marlin/src/feature/tmc_util.h index 55a4eb02aa..99d9dc4bc1 100644 --- a/Marlin/src/feature/tmc_util.h +++ b/Marlin/src/feature/tmc_util.h @@ -422,6 +422,9 @@ void test_tmc_connection(LOGICAL_AXIS_DECL_LC(const bool, true)); bool tmc_enable_stallguard(TMC2209Stepper &st); void tmc_disable_stallguard(TMC2209Stepper &st, const bool restore_stealth); + bool tmc_enable_stallguard(TMC2240Stepper &st); + void tmc_disable_stallguard(TMC2240Stepper &st, const bool restore_stealth); + bool tmc_enable_stallguard(TMC2660Stepper); void tmc_disable_stallguard(TMC2660Stepper, const bool); diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 5d427e7e08..98498f4355 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -3381,7 +3381,7 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i // Stall detection DIAG = HIGH : TMC2209/2240 // Stall detection DIAG = LOW : TMC2130/2160/2660/5130/5160 #if X_SENSORLESS - #define _HIT_STATE AXIS_DRIVER_TYPE(X,TMC2209) || AXIS_DRIVER_TYPE(X,TMC2240) + #define _HIT_STATE (AXIS_DRIVER_TYPE(X,TMC2209) || AXIS_DRIVER_TYPE(X,TMC2240)) #if X_HOME_TO_MIN && X_MIN_ENDSTOP_HIT_STATE != _HIT_STATE #if _HIT_STATE #error "SENSORLESS_HOMING requires X_MIN_ENDSTOP_HIT_STATE HIGH for X MIN homing with TMC2209/2240." @@ -3399,7 +3399,7 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i #endif #if Y_SENSORLESS - #define _HIT_STATE AXIS_DRIVER_TYPE(Y,TMC2209) || AXIS_DRIVER_TYPE(Y,TMC2240) + #define _HIT_STATE (AXIS_DRIVER_TYPE(Y,TMC2209) || AXIS_DRIVER_TYPE(Y,TMC2240)) #if Y_HOME_TO_MIN && Y_MIN_ENDSTOP_HIT_STATE != _HIT_STATE #if _HIT_STATE #error "SENSORLESS_HOMING requires Y_MIN_ENDSTOP_HIT_STATE HIGH for Y MIN homing with TMC2209/2240." @@ -3417,7 +3417,7 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i #endif #if Z_SENSORLESS - #define _HIT_STATE AXIS_DRIVER_TYPE(Z,TMC2209) || AXIS_DRIVER_TYPE(Z,TMC2240) + #define _HIT_STATE (AXIS_DRIVER_TYPE(Z,TMC2209) || AXIS_DRIVER_TYPE(Z,TMC2240)) #if Z_HOME_TO_MIN && Z_MIN_ENDSTOP_HIT_STATE != _HIT_STATE #if _HIT_STATE #error "SENSORLESS_HOMING requires Z_MIN_ENDSTOP_HIT_STATE HIGH for Z MIN homing with TMC2209/2240." @@ -3435,7 +3435,7 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i #endif #if I_SENSORLESS - #define _HIT_STATE AXIS_DRIVER_TYPE(I,TMC2209) || AXIS_DRIVER_TYPE(I,TMC2240) + #define _HIT_STATE (AXIS_DRIVER_TYPE(I,TMC2209) || AXIS_DRIVER_TYPE(I,TMC2240)) #if I_HOME_TO_MIN && I_MIN_ENDSTOP_HIT_STATE != _HIT_STATE #if _HIT_STATE #error "SENSORLESS_HOMING requires I_MIN_ENDSTOP_HIT_STATE HIGH for I MIN homing with TMC2209/2240." @@ -3453,7 +3453,7 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i #endif #if J_SENSORLESS - #define _HIT_STATE AXIS_DRIVER_TYPE(J,TMC2209) || AXIS_DRIVER_TYPE(J,TMC2240) + #define _HIT_STATE (AXIS_DRIVER_TYPE(J,TMC2209) || AXIS_DRIVER_TYPE(J,TMC2240)) #if J_HOME_TO_MIN && J_MIN_ENDSTOP_HIT_STATE != _HIT_STATE #if _HIT_STATE #error "SENSORLESS_HOMING requires J_MIN_ENDSTOP_HIT_STATE HIGH for J MIN homing with TMC2209/2240." @@ -3471,7 +3471,7 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i #endif #if K_SENSORLESS - #define _HIT_STATE AXIS_DRIVER_TYPE(K,TMC2209) || AXIS_DRIVER_TYPE(K,TMC2240) + #define _HIT_STATE (AXIS_DRIVER_TYPE(K,TMC2209) || AXIS_DRIVER_TYPE(K,TMC2240)) #if K_HOME_TO_MIN && K_MIN_ENDSTOP_HIT_STATE != _HIT_STATE #if _HIT_STATE #error "SENSORLESS_HOMING requires K_MIN_ENDSTOP_HIT_STATE HIGH for K MIN homing with TMC2209/2240." @@ -3489,7 +3489,7 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i #endif #if U_SENSORLESS - #define _HIT_STATE AXIS_DRIVER_TYPE(U,TMC2209) || AXIS_DRIVER_TYPE(U,TMC2240) + #define _HIT_STATE (AXIS_DRIVER_TYPE(U,TMC2209) || AXIS_DRIVER_TYPE(U,TMC2240)) #if U_HOME_TO_MIN && U_MIN_ENDSTOP_HIT_STATE != _HIT_STATE #if _HIT_STATE #error "SENSORLESS_HOMING requires U_MIN_ENDSTOP_HIT_STATE HIGH for U MIN homing with TMC2209/2240." @@ -3507,7 +3507,7 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i #endif #if V_SENSORLESS - #define _HIT_STATE AXIS_DRIVER_TYPE(V,TMC2209) || AXIS_DRIVER_TYPE(V,TMC2240) + #define _HIT_STATE (AXIS_DRIVER_TYPE(V,TMC2209) || AXIS_DRIVER_TYPE(V,TMC2240)) #if V_HOME_TO_MIN && V_MIN_ENDSTOP_HIT_STATE != _HIT_STATE #if _HIT_STATE #error "SENSORLESS_HOMING requires V_MIN_ENDSTOP_HIT_STATE HIGH for V MIN homing with TMC2209/2240." @@ -3525,7 +3525,7 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i #endif #if W_SENSORLESS - #define _HIT_STATE AXIS_DRIVER_TYPE(W,TMC2209) || AXIS_DRIVER_TYPE(W,TMC2240) + #define _HIT_STATE (AXIS_DRIVER_TYPE(W,TMC2209) || AXIS_DRIVER_TYPE(W,TMC2240)) #if W_HOME_TO_MIN && W_MIN_ENDSTOP_HIT_STATE != _HIT_STATE #if _HIT_STATE #error "SENSORLESS_HOMING requires W_MIN_ENDSTOP_HIT_STATE HIGH for W MIN homing with TMC2209/2240." diff --git a/ini/features.ini b/ini/features.ini index 5bd955dd0a..833fe76510 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -20,7 +20,7 @@ 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/marlin-2.1.3.x.zip +HAS_TRINAMIC_CONFIG = TMCStepper=https://github.com/MarlinFirmware/TMCStepper/archive/v0.8.2.zip build_src_filter=+ + + + + HAS_STEPPER_CONTROL = build_src_filter=+ HAS_T(RINAMIC_CONFIG|MC_SPI) = build_src_filter=+ From c7bcbf944ec366c55b6ebbf2909c0baad36491e3 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 26 May 2025 11:29:26 -0500 Subject: [PATCH 061/102] =?UTF-8?q?=F0=9F=8C=90=20Specific=20USB-FD=20stri?= =?UTF-8?q?ngs?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/language/language_cz.h | 7 ++++--- Marlin/src/lcd/language/language_de.h | 7 ++++--- Marlin/src/lcd/language/language_el.h | 8 ++++---- Marlin/src/lcd/language/language_en.h | 9 ++++----- Marlin/src/lcd/language/language_es.h | 7 ++++--- Marlin/src/lcd/language/language_fr.h | 7 ++++--- Marlin/src/lcd/language/language_fr_na.h | 7 ++++--- Marlin/src/lcd/language/language_gl.h | 7 ++++--- Marlin/src/lcd/language/language_hu.h | 7 ++++--- Marlin/src/lcd/language/language_it.h | 10 +++++++--- Marlin/src/lcd/language/language_pl.h | 7 ++++--- Marlin/src/lcd/language/language_pt_br.h | 7 ++++--- Marlin/src/lcd/language/language_ro.h | 7 ++++--- Marlin/src/lcd/language/language_ru.h | 7 ++++--- Marlin/src/lcd/language/language_sk.h | 7 ++++--- Marlin/src/lcd/language/language_sv.h | 7 ++++--- Marlin/src/lcd/language/language_tr.h | 7 ++++--- Marlin/src/lcd/language/language_uk.h | 7 ++++--- Marlin/src/lcd/language/language_vi.h | 7 ++++--- Marlin/src/lcd/language/language_zh_CN.h | 7 ++++--- Marlin/src/lcd/language/language_zh_TW.h | 7 ++++--- Marlin/src/lcd/marlinui.cpp | 2 +- Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.cpp | 10 +++++----- 23 files changed, 93 insertions(+), 72 deletions(-) diff --git a/Marlin/src/lcd/language/language_cz.h b/Marlin/src/lcd/language/language_cz.h index ac23bc8daf..2b5fb524d4 100644 --- a/Marlin/src/lcd/language/language_cz.h +++ b/Marlin/src/lcd/language/language_cz.h @@ -45,13 +45,14 @@ namespace LanguageNarrow_cz { LSTR MSG_YES = _UxGT("ANO"); LSTR MSG_NO = _UxGT("NE"); LSTR MSG_BACK = _UxGT("Zpět"); + LSTR MSG_MEDIA_ABORTING = _UxGT("Rušení..."); LSTR MSG_MEDIA_INSERTED = _UxGT("Médium vloženo"); LSTR MSG_MEDIA_REMOVED = _UxGT("Médium vyjmuto"); - LSTR MSG_MEDIA_WAITING = _UxGT("Čekání na médium"); LSTR MSG_MEDIA_READ_ERROR = _UxGT("Chyba čtení média"); - LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB odstraněno"); - LSTR MSG_MEDIA_USB_FAILED = _UxGT("Chyba USB"); + LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("USB odstraněno"); + LSTR MSG_USB_FD_USB_FAILED = _UxGT("Chyba USB"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstopy"); // max 8 znaku LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Soft Endstopy"); LSTR MSG_MAIN_MENU = _UxGT("Hlavní nabídka"); diff --git a/Marlin/src/lcd/language/language_de.h b/Marlin/src/lcd/language/language_de.h index e681317fb8..4f2cdb79ff 100644 --- a/Marlin/src/lcd/language/language_de.h +++ b/Marlin/src/lcd/language/language_de.h @@ -41,15 +41,16 @@ namespace LanguageNarrow_de { LSTR MSG_LOW = _UxGT("RUNTER"); LSTR MSG_BACK = _UxGT("Zurück"); LSTR MSG_ERROR = _UxGT("Fehler"); + LSTR MSG_MEDIA_ABORTING = _UxGT("Abbruch..."); LSTR MSG_MEDIA_INSERTED = _UxGT("Medium erkannt"); LSTR MSG_MEDIA_REMOVED = _UxGT("Medium entfernt"); - LSTR MSG_MEDIA_WAITING = _UxGT("Warten auf Medium"); LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Medium Init fehlgesch."); LSTR MSG_MEDIA_READ_ERROR = _UxGT("Medium Lesefehler"); - LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB Gerät entfernt"); - LSTR MSG_MEDIA_USB_FAILED = _UxGT("USB Start fehlge."); + LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("USB Gerät entfernt"); + LSTR MSG_USB_FD_USB_FAILED = _UxGT("USB Start fehlge."); LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Subcall überschritten"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstopp"); // Max length 8 characters LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Software-Endstopp"); LSTR MSG_MAIN_MENU = _UxGT("Hauptmenü"); diff --git a/Marlin/src/lcd/language/language_el.h b/Marlin/src/lcd/language/language_el.h index 0d3d355cb0..ab816adae0 100644 --- a/Marlin/src/lcd/language/language_el.h +++ b/Marlin/src/lcd/language/language_el.h @@ -45,12 +45,12 @@ namespace LanguageNarrow_el { LSTR MSG_MEDIA_INSERTED = _UxGT("Κάρτα εισήχθη"); LSTR MSG_MEDIA_REMOVED = _UxGT("Κάρτα αφαιρέθη"); - LSTR MSG_MEDIA_WAITING = _UxGT("Αναμονή για κάρτα"); LSTR MSG_MEDIA_ABORTING = _UxGT("Ματαίωση..."); - LSTR MSG_MEDIA_READ_ERROR = MEDIA_TYPE_EN _UxGT(" σφάλμα ανάγνωσης"); - LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB αφαιρέθη"); - LSTR MSG_MEDIA_USB_FAILED = _UxGT("Αποτυχία εκκίνησης USB"); LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Αποτυχία αρχικοποίησης SD"); + LSTR MSG_MEDIA_READ_ERROR = MEDIA_TYPE_EN _UxGT(" σφάλμα ανάγνωσης"); + LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("USB αφαιρέθη"); + LSTR MSG_USB_FD_USB_FAILED = _UxGT("Αποτυχία εκκίνησης USB"); + LSTR MSG_MAIN_MENU = _UxGT("Αρχική Οθόνη"); LSTR MSG_DISABLE_STEPPERS = _UxGT("Απενεργοποίηση μοτέρ"); LSTR MSG_AUTO_HOME = _UxGT("Αυτόμ. επαναφορά XYZ"); diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 5ed5b24635..a74d28b82a 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -90,17 +90,16 @@ namespace LanguageNarrow_en { LSTR MSG_MEDIA_REMOVED = MEDIA_TYPE_EN _UxGT(" Removed"); LSTR MSG_MEDIA_REMOVED_SD = _UxGT("SD Card Removed"); LSTR MSG_MEDIA_REMOVED_USB = _UxGT("USB Drive Removed"); - LSTR MSG_MEDIA_WAITING = _UxGT("Waiting for ") MEDIA_TYPE_EN; - LSTR MSG_MEDIA_WAITING_SD = _UxGT("Waiting for SD Card"); - LSTR MSG_MEDIA_WAITING_USB = _UxGT("Waiting for USB Drive"); LSTR MSG_MEDIA_INIT_FAIL = MEDIA_TYPE_EN _UxGT(" Init Fail"); LSTR MSG_MEDIA_INIT_FAIL_SD = _UxGT("SD Card Init Fail"); LSTR MSG_MEDIA_INIT_FAIL_USB = _UxGT("USB Drive Init Fail"); LSTR MSG_MEDIA_READ_ERROR = MEDIA_TYPE_EN _UxGT(" read error"); - LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB device removed"); - LSTR MSG_MEDIA_USB_FAILED = _UxGT("USB start failed"); LSTR MSG_MEDIA_SORT = _UxGT("Sort ") MEDIA_TYPE_EN; LSTR MSG_MEDIA_UPDATE = MEDIA_TYPE_EN _UxGT(" Update"); + LSTR MSG_USB_FD_WAITING_FOR_MEDIA = _UxGT("Wait for USB Drive"); + LSTR MSG_USB_FD_MEDIA_REMOVED = _UxGT("USB Drive Removed"); + LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("USB device removed"); + LSTR MSG_USB_FD_USB_FAILED = _UxGT("USB start failed"); LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Subcall Overflow"); LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstops"); // Max length 8 characters diff --git a/Marlin/src/lcd/language/language_es.h b/Marlin/src/lcd/language/language_es.h index a92efd5389..2646a85f09 100644 --- a/Marlin/src/lcd/language/language_es.h +++ b/Marlin/src/lcd/language/language_es.h @@ -46,15 +46,16 @@ namespace LanguageNarrow_es { LSTR MSG_YES = _UxGT("SI"); LSTR MSG_NO = _UxGT("NO"); LSTR MSG_BACK = _UxGT("Atrás"); + LSTR MSG_MEDIA_ABORTING = _UxGT("Cancelando..."); LSTR MSG_MEDIA_INSERTED = MEDIA_TYPE_ES _UxGT(" insertado"); LSTR MSG_MEDIA_REMOVED = MEDIA_TYPE_ES _UxGT(" retirado"); - LSTR MSG_MEDIA_WAITING = _UxGT("Esperando al ") MEDIA_TYPE_ES; LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Fallo al iniciar ") MEDIA_TYPE_ES; LSTR MSG_MEDIA_READ_ERROR = _UxGT("Error lectura ") MEDIA_TYPE_ES; - LSTR MSG_MEDIA_USB_REMOVED = _UxGT("Disp. USB retirado"); - LSTR MSG_MEDIA_USB_FAILED = _UxGT("Inicio USB fallido"); + LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("Disp. USB retirado"); + LSTR MSG_USB_FD_USB_FAILED = _UxGT("Inicio USB fallido"); LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Desbordamiento de subllamada"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstops"); // Max length 8 characters LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Soft Endstops"); LSTR MSG_MAIN_MENU = _UxGT("Menú principal"); diff --git a/Marlin/src/lcd/language/language_fr.h b/Marlin/src/lcd/language/language_fr.h index 6d9fd3b4f4..6f0e870807 100644 --- a/Marlin/src/lcd/language/language_fr.h +++ b/Marlin/src/lcd/language/language_fr.h @@ -40,13 +40,14 @@ namespace LanguageNarrow_fr { LSTR MSG_YES = _UxGT("Oui"); LSTR MSG_NO = _UxGT("Non"); LSTR MSG_BACK = _UxGT("Retour"); + LSTR MSG_MEDIA_ABORTING = _UxGT("Annulation..."); LSTR MSG_MEDIA_INSERTED = _UxGT("Média inséré"); LSTR MSG_MEDIA_REMOVED = _UxGT("Média retiré"); - LSTR MSG_MEDIA_WAITING = _UxGT("Attente média"); LSTR MSG_MEDIA_READ_ERROR = _UxGT("Err lecture média"); - LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB débranché"); - LSTR MSG_MEDIA_USB_FAILED = _UxGT("Erreur média USB"); + LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("USB débranché"); + LSTR MSG_USB_FD_USB_FAILED = _UxGT("Erreur média USB"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("Butées"); LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Butées SW"); LSTR MSG_MAIN_MENU = _UxGT("Menu principal"); diff --git a/Marlin/src/lcd/language/language_fr_na.h b/Marlin/src/lcd/language/language_fr_na.h index 07f2b86499..ef1e29a6b9 100644 --- a/Marlin/src/lcd/language/language_fr_na.h +++ b/Marlin/src/lcd/language/language_fr_na.h @@ -40,13 +40,14 @@ namespace LanguageNarrow_fr_na { LSTR MSG_YES = _UxGT("Oui"); LSTR MSG_NO = _UxGT("Non"); LSTR MSG_BACK = _UxGT("Retour"); + LSTR MSG_MEDIA_ABORTING = _UxGT("Annulation..."); LSTR MSG_MEDIA_INSERTED = _UxGT("Media insere"); LSTR MSG_MEDIA_REMOVED = _UxGT("Media retire"); - LSTR MSG_MEDIA_WAITING = _UxGT("Attente media"); LSTR MSG_MEDIA_READ_ERROR = _UxGT("Err lecture media"); - LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB debranche"); - LSTR MSG_MEDIA_USB_FAILED = _UxGT("Erreur media USB"); + LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("USB debranche"); + LSTR MSG_USB_FD_USB_FAILED = _UxGT("Erreur media USB"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("Butees"); LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Butees SW"); LSTR MSG_MAIN_MENU = _UxGT("Menu principal"); diff --git a/Marlin/src/lcd/language/language_gl.h b/Marlin/src/lcd/language/language_gl.h index 3b7620de90..6285626625 100644 --- a/Marlin/src/lcd/language/language_gl.h +++ b/Marlin/src/lcd/language/language_gl.h @@ -48,14 +48,15 @@ namespace LanguageNarrow_gl { LSTR MSG_YES = _UxGT("SI"); LSTR MSG_NO = _UxGT("NON"); LSTR MSG_BACK = _UxGT("Atrás"); + LSTR MSG_MEDIA_ABORTING = _UxGT("Cancelando..."); LSTR MSG_MEDIA_INSERTED = _UxGT("Tarxeta inserida"); LSTR MSG_MEDIA_REMOVED = _UxGT("Tarxeta retirada"); - LSTR MSG_MEDIA_WAITING = _UxGT("Agardando ao ") MEDIA_TYPE_GL; LSTR MSG_MEDIA_READ_ERROR = _UxGT("Erro lectura ") MEDIA_TYPE_GL; - LSTR MSG_MEDIA_USB_REMOVED = _UxGT("Disp. USB retirado"); - LSTR MSG_MEDIA_USB_FAILED = _UxGT("Inicio USB fallido"); + LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("Disp. USB retirado"); + LSTR MSG_USB_FD_USB_FAILED = _UxGT("Inicio USB fallido"); LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Desbord. Subch."); + LSTR MSG_LCD_ENDSTOPS = _UxGT("FinCarro"); LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("FinCarro SW"); LSTR MSG_MAIN_MENU = _UxGT("Menú principal"); diff --git a/Marlin/src/lcd/language/language_hu.h b/Marlin/src/lcd/language/language_hu.h index 3159b79827..7a3e51539c 100644 --- a/Marlin/src/lcd/language/language_hu.h +++ b/Marlin/src/lcd/language/language_hu.h @@ -43,15 +43,16 @@ namespace LanguageNarrow_hu { LSTR MSG_YES = _UxGT("IGEN"); LSTR MSG_NO = _UxGT("NEM"); LSTR MSG_BACK = _UxGT("Vissza"); + LSTR MSG_MEDIA_ABORTING = _UxGT("Megszakítás..."); LSTR MSG_MEDIA_INSERTED = _UxGT("Tároló behelyezve"); LSTR MSG_MEDIA_REMOVED = _UxGT("Tároló eltávolítva"); - LSTR MSG_MEDIA_WAITING = _UxGT("Várakozás a tárolóra"); LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Tároló-kártya hiba"); LSTR MSG_MEDIA_READ_ERROR = _UxGT("Tároló olvasási hiba"); - LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB eltávolítva"); - LSTR MSG_MEDIA_USB_FAILED = _UxGT("USB eszköz hiba"); + LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("USB eltávolítva"); + LSTR MSG_USB_FD_USB_FAILED = _UxGT("USB eszköz hiba"); LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Túlfolyás"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("Végállás"); // Maximum 8 karakter LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Szoft. végállás"); LSTR MSG_MAIN_MENU = _UxGT(""); diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index 0e8689cb0f..bdcd0b8ff6 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -59,16 +59,19 @@ namespace LanguageNarrow_it { LSTR MSG_LOW = _UxGT("BASSO"); LSTR MSG_BACK = _UxGT("Indietro"); LSTR MSG_ERROR = _UxGT("Errore"); + LSTR MSG_MEDIA_ABORTING = _UxGT("Annullando..."); LSTR MSG_MEDIA_INSERTED = MEDIA_TYPE_IT _UxGT(" inserito"); LSTR MSG_MEDIA_REMOVED = MEDIA_TYPE_IT _UxGT(" rimosso"); - LSTR MSG_MEDIA_WAITING = _UxGT("Aspettando ") MEDIA_TYPE_IT; LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Iniz.") MEDIA_TYPE_IT _UxGT(" fallita"); LSTR MSG_MEDIA_READ_ERROR = _UxGT("Err.leggendo ") MEDIA_TYPE_IT; - LSTR MSG_MEDIA_USB_REMOVED = _UxGT("Dispos.USB rimosso"); - LSTR MSG_MEDIA_USB_FAILED = _UxGT("Avvio USB fallito"); LSTR MSG_MEDIA_SORT = _UxGT("Ordina ") MEDIA_TYPE_IT; LSTR MSG_MEDIA_UPDATE = _UxGT("Aggiorna ") MEDIA_TYPE_IT; + LSTR MSG_USB_FD_WAITING_FOR_MEDIA = _UxGT("In attesa unità USB"); + LSTR MSG_USB_FD_MEDIA_REMOVED = _UxGT("Unità USB rimossa"); + LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("Unità USB rimossa"); + LSTR MSG_USB_FD_USB_FAILED = _UxGT("Iniz. USB fallita"); + LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Overflow sottochiamate"); LSTR MSG_LCD_ENDSTOPS = _UxGT("Finecor."); // Max 8 characters LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Finecorsa soft"); @@ -848,6 +851,7 @@ namespace LanguageNarrow_it { LSTR MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_1_LINE("Spurgo filamento")); LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Premi x terminare")); LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Ripresa...")); + LSTR MSG_TMC_DRIVERS = _UxGT("Driver TMC"); LSTR MSG_TMC_CURRENT = _UxGT("Corrente driver"); LSTR MSG_TMC_ACURRENT = _UxGT("Corrente driver ") STR_A; diff --git a/Marlin/src/lcd/language/language_pl.h b/Marlin/src/lcd/language/language_pl.h index 7c7297d184..df0f995416 100644 --- a/Marlin/src/lcd/language/language_pl.h +++ b/Marlin/src/lcd/language/language_pl.h @@ -48,14 +48,15 @@ namespace LanguageNarrow_pl { LSTR MSG_YES = _UxGT("TAK"); LSTR MSG_NO = _UxGT("NIE"); LSTR MSG_BACK = _UxGT("Wstecz"); + LSTR MSG_MEDIA_ABORTING = _UxGT("Przerywanie..."); LSTR MSG_MEDIA_INSERTED = _UxGT("Karta włożona"); LSTR MSG_MEDIA_REMOVED = _UxGT("Karta usunięta"); - LSTR MSG_MEDIA_WAITING = _UxGT("Oczekiwanie na kartę"); LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Błąd inicializacji karty"); LSTR MSG_MEDIA_READ_ERROR = _UxGT("Bład odczytu karty"); - LSTR MSG_MEDIA_USB_REMOVED = _UxGT("Urządzenie USB usunięte"); - LSTR MSG_MEDIA_USB_FAILED = _UxGT("Błąd uruchomienia USB"); + LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("Urządzenie USB usunięte"); + LSTR MSG_USB_FD_USB_FAILED = _UxGT("Błąd uruchomienia USB"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("Krańców."); // Max length 8 characters LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Progr. Krańcówki"); LSTR MSG_MAIN_MENU = _UxGT("Menu główne"); diff --git a/Marlin/src/lcd/language/language_pt_br.h b/Marlin/src/lcd/language/language_pt_br.h index 80a8d95bdb..49c52300f9 100644 --- a/Marlin/src/lcd/language/language_pt_br.h +++ b/Marlin/src/lcd/language/language_pt_br.h @@ -38,13 +38,14 @@ namespace LanguageNarrow_pt_br { LSTR MSG_YES = _UxGT("SIM"); LSTR MSG_NO = _UxGT("NÃO"); LSTR MSG_BACK = _UxGT("Voltar"); + LSTR MSG_MEDIA_ABORTING = _UxGT("Abortando..."); LSTR MSG_MEDIA_INSERTED = _UxGT("Cartão inserido"); LSTR MSG_MEDIA_REMOVED = _UxGT("Cartão removido"); - LSTR MSG_MEDIA_WAITING = _UxGT("Aguardando cartão"); LSTR MSG_MEDIA_READ_ERROR = _UxGT("Erro de leitura"); - LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB removido"); - LSTR MSG_MEDIA_USB_FAILED = _UxGT("USB falhou"); + LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("USB removido"); + LSTR MSG_USB_FD_USB_FAILED = _UxGT("USB falhou"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("Fins de curso"); LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Soft Fins curso"); LSTR MSG_MAIN_MENU = _UxGT("Menu principal"); diff --git a/Marlin/src/lcd/language/language_ro.h b/Marlin/src/lcd/language/language_ro.h index 7337862909..3a939c6a3d 100644 --- a/Marlin/src/lcd/language/language_ro.h +++ b/Marlin/src/lcd/language/language_ro.h @@ -39,14 +39,15 @@ namespace LanguageNarrow_ro { LSTR MSG_YES = _UxGT("DA"); LSTR MSG_NO = _UxGT("NU"); LSTR MSG_BACK = _UxGT("Inapoi"); + LSTR MSG_MEDIA_ABORTING = _UxGT("Abandon..."); LSTR MSG_MEDIA_INSERTED = _UxGT("Media Introdus"); LSTR MSG_MEDIA_REMOVED = _UxGT("Media Inlaturat"); - LSTR MSG_MEDIA_WAITING = _UxGT("Astept Media"); LSTR MSG_MEDIA_READ_ERROR = _UxGT("Eroare Citire Media"); - LSTR MSG_MEDIA_USB_REMOVED = _UxGT("Dispozitiv USB Inlaturat"); - LSTR MSG_MEDIA_USB_FAILED = _UxGT("Pornire USB Esuata"); + LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("Dispozitiv USB Inlaturat"); + LSTR MSG_USB_FD_USB_FAILED = _UxGT("Pornire USB Esuata"); LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Eroare:Subcall Overflow"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstops"); // Max length 8 characters LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Soft Endstops"); LSTR MSG_MAIN_MENU = _UxGT("Principal"); diff --git a/Marlin/src/lcd/language/language_ru.h b/Marlin/src/lcd/language/language_ru.h index 40b3a03d3d..37bc17aa0c 100644 --- a/Marlin/src/lcd/language/language_ru.h +++ b/Marlin/src/lcd/language/language_ru.h @@ -39,16 +39,17 @@ namespace LanguageNarrow_ru { LSTR MSG_YES = _UxGT("Да"); LSTR MSG_NO = _UxGT("Нет"); LSTR MSG_BACK = _UxGT("Назад"); + LSTR MSG_MEDIA_ABORTING = _UxGT("Прерывание..."); LSTR MSG_MEDIA_INSERTED = _UxGT("SD карта вставлена"); LSTR MSG_MEDIA_REMOVED = _UxGT("SD карта извлечена"); - LSTR MSG_MEDIA_WAITING = _UxGT("Вставьте SD карту"); LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Сбой инициализ. SD"); LSTR MSG_ADVANCED_SETTINGS = _UxGT("Расшир. настройки"); LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Переполн. вызова"); LSTR MSG_MEDIA_READ_ERROR = _UxGT("Ошибка чтения"); - LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB диск удалён"); - LSTR MSG_MEDIA_USB_FAILED = _UxGT("Ошибка USB диска"); + LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("USB диск удалён"); + LSTR MSG_USB_FD_USB_FAILED = _UxGT("Ошибка USB диска"); + LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Прогр. концевики"); LSTR MSG_LCD_ENDSTOPS = _UxGT("Концевик"); // Max length 8 characters LSTR MSG_MAIN_MENU = _UxGT("Главное меню"); diff --git a/Marlin/src/lcd/language/language_sk.h b/Marlin/src/lcd/language/language_sk.h index 7a8c228d84..f1efc0e7c3 100644 --- a/Marlin/src/lcd/language/language_sk.h +++ b/Marlin/src/lcd/language/language_sk.h @@ -54,14 +54,15 @@ namespace LanguageNarrow_sk { LSTR MSG_LOW = _UxGT("NÍZKA"); LSTR MSG_BACK = _UxGT("Naspäť"); LSTR MSG_ERROR = _UxGT("Chyba"); + LSTR MSG_MEDIA_ABORTING = _UxGT("Ruším..."); LSTR MSG_MEDIA_INSERTED = _UxGT("Karta vložená"); LSTR MSG_MEDIA_REMOVED = _UxGT("Karta vybraná"); - LSTR MSG_MEDIA_WAITING = _UxGT("Čakám na kartu"); LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Inicial.karty zlyhala"); LSTR MSG_MEDIA_READ_ERROR = _UxGT("Chyba čítania karty"); - LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB zaria. odstrán."); - LSTR MSG_MEDIA_USB_FAILED = _UxGT("Chyba spúšťania USB"); + LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("USB zaria. odstrán."); + LSTR MSG_USB_FD_USB_FAILED = _UxGT("Chyba spúšťania USB"); + LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Preteč. podprogramu"); LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstopy"); // max 8 znakov LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Soft. endstopy"); diff --git a/Marlin/src/lcd/language/language_sv.h b/Marlin/src/lcd/language/language_sv.h index e2e408391c..33ffe8a77d 100644 --- a/Marlin/src/lcd/language/language_sv.h +++ b/Marlin/src/lcd/language/language_sv.h @@ -40,15 +40,16 @@ namespace LanguageNarrow_sv { LSTR MSG_YES = _UxGT("JA"); LSTR MSG_NO = _UxGT("NEJ"); LSTR MSG_BACK = _UxGT("Bakåt"); + LSTR MSG_MEDIA_ABORTING = _UxGT("Avbryter..."); LSTR MSG_MEDIA_INSERTED = _UxGT("Media Instatt"); LSTR MSG_MEDIA_REMOVED = _UxGT("Media Borttaget"); - LSTR MSG_MEDIA_WAITING = _UxGT("Väntar på media"); LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Media init misslyckades"); LSTR MSG_MEDIA_READ_ERROR = _UxGT("Media läsningsfel"); - LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB enhet borttagen"); - LSTR MSG_MEDIA_USB_FAILED = _UxGT("USB start misslyckad"); + LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("USB enhet borttagen"); + LSTR MSG_USB_FD_USB_FAILED = _UxGT("USB start misslyckad"); LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Underanrop överskriden"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("Slutstop"); // Max length 8 characters LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Mjuk slutstopp"); LSTR MSG_MAIN_MENU = _UxGT("Huvud"); diff --git a/Marlin/src/lcd/language/language_tr.h b/Marlin/src/lcd/language/language_tr.h index 36fe4188fa..9e4f261271 100644 --- a/Marlin/src/lcd/language/language_tr.h +++ b/Marlin/src/lcd/language/language_tr.h @@ -52,17 +52,18 @@ namespace LanguageNarrow_tr { LSTR MSG_LOW = _UxGT("DÜŞÜK"); LSTR MSG_BACK = _UxGT("Geri"); LSTR MSG_ERROR = _UxGT("Hata"); + LSTR MSG_MEDIA_ABORTING = _UxGT("Durduruluyor..."); LSTR MSG_MEDIA_INSERTED = _UxGT("SD K. Yerleştirildi."); LSTR MSG_MEDIA_REMOVED = _UxGT("SD Kart Çıkarıldı."); - LSTR MSG_MEDIA_WAITING = _UxGT("SD Kart Bekleniyor"); LSTR MSG_MEDIA_INIT_FAIL = _UxGT("SD K. Başlatma Hatası"); LSTR MSG_MEDIA_READ_ERROR = _UxGT("Kart Okuma Hatası"); - LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB Çıkarıldı"); - LSTR MSG_MEDIA_USB_FAILED = _UxGT("USB Başlat. Hatası"); + LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("USB Çıkarıldı"); + LSTR MSG_USB_FD_USB_FAILED = _UxGT("USB Başlat. Hatası"); LSTR MSG_MEDIA_SORT = _UxGT("Medyayı Sırala"); LSTR MSG_MEDIA_UPDATE = _UxGT("Medyayı Güncelle"); LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Subcall Overflow"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("Endstops"); // Max length 8 characters LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Soft Endstops"); LSTR MSG_MAIN_MENU = _UxGT("Ana"); diff --git a/Marlin/src/lcd/language/language_uk.h b/Marlin/src/lcd/language/language_uk.h index 4d323d6ba7..a6d87e2ae8 100644 --- a/Marlin/src/lcd/language/language_uk.h +++ b/Marlin/src/lcd/language/language_uk.h @@ -40,15 +40,16 @@ namespace LanguageNarrow_uk { LSTR MSG_YES = _UxGT("ТАК"); LSTR MSG_NO = _UxGT("НІ"); LSTR MSG_BACK = _UxGT("Назад"); + LSTR MSG_MEDIA_ABORTING = _UxGT("Переривання..."); LSTR MSG_MEDIA_INSERTED = _UxGT("SD-картка вставлена"); LSTR MSG_MEDIA_REMOVED = _UxGT("SD-картка видалена"); - LSTR MSG_MEDIA_WAITING = _UxGT("Вставте SD-картку"); LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Збій ініціаліз. SD"); LSTR MSG_MEDIA_READ_ERROR = _UxGT("Помилка зчитування"); - LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB диск видалений"); - LSTR MSG_MEDIA_USB_FAILED = _UxGT("Помилка USB диску"); + LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("USB диск видалений"); + LSTR MSG_USB_FD_USB_FAILED = _UxGT("Помилка USB диску"); LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Переповн. виклику"); + LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Прогр.кінцевики"); LSTR MSG_LCD_ENDSTOPS = _UxGT("Кінцевик"); // Max length 8 characters LSTR MSG_MAIN_MENU = _UxGT("Основне меню"); diff --git a/Marlin/src/lcd/language/language_vi.h b/Marlin/src/lcd/language/language_vi.h index f7f5545bcb..e411668a91 100644 --- a/Marlin/src/lcd/language/language_vi.h +++ b/Marlin/src/lcd/language/language_vi.h @@ -35,13 +35,14 @@ namespace LanguageNarrow_vi { LSTR WELCOME_MSG = MACHINE_NAME_SUBST _UxGT(" Sẵn sàng."); // Ready LSTR MSG_BACK = _UxGT("Trở lại"); // Back + LSTR MSG_MEDIA_ABORTING = _UxGT("Đang hủy bỏ..."); LSTR MSG_MEDIA_INSERTED = _UxGT("Phương tiện được cắm vào"); // Media inserted LSTR MSG_MEDIA_REMOVED = _UxGT("Phương tiện được rút ra"); - LSTR MSG_MEDIA_WAITING = _UxGT("Chờ đợi phương tiện"); LSTR MSG_MEDIA_READ_ERROR = _UxGT("Lỗi đọc phương tiện"); - LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB được rút ra"); - LSTR MSG_MEDIA_USB_FAILED = _UxGT("USB khởi thất bại"); + LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("USB được rút ra"); + LSTR MSG_USB_FD_USB_FAILED = _UxGT("USB khởi thất bại"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("Công tắc"); // Endstops - công tắc hành trình LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Công tắc mềm"); // Soft Endstops LSTR MSG_MAIN_MENU = _UxGT("Chính"); // Main diff --git a/Marlin/src/lcd/language/language_zh_CN.h b/Marlin/src/lcd/language/language_zh_CN.h index 01f9f53d0c..ff095889af 100644 --- a/Marlin/src/lcd/language/language_zh_CN.h +++ b/Marlin/src/lcd/language/language_zh_CN.h @@ -41,14 +41,15 @@ namespace LanguageNarrow_zh_CN { LSTR MSG_LOW = _UxGT("低"); LSTR MSG_BACK = _UxGT("返回"); // ”Back“ LSTR MSG_ERROR = _UxGT("错误"); + LSTR MSG_MEDIA_ABORTING = _UxGT("存储卡中止..."); LSTR MSG_MEDIA_INSERTED = _UxGT("存储卡已插入"); // "Card inserted" LSTR MSG_MEDIA_REMOVED = _UxGT("存储卡被拔出"); // "Card removed" - LSTR MSG_MEDIA_WAITING = _UxGT("等待存储器"); LSTR MSG_MEDIA_READ_ERROR = _UxGT("卡读卡器错误"); - LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB设备已弹出"); - LSTR MSG_MEDIA_USB_FAILED = _UxGT("USB读取失败"); + LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("USB设备已弹出"); + LSTR MSG_USB_FD_USB_FAILED = _UxGT("USB读取失败"); LSTR MSG_KILL_SUBCALL_OVERFLOW = _UxGT("子响应溢出"); + LSTR MSG_LCD_ENDSTOPS = _UxGT("挡块"); // "Endstops" // Max length 8 characters LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("软挡块"); LSTR MSG_MAIN_MENU = _UxGT("主菜单"); // "Main" diff --git a/Marlin/src/lcd/language/language_zh_TW.h b/Marlin/src/lcd/language/language_zh_TW.h index 7321252de7..ecacf7e33d 100644 --- a/Marlin/src/lcd/language/language_zh_TW.h +++ b/Marlin/src/lcd/language/language_zh_TW.h @@ -37,13 +37,14 @@ namespace LanguageNarrow_zh_TW { LSTR MSG_YES = _UxGT("是"); // "YES" LSTR MSG_NO = _UxGT("否"); // "NO" LSTR MSG_BACK = _UxGT("返回"); // "Back" + LSTR MSG_MEDIA_ABORTING = _UxGT("正在中止..."); // "Aborting..." LSTR MSG_MEDIA_INSERTED = _UxGT("記憶卡已插入"); // "Card inserted" LSTR MSG_MEDIA_REMOVED = _UxGT("記憶卡被拔出"); // "Card removed" - LSTR MSG_MEDIA_WAITING = _UxGT("等待記憶卡"); // "Waiting for media" LSTR MSG_MEDIA_READ_ERROR = _UxGT("記憶卡讀取錯誤"); //"Media read error" - LSTR MSG_MEDIA_USB_REMOVED = _UxGT("USB裝置已移除"); // "USB device removed" - LSTR MSG_MEDIA_USB_FAILED = _UxGT("USB啟動失敗"); // "USB start failed" + LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("USB裝置已移除"); // "USB device removed" + LSTR MSG_USB_FD_USB_FAILED = _UxGT("USB啟動失敗"); // "USB start failed" + LSTR MSG_LCD_ENDSTOPS = _UxGT("擋塊"); // "Endstops" // Max length 8 characters LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("軟體擋塊"); // "Soft Endstops" LSTR MSG_MAIN_MENU = _UxGT("主選單"); // "Main" diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index ab932adfcd..9cfc6498a8 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -1957,7 +1957,7 @@ uint8_t expand_u8str_P(char * const outstr, PGM_P const ptpl, const int8_t ind, if ((old_status ^ status) & INSERT_SD) LCD_MESSAGE(MSG_MEDIA_REMOVED_SD); else if ((old_status ^ status) & INSERT_USB) - LCD_MESSAGE(MSG_MEDIA_REMOVED_USB); + LCD_MESSAGE(MSG_USB_FD_MEDIA_REMOVED); else LCD_MESSAGE(MSG_MEDIA_REMOVED); diff --git a/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.cpp b/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.cpp index 8b25df16b9..fde697c1f4 100644 --- a/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.cpp +++ b/Marlin/src/sd/usb_flashdrive/Sd2Card_FlashDrive.cpp @@ -128,7 +128,7 @@ bool DiskIODriver_USBFlash::usbStartup() { SERIAL_ECHOPGM("Starting USB host..."); if (!UHS_START) { SERIAL_ECHOLNPGM(" failed."); - LCD_MESSAGE(MSG_MEDIA_USB_FAILED); + LCD_MESSAGE(MSG_USB_FD_USB_FAILED); return false; } @@ -223,8 +223,8 @@ void DiskIODriver_USBFlash::idle() { #endif #if USB_DEBUG >= 1 SERIAL_ECHOLNPGM("Waiting for media"); + LCD_MESSAGE(MSG_USB_FD_WAITING_FOR_MEDIA); #endif - LCD_MESSAGE(MSG_MEDIA_WAITING); GOTO_STATE_AFTER_DELAY(state, 2000); } break; @@ -237,9 +237,9 @@ void DiskIODriver_USBFlash::idle() { // Handle device removal events #if USB_DEBUG >= 1 SERIAL_ECHOLNPGM("USB device removed"); + if (state != MEDIA_READY) + LCD_MESSAGE(MSG_USB_FD_DEVICE_REMOVED); #endif - if (state != MEDIA_READY) - LCD_MESSAGE(MSG_MEDIA_USB_REMOVED); GOTO_STATE_AFTER_DELAY(WAIT_FOR_DEVICE, 0); } @@ -247,8 +247,8 @@ void DiskIODriver_USBFlash::idle() { // Handle media removal events #if USB_DEBUG >= 1 SERIAL_ECHOLNPGM("Media removed"); + LCD_MESSAGE(MSG_USB_FD_MEDIA_REMOVED); #endif - LCD_MESSAGE(MSG_MEDIA_REMOVED); GOTO_STATE_AFTER_DELAY(WAIT_FOR_DEVICE, 0); } From bc990ccca669e513be71050486f380161dfeee3c Mon Sep 17 00:00:00 2001 From: Giuliano <3684609+GMagician@users.noreply.github.com> Date: Mon, 26 May 2025 18:43:47 +0200 Subject: [PATCH 062/102] =?UTF-8?q?=F0=9F=8C=90=20Update=20Italian=20langu?= =?UTF-8?q?age=20(#27877)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/language/language_it.h | 103 +++++++++++++++++++++----- 1 file changed, 86 insertions(+), 17 deletions(-) diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index bdcd0b8ff6..dbf093c042 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -61,9 +61,15 @@ namespace LanguageNarrow_it { LSTR MSG_ERROR = _UxGT("Errore"); LSTR MSG_MEDIA_ABORTING = _UxGT("Annullando..."); - LSTR MSG_MEDIA_INSERTED = MEDIA_TYPE_IT _UxGT(" inserito"); - LSTR MSG_MEDIA_REMOVED = MEDIA_TYPE_IT _UxGT(" rimosso"); + LSTR MSG_MEDIA_INSERTED = MEDIA_TYPE_IT _UxGT(" inserita"); + LSTR MSG_MEDIA_INSERTED_SD = _UxGT("Scheda SD inserita"); + LSTR MSG_MEDIA_INSERTED_USB = _UxGT("Unità USB inserita"); + LSTR MSG_MEDIA_REMOVED = MEDIA_TYPE_IT _UxGT(" rimossa"); + LSTR MSG_MEDIA_REMOVED_SD = _UxGT("Scheda SD rimossa"); + LSTR MSG_MEDIA_REMOVED_USB = _UxGT("Unità USB rimossa"); LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Iniz.") MEDIA_TYPE_IT _UxGT(" fallita"); + LSTR MSG_MEDIA_INIT_FAIL_SD = _UxGT("Iniz. SD fallita"); + LSTR MSG_MEDIA_INIT_FAIL_USB = _UxGT("Iniz. USB fallita"); LSTR MSG_MEDIA_READ_ERROR = _UxGT("Err.leggendo ") MEDIA_TYPE_IT; LSTR MSG_MEDIA_SORT = _UxGT("Ordina ") MEDIA_TYPE_IT; LSTR MSG_MEDIA_UPDATE = _UxGT("Aggiorna ") MEDIA_TYPE_IT; @@ -136,11 +142,12 @@ namespace LanguageNarrow_it { LSTR MSG_PREHEAT_M = _UxGT("Preriscalda $"); LSTR MSG_PREHEAT_M_H = _UxGT("Preriscalda $ ~"); - LSTR MSG_PREHEAT_M_END = _UxGT("Preris.$ ugello"); - LSTR MSG_PREHEAT_M_END_E = _UxGT("Preris.$ ugello ~"); - LSTR MSG_PREHEAT_M_ALL = _UxGT("Preris.$ tutto"); - LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("Preris.$ piatto"); - LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("Preris.$ conf"); + LSTR MSG_PREHEAT_M_END = _UxGT("Preris.ugello $"); + LSTR MSG_PREHEAT_M_END_E = _UxGT("Preris.ugello ~ $"); + LSTR MSG_PREHEAT_M_ALL = _UxGT("Preris.tutto $"); + LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("Preris.piatto $"); + LSTR MSG_PREHEAT_M_CHAMBER = _UxGT("Preris.camera $"); + LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("Preris.conf $"); LSTR MSG_PREHEAT_HOTEND = _UxGT("Prerisc.ugello"); LSTR MSG_PREHEAT_CUSTOM = _UxGT("Prerisc.personal."); @@ -164,6 +171,7 @@ namespace LanguageNarrow_it { LSTR MSG_SPINDLE_REVERSE = _UxGT("Inverti mandrino"); LSTR MSG_SWITCH_PS_ON = _UxGT("Accendi aliment."); LSTR MSG_SWITCH_PS_OFF = _UxGT("Spegni aliment."); + LSTR MSG_POWER_EDM_FAULT = _UxGT("Anomalia alim.EDM"); LSTR MSG_EXTRUDE = _UxGT("Estrudi"); LSTR MSG_RETRACT = _UxGT("Ritrai"); LSTR MSG_MOVE_AXIS = _UxGT("Muovi asse"); @@ -181,6 +189,7 @@ namespace LanguageNarrow_it { LSTR MSG_MESH_VIEWER = _UxGT("Visualiz. mesh"); LSTR MSG_EDIT_MESH = _UxGT("Modifica mesh"); LSTR MSG_MESH_VIEW = _UxGT("Visualizza mesh"); + LSTR MSG_MESH_VIEW_GRID = _UxGT("Vis.mesh (griglia)"); LSTR MSG_EDITING_STOPPED = _UxGT("Modif. mesh fermata"); LSTR MSG_NO_VALID_MESH = _UxGT("Mesh non valida"); LSTR MSG_ACTIVATE_MESH = _UxGT("Attiva livellamento"); @@ -204,7 +213,9 @@ namespace LanguageNarrow_it { LSTR MSG_M48_TEST = _UxGT("Test sonda M48"); LSTR MSG_M48_POINT = _UxGT("Punto M48"); LSTR MSG_M48_OUT_OF_BOUNDS = _UxGT("Sonda oltre i limiti"); + LSTR MSG_M48_DEV = _UxGT("Dev"); LSTR MSG_M48_DEVIATION = _UxGT("Deviazione"); + LSTR MSG_M48_MAX_DELTA = _UxGT("Delta max"); LSTR MSG_IDEX_MENU = _UxGT("Modo IDEX"); LSTR MSG_OFFSETS_MENU = _UxGT("Strumenti offsets"); LSTR MSG_IDEX_MODE_AUTOPARK = _UxGT("Auto-Park"); @@ -431,6 +442,7 @@ namespace LanguageNarrow_it { LSTR MSG_AMAX_EN = _UxGT("Acc.massima *"); LSTR MSG_A_RETRACT = _UxGT("A-Ritrazione"); LSTR MSG_A_TRAVEL = _UxGT("A-Spostamento"); + LSTR MSG_A_SPINDLE = _UxGT("Acc.mandrino"); LSTR MSG_INPUT_SHAPING = _UxGT("Input shaping"); LSTR MSG_SHAPING_ENABLE_N = _UxGT("Abilita shaping @"); LSTR MSG_SHAPING_DISABLE_N = _UxGT("Disabil. shaping @"); @@ -469,8 +481,10 @@ namespace LanguageNarrow_it { LSTR MSG_DRAW_MAX_Y = _UxGT("Max Y area disegno"); LSTR MSG_MAX_BELT_LEN = _UxGT("Lungh.max cinghia"); LSTR MSG_LINEAR_ADVANCE = _UxGT("Avanzam.lineare"); - LSTR MSG_ADVANCE_K = _UxGT("K Avanzamento"); - LSTR MSG_ADVANCE_K_E = _UxGT("K Avanzamento *"); + LSTR MSG_ADVANCE_K = _UxGT("K advance"); + LSTR MSG_ADVANCE_TAU = _UxGT("Tau advance"); + LSTR MSG_ADVANCE_K_E = _UxGT("K advance *"); + LSTR MSG_ADVANCE_TAU_E = _UxGT("Tau advance *"); LSTR MSG_CONTRAST = _UxGT("Contrasto LCD"); LSTR MSG_BRIGHTNESS = _UxGT("Luminosità LCD"); LSTR MSG_SCREEN_TIMEOUT = _UxGT("Timeout LCD (m)"); @@ -535,10 +549,8 @@ namespace LanguageNarrow_it { LSTR MSG_CANCEL_OBJECT = _UxGT("Cancella oggetto"); LSTR MSG_CANCEL_OBJECT_N = _UxGT("Canc. oggetto {"); LSTR MSG_CONTINUE_PRINT_JOB = _UxGT("Cont.proc.stampa"); - LSTR MSG_MEDIA_MENU = _UxGT("Stampa da ") MEDIA_TYPE_IT; LSTR MSG_TURN_OFF = _UxGT("Spegni stampante"); LSTR MSG_END_LOOPS = _UxGT("Fine cicli di rip."); - LSTR MSG_NO_MEDIA = MEDIA_TYPE_IT _UxGT(" non presente"); LSTR MSG_DWELL = _UxGT("Sospensione..."); LSTR MSG_USERWAIT = _UxGT("Premi tasto.."); LSTR MSG_PRINT_PAUSED = _UxGT("Stampa sospesa"); @@ -592,10 +604,20 @@ namespace LanguageNarrow_it { LSTR MSG_ATTACH_MEDIA = _UxGT("Collega ") MEDIA_TYPE_IT; LSTR MSG_ATTACH_SD = _UxGT("Collega scheda SD"); - LSTR MSG_ATTACH_USB = _UxGT("Collega penna USB"); - LSTR MSG_CHANGE_MEDIA = _UxGT("Cambia ") MEDIA_TYPE_IT; + LSTR MSG_ATTACH_USB = _UxGT("Collega unità USB"); LSTR MSG_RELEASE_MEDIA = _UxGT("Rilascia ") MEDIA_TYPE_IT; - LSTR MSG_RUN_AUTOFILES = _UxGT("Esegui files auto"); + LSTR MSG_RELEASE_SD = _UxGT("Rilascia sceda SD"); + LSTR MSG_RELEASE_USB = _UxGT("Rilascia unità USB"); + LSTR MSG_CHANGE_MEDIA = _UxGT("Selez.") MEDIA_TYPE_IT; + LSTR MSG_CHANGE_SD = _UxGT("Selez. scheda SD"); + LSTR MSG_CHANGE_USB = _UxGT("Selez. unità USB"); + LSTR MSG_RUN_AUTOFILES = _UxGT("Esegui Autofiles"); + LSTR MSG_RUN_AUTOFILES_SD = _UxGT("Esegui Autofiles SD"); + LSTR MSG_RUN_AUTOFILES_USB = _UxGT("Esegui Autofiles USB"); + LSTR MSG_MEDIA_MENU = _UxGT("Stampa da ") MEDIA_TYPE_IT; + LSTR MSG_MEDIA_MENU_SD = _UxGT("Selez. da SD"); + LSTR MSG_MEDIA_MENU_USB = _UxGT("Selez. da USB"); + LSTR MSG_NO_MEDIA = MEDIA_TYPE_IT _UxGT(" non rilevato"); LSTR MSG_ZPROBE_OUT = _UxGT("Z probe fuori piatto"); LSTR MSG_SKEW_FACTOR = _UxGT("Fattore distorsione"); @@ -862,6 +884,7 @@ namespace LanguageNarrow_it { LSTR MSG_TMC_HOMING_THRS = _UxGT("Sensorless homing"); LSTR MSG_TMC_STEPPING_MODE = _UxGT("Modo Stepping"); LSTR MSG_TMC_STEALTHCHOP = _UxGT("StealthChop"); + LSTR MSG_TMC_HOMING_CURRENT = _UxGT("Corrente homing"); LSTR MSG_SERVICE_RESET = _UxGT("Resetta"); LSTR MSG_SERVICE_IN = _UxGT(" tra:"); @@ -901,6 +924,7 @@ namespace LanguageNarrow_it { LSTR MSG_BOTTOM_LEFT = _UxGT("Basso sinistra"); LSTR MSG_TOP_RIGHT = _UxGT("Alto destra"); LSTR MSG_BOTTOM_RIGHT = _UxGT("Basso destra"); + LSTR MSG_TOUCH_CALIBRATION = _UxGT("Calibrazione touch"); LSTR MSG_CALIBRATION_COMPLETED = _UxGT("Calibrazione completata"); LSTR MSG_CALIBRATION_FAILED = _UxGT("Calibrazione fallita"); @@ -911,7 +935,7 @@ namespace LanguageNarrow_it { LSTR MSG_HOST_SHUTDOWN = _UxGT("Arresta host"); -// DGUS-Specific message strings, not used elsewhere + // DGUS-Specific message strings, not used elsewhere LSTR DGUS_MSG_NOT_WHILE_PRINTING = _UxGT("Non ammesso durante la stampa"); LSTR DGUS_MSG_NOT_WHILE_IDLE = _UxGT("Non ammesso mentre è in riposo"); LSTR DGUS_MSG_NO_FILE_SELECTED = _UxGT("Nessun file selezionato"); @@ -943,17 +967,56 @@ namespace LanguageNarrow_it { LSTR MSG_BTN_STOP = _UxGT("Stop"); LSTR MSG_BTN_DISABLE_MMU = _UxGT("Disabilita"); LSTR MSG_BTN_MORE = _UxGT("Più info"); + + // Prusa MMU + LSTR MSG_DONE = _UxGT("Eseguito"); + LSTR MSG_FINISHING_MOVEMENTS = _UxGT("Termina movimenti"); + LSTR MSG_LOADING_FILAMENT = _UxGT("Carica. filamento"); + LSTR MSG_UNLOADING_FILAMENT = _UxGT("Scarico filamento"); + LSTR MSG_TESTING_FILAMENT = _UxGT("Testando filamento"); + LSTR MSG_EJECT_FROM_MMU = _UxGT("Espelli da MMU"); + LSTR MSG_CUT_FILAMENT = _UxGT("Taglia filamento"); + LSTR MSG_OFF = _UxGT("Off"); + LSTR MSG_ON = _UxGT("On"); + LSTR MSG_PROGRESS_OK = _UxGT("OK"); + LSTR MSG_PROGRESS_ENGAGE_IDLER = _UxGT("Innesto idler"); + LSTR MSG_PROGRESS_DISENGAGE_IDLER = _UxGT("Disinnesto idler"); + LSTR MSG_PROGRESS_UNLOAD_FINDA = _UxGT("Scarico a FINDA"); + LSTR MSG_PROGRESS_UNLOAD_PULLEY = _UxGT("Scarico a puleggia"); + LSTR MSG_PROGRESS_FEED_FINDA = _UxGT("Alim. a FINDA"); + LSTR MSG_PROGRESS_FEED_EXTRUDER = _UxGT("Alim. all'estrusore"); + LSTR MSG_PROGRESS_FEED_NOZZLE = _UxGT("Alim. all'ugello"); + LSTR MSG_PROGRESS_AVOID_GRIND = _UxGT("Evita grind"); + LSTR MSG_PROGRESS_WAIT_USER = _UxGT("ERR attesa utente"); + LSTR MSG_PROGRESS_ERR_INTERNAL = _UxGT("ERR interno"); + LSTR MSG_PROGRESS_ERR_HELP_FIL = _UxGT("ERR aiuto filamento"); + LSTR MSG_PROGRESS_ERR_TMC = _UxGT("ERR anomalia TMC"); + LSTR MSG_PROGRESS_SELECT_SLOT = _UxGT("Selez.slot filam."); + LSTR MSG_PROGRESS_PREPARE_BLADE = _UxGT("Preparaz.lama"); + LSTR MSG_PROGRESS_PUSH_FILAMENT = _UxGT("Spinta fialmento"); + LSTR MSG_PROGRESS_PERFORM_CUT = _UxGT("Esecuzione taglio"); + LSTR MSG_PROGRESSPSTRETURN_SELECTOR = _UxGT("Ritorno selettore"); + LSTR MSG_PROGRESS_PARK_SELECTOR = _UxGT("Parcheggio selettore"); + LSTR MSG_PROGRESS_EJECT_FILAMENT = _UxGT("Esplusione filamento"); + LSTR MSG_PROGRESSPSTRETRACT_FINDA = _UxGT("Ritrai a FINDA"); + LSTR MSG_PROGRESS_HOMING = _UxGT("Homing"); + LSTR MSG_PROGRESS_MOVING_SELECTOR = _UxGT("Movim. selettore"); + LSTR MSG_PROGRESS_FEED_FSENSOR = _UxGT("Alim. a FSensor"); } namespace LanguageWide_it { using namespace LanguageNarrow_it; #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 + LSTR MSG_LIVE_MOVE = _UxGT("Movimento live"); LSTR MSG_HOST_START_PRINT = _UxGT("Avvio stampa host"); LSTR MSG_PRINTING_OBJECT = _UxGT("Stampa oggetto"); LSTR MSG_CANCEL_OBJECT = _UxGT("Cancella oggetto"); LSTR MSG_CANCEL_OBJECT_N = _UxGT("Cancella oggetto {"); LSTR MSG_CONTINUE_PRINT_JOB = _UxGT("Continua il job di stampa"); - LSTR MSG_MEDIA_MENU = _UxGT("Selez.da supporto"); + LSTR MSG_MEDIA_MENU = _UxGT("Seleziona da ") MEDIA_TYPE_IT; + LSTR MSG_MEDIA_MENU_SD = _UxGT("Seleziona da scheda SD"); + LSTR MSG_MEDIA_MENU_USB = _UxGT("Seleziona da unità USB"); + LSTR MSG_NO_MEDIA = MEDIA_TYPE_EN _UxGT(" non trovato"); LSTR MSG_TURN_OFF = _UxGT("Spegni la stampante"); LSTR MSG_END_LOOPS = _UxGT("Termina i cicli di ripetizione"); LSTR MSG_MEDIA_NOT_INSERTED = _UxGT("Nessun supporto inserito."); // ProUI @@ -963,7 +1026,13 @@ namespace LanguageWide_it { LSTR MSG_INFO_PRINT_TIME = _UxGT("Tempo totale"); LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Lavoro più lungo"); LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Totale estruso"); - LSTR MSG_TEMP_TOO_LOW = _UxGT("Temperatura troppo bassa"); + LSTR MSG_HOMING_FEEDRATE_N = _UxGT("Velocità @ di homing"); + LSTR MSG_HOMING_FEEDRATE_X = _UxGT("Velocità X di homing"); + LSTR MSG_HOMING_FEEDRATE_Y = _UxGT("Velocità Y di homing"); + LSTR MSG_HOMING_FEEDRATE_Z = _UxGT("Velocità Z di homing"); + LSTR MSG_EEPROM_INITIALIZED = _UxGT("Ripristinate impostazioni predefinite"); + LSTR MSG_PREHEAT_M_CHAMBER = _UxGT("Preriscalda camera per $"); + LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("Configurazioni preriscaldo $"); #endif } From af7b126edc3d6fbbbf26b1221f0c2cb5b7a82160 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 26 May 2025 18:09:01 +0000 Subject: [PATCH 063/102] [cron] Bump distribution date (2025-05-26) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 82979634d4..b46b688339 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-05-25" +//#define STRING_DISTRIBUTION_DATE "2025-05-26" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 7c80ca1f17..06c29974a7 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-05-25" + #define STRING_DISTRIBUTION_DATE "2025-05-26" #endif /** From 0916d325898cba1314e9502690f908547d34fbd6 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 26 May 2025 14:33:40 -0500 Subject: [PATCH 064/102] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Ser?= =?UTF-8?q?ial=20ON=5FOFF,=20TRUE=5FFALSE?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/serial.cpp | 4 --- Marlin/src/core/serial.h | 6 ++-- Marlin/src/feature/meatpack.cpp | 8 +++-- Marlin/src/feature/tmc_util.cpp | 32 ++++++++++--------- Marlin/src/gcode/bedlevel/M420.cpp | 9 ++---- Marlin/src/gcode/bedlevel/mbl/G29.cpp | 2 +- Marlin/src/gcode/control/M211.cpp | 3 +- Marlin/src/gcode/control/M605.cpp | 3 +- Marlin/src/gcode/feature/mixing/M166.cpp | 3 +- Marlin/src/gcode/feature/powerloss/M413.cpp | 5 ++- .../gcode/feature/prusa_MMU2/M704-M709.cpp | 9 +++--- Marlin/src/gcode/feature/runout/M412.cpp | 11 +++---- .../src/gcode/feature/trinamic/M911-M914.cpp | 4 +-- Marlin/src/gcode/probe/M401_M402.cpp | 4 +-- Marlin/src/gcode/temp/M303.cpp | 4 +-- 15 files changed, 45 insertions(+), 62 deletions(-) diff --git a/Marlin/src/core/serial.cpp b/Marlin/src/core/serial.cpp index 8a8378330f..3ddfa6d345 100644 --- a/Marlin/src/core/serial.cpp +++ b/Marlin/src/core/serial.cpp @@ -114,10 +114,6 @@ void serial_ternary(FSTR_P const pre, const bool onoff, FSTR_P const on, FSTR_P if (post) SERIAL_ECHO(post); } -void serialprint_onoff(const bool onoff) { SERIAL_ECHO(onoff ? F(STR_ON) : F(STR_OFF)); } -void serialprintln_onoff(const bool onoff) { serialprint_onoff(onoff); SERIAL_EOL(); } -void serialprint_truefalse(const bool tf) { SERIAL_ECHO(tf ? F("true") : F("false")); } - void print_bin(uint16_t val) { for (uint8_t i = 16; i--;) { SERIAL_CHAR('0' + TEST(val, i)); diff --git a/Marlin/src/core/serial.h b/Marlin/src/core/serial.h index 97f31dea35..8ec8b8db2a 100644 --- a/Marlin/src/core/serial.h +++ b/Marlin/src/core/serial.h @@ -233,9 +233,9 @@ void serial_ternary(FSTR_P const pre, const bool onoff, FSTR_P const on, FSTR_P // Print up to 255 spaces void SERIAL_ECHO_SP(uint8_t count); -void serialprint_onoff(const bool onoff); -void serialprintln_onoff(const bool onoff); -void serialprint_truefalse(const bool tf); +inline FSTR_P const ON_OFF(const bool onoff) { return onoff ? F("ON") : F("OFF"); } +inline FSTR_P const TRUE_FALSE(const bool tf) { return tf ? F("true") : F("false"); } + void serial_offset(const_float_t v, const uint8_t sp=0); // For v==0 draw space (sp==1) or plus (sp==2) void print_bin(const uint16_t val); diff --git a/Marlin/src/feature/meatpack.cpp b/Marlin/src/feature/meatpack.cpp index fe3dabe8da..3b762d4ded 100644 --- a/Marlin/src/feature/meatpack.cpp +++ b/Marlin/src/feature/meatpack.cpp @@ -169,9 +169,11 @@ void MeatPack::handle_command(const MeatPack_Command c) { void MeatPack::report_state() { // NOTE: if any configuration vars are added below, the outgoing sync text for host plugin // should not contain the "PV' substring, as this is used to indicate protocol version - SERIAL_ECHOPGM("[MP] " MeatPack_ProtocolVersion " "); - serialprint_onoff(TEST(state, MPConfig_Bit_Active)); - SERIAL_ECHO(TEST(state, MPConfig_Bit_NoSpaces) ? F(" NSP\n") : F(" ESP\n")); + SERIAL_ECHO( + F("[MP] " MeatPack_ProtocolVersion " "), + ON_OFF(TEST(state, MPConfig_Bit_Active)), + TEST(state, MPConfig_Bit_NoSpaces) ? F(" NSP\n") : F(" ESP\n") + ); } /** diff --git a/Marlin/src/feature/tmc_util.cpp b/Marlin/src/feature/tmc_util.cpp index fb17e562ad..d280b55854 100644 --- a/Marlin/src/feature/tmc_util.cpp +++ b/Marlin/src/feature/tmc_util.cpp @@ -595,13 +595,15 @@ void print_cs_actual(TMCMarlin &) { } #endif + static void print_true_or_false(const bool tf) { SERIAL_ECHO(TRUE_FALSE(tf)); } + #if HAS_DRIVER(TMC2130) || HAS_DRIVER(TMC5130) static void _tmc_status(TMC2130Stepper &st, const TMC_debug_enum i) { switch (i) { case TMC_PWM_SCALE: SERIAL_ECHO(st.PWM_SCALE()); break; case TMC_SGT: SERIAL_ECHO(st.sgt()); break; - case TMC_STEALTHCHOP: serialprint_truefalse(st.en_pwm_mode()); break; - case TMC_INTERPOLATE: serialprint_truefalse(st.intpol()); break; + case TMC_STEALTHCHOP: print_true_or_false(st.en_pwm_mode()); break; + case TMC_INTERPOLATE: print_true_or_false(st.intpol()); break; default: break; } } @@ -623,7 +625,7 @@ switch (i) { case TMC_PWM_SCALE: SERIAL_ECHO(st.PWM_SCALE()); break; case TMC_SGT: SERIAL_ECHO(st.sgt()); break; - case TMC_STEALTHCHOP: serialprint_truefalse(st.en_pwm_mode()); break; + case TMC_STEALTHCHOP: print_true_or_false(st.en_pwm_mode()); break; case TMC_GLOBAL_SCALER: { const uint16_t value = st.GLOBAL_SCALER(); @@ -631,7 +633,7 @@ SERIAL_ECHOPGM("/256"); } break; - case TMC_INTERPOLATE: serialprint_truefalse(st.intpol()); break; + case TMC_INTERPOLATE: print_true_or_false(st.intpol()); break; default: break; } } @@ -645,8 +647,8 @@ case TMC_PWM_SCALE_AUTO: SERIAL_ECHO(st.pwm_scale_auto()); break; case TMC_PWM_OFS_AUTO: SERIAL_ECHO(st.pwm_ofs_auto()); break; case TMC_PWM_GRAD_AUTO: SERIAL_ECHO(st.pwm_grad_auto()); break; - case TMC_STEALTHCHOP: serialprint_truefalse(st.stealth()); break; - case TMC_INTERPOLATE: serialprint_truefalse(st.intpol()); break; + case TMC_STEALTHCHOP: print_true_or_false(st.stealth()); break; + case TMC_INTERPOLATE: print_true_or_false(st.intpol()); break; default: break; } } @@ -697,8 +699,8 @@ case TMC_PWM_SCALE_AUTO: SERIAL_ECHO(st.pwm_scale_auto()); break; case TMC_PWM_OFS_AUTO: SERIAL_ECHO(st.pwm_ofs_auto()); break; case TMC_PWM_GRAD_AUTO: SERIAL_ECHO(st.pwm_grad_auto()); break; - case TMC_STEALTHCHOP: serialprint_truefalse(st.stealth()); break; - case TMC_INTERPOLATE: serialprint_truefalse(st.intpol()); break; + case TMC_STEALTHCHOP: print_true_or_false(st.stealth()); break; + case TMC_INTERPOLATE: print_true_or_false(st.intpol()); break; default: break; } } @@ -708,7 +710,7 @@ static void _tmc_parse_drv_status(TMC2660Stepper, const TMC_drv_status_enum) { } static void _tmc_status(TMC2660Stepper &st, const TMC_debug_enum i) { switch (i) { - case TMC_INTERPOLATE: serialprint_truefalse(st.intpol()); break; + case TMC_INTERPOLATE: print_true_or_false(st.intpol()); break; default: break; } } @@ -734,7 +736,7 @@ SERIAL_CHAR('\t'); switch (i) { case TMC_CODES: st.printLabel(); break; - case TMC_ENABLED: serialprint_truefalse(st.isEnabled()); break; + case TMC_ENABLED: print_true_or_false(st.isEnabled()); break; case TMC_CURRENT: SERIAL_ECHO(st.getMilliamps()); break; case TMC_RMS_CURRENT: SERIAL_ECHO(st.rms_current()); break; case TMC_MAX_CURRENT: SERIAL_ECHO(p_float_t(st.rms_current() * 1.41, 0)); break; @@ -757,9 +759,9 @@ if (tpwmthrs_val) SERIAL_ECHO(tpwmthrs_val); else SERIAL_CHAR('-'); } break; #endif - case TMC_OTPW: serialprint_truefalse(st.otpw()); break; + case TMC_OTPW: print_true_or_false(st.otpw()); break; #if ENABLED(MONITOR_DRIVER_STATUS) - case TMC_OTPW_TRIGGERED: serialprint_truefalse(st.getOTPW()); break; + case TMC_OTPW_TRIGGERED: print_true_or_false(st.getOTPW()); break; #endif case TMC_TOFF: SERIAL_ECHO(st.toff()); break; case TMC_TBL: print_blank_time(st); break; @@ -776,7 +778,7 @@ SERIAL_CHAR('\t'); switch (i) { case TMC_CODES: st.printLabel(); break; - case TMC_ENABLED: serialprint_truefalse(st.isEnabled()); break; + case TMC_ENABLED: print_true_or_false(st.isEnabled()); break; case TMC_CURRENT: SERIAL_ECHO(st.getMilliamps()); break; case TMC_RMS_CURRENT: SERIAL_ECHO(st.rms_current()); break; case TMC_MAX_CURRENT: SERIAL_ECHO(p_float_t(st.rms_current() * 1.41, 0)); break; @@ -786,8 +788,8 @@ break; case TMC_VSENSE: SERIAL_ECHO(st.vsense() ? F("1=.165") : F("0=.310")); break; case TMC_MICROSTEPS: SERIAL_ECHO(st.microsteps()); break; - //case TMC_OTPW: serialprint_truefalse(st.otpw()); break; - //case TMC_OTPW_TRIGGERED: serialprint_truefalse(st.getOTPW()); break; + //case TMC_OTPW: print_true_or_false(st.otpw()); break; + //case TMC_OTPW_TRIGGERED: print_true_or_false(st.getOTPW()); break; case TMC_SGT: SERIAL_ECHO(st.sgt()); break; case TMC_TOFF: SERIAL_ECHO(st.toff()); break; case TMC_TBL: print_blank_time(st); break; diff --git a/Marlin/src/gcode/bedlevel/M420.cpp b/Marlin/src/gcode/bedlevel/M420.cpp index 8711bab9c8..7903cc623c 100644 --- a/Marlin/src/gcode/bedlevel/M420.cpp +++ b/Marlin/src/gcode/bedlevel/M420.cpp @@ -228,9 +228,7 @@ void GcodeSuite::M420() { if (to_enable && !planner.leveling_active) SERIAL_ERROR_MSG(STR_ERR_M420_FAILED); - SERIAL_ECHO_START(); - SERIAL_ECHOPGM("Bed Leveling "); - serialprintln_onoff(planner.leveling_active); + SERIAL_ECHO_MSG("Bed Leveling ", ON_OFF(planner.leveling_active)); #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) SERIAL_ECHO_START(); @@ -252,14 +250,13 @@ void GcodeSuite::M420_report(const bool forReplay/*=true*/) { report_heading_etc(forReplay, F( TERN(MESH_BED_LEVELING, "Mesh Bed Leveling", TERN(AUTO_BED_LEVELING_UBL, "Unified Bed Leveling", "Auto Bed Leveling")) )); - SERIAL_ECHO( + SERIAL_ECHOLN( F(" M420 S"), planner.leveling_active #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) , FPSTR(SP_Z_STR), LINEAR_UNIT(planner.z_fade_height) #endif - , F(" ; Leveling ") + , F(" ; Leveling "), ON_OFF(planner.leveling_active) ); - serialprintln_onoff(planner.leveling_active); } #endif // HAS_LEVELING diff --git a/Marlin/src/gcode/bedlevel/mbl/G29.cpp b/Marlin/src/gcode/bedlevel/mbl/G29.cpp index be0e5d7f18..4bd444c5a3 100644 --- a/Marlin/src/gcode/bedlevel/mbl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/mbl/G29.cpp @@ -99,7 +99,7 @@ void GcodeSuite::G29() { case MeshReport: SERIAL_ECHOPGM("Mesh Bed Leveling "); if (leveling_is_valid()) { - serialprintln_onoff(planner.leveling_active); + SERIAL_ECHOLN(ON_OFF(planner.leveling_active)); bedlevel.report_mesh(); } else diff --git a/Marlin/src/gcode/control/M211.cpp b/Marlin/src/gcode/control/M211.cpp index 471ca6c448..e51a9d5297 100644 --- a/Marlin/src/gcode/control/M211.cpp +++ b/Marlin/src/gcode/control/M211.cpp @@ -43,8 +43,7 @@ void GcodeSuite::M211_report(const bool forReplay/*=true*/) { TERN_(MARLIN_SMALL_BUILD, return); report_heading_etc(forReplay, F(STR_SOFT_ENDSTOPS)); - SERIAL_ECHOPGM(" M211 S", AS_DIGIT(soft_endstop._enabled), " ; "); - serialprintln_onoff(soft_endstop._enabled); + SERIAL_ECHOLNPGM(" M211 S", AS_DIGIT(soft_endstop._enabled), " ; ", ON_OFF(soft_endstop._enabled)); report_echo_start(forReplay); const xyz_pos_t l_soft_min = soft_endstop.min.asLogical(), diff --git a/Marlin/src/gcode/control/M605.cpp b/Marlin/src/gcode/control/M605.cpp index 56d7594b08..4679422dfb 100644 --- a/Marlin/src/gcode/control/M605.cpp +++ b/Marlin/src/gcode/control/M605.cpp @@ -173,8 +173,7 @@ set_duplication_enabled(ena && (duplication_e_mask >= 3)); } SERIAL_ECHO_START(); - SERIAL_ECHOPGM(STR_DUPLICATION_MODE); - serialprint_onoff(extruder_duplication_enabled); + SERIAL_ECHOPGM(STR_DUPLICATION_MODE, ON_OFF(extruder_duplication_enabled)); if (ena) { SERIAL_ECHOPGM(" ( "); HOTEND_LOOP() if (TEST(duplication_e_mask, e)) { SERIAL_ECHO(e); SERIAL_CHAR(' '); } diff --git a/Marlin/src/gcode/feature/mixing/M166.cpp b/Marlin/src/gcode/feature/mixing/M166.cpp index f42583d052..29411f2122 100644 --- a/Marlin/src/gcode/feature/mixing/M166.cpp +++ b/Marlin/src/gcode/feature/mixing/M166.cpp @@ -68,8 +68,7 @@ void GcodeSuite::M166() { mixer.refresh_gradient(); - SERIAL_ECHOPGM("Gradient Mix "); - serialprint_onoff(mixer.gradient.enabled); + SERIAL_ECHOPGM("Gradient Mix ", ON_OFF(mixer.gradient.enabled)); if (mixer.gradient.enabled) { #if ENABLED(GRADIENT_VTOOL) diff --git a/Marlin/src/gcode/feature/powerloss/M413.cpp b/Marlin/src/gcode/feature/powerloss/M413.cpp index b12257b4e5..7f0e2e2b9a 100644 --- a/Marlin/src/gcode/feature/powerloss/M413.cpp +++ b/Marlin/src/gcode/feature/powerloss/M413.cpp @@ -67,13 +67,12 @@ void GcodeSuite::M413_report(const bool forReplay/*=true*/) { TERN_(MARLIN_SMALL_BUILD, return); report_heading_etc(forReplay, F(STR_POWER_LOSS_RECOVERY)); - SERIAL_ECHOPGM(" M413 S", AS_DIGIT(recovery.enabled) + SERIAL_ECHOLNPGM(" M413 S", AS_DIGIT(recovery.enabled) #if HAS_PLR_BED_THRESHOLD , " B", recovery.bed_temp_threshold #endif + , " ; ", ON_OFF(recovery.enabled) ); - SERIAL_ECHO(" ; "); - serialprintln_onoff(recovery.enabled); } #endif // POWER_LOSS_RECOVERY diff --git a/Marlin/src/gcode/feature/prusa_MMU2/M704-M709.cpp b/Marlin/src/gcode/feature/prusa_MMU2/M704-M709.cpp index f6af70b8dd..19aea31ff1 100644 --- a/Marlin/src/gcode/feature/prusa_MMU2/M704-M709.cpp +++ b/Marlin/src/gcode/feature/prusa_MMU2/M704-M709.cpp @@ -185,13 +185,12 @@ void GcodeSuite::M709() { void GcodeSuite::MMU3_report(const bool forReplay/*=true*/) { using namespace MMU3; report_heading(forReplay, F("MMU3 Operational Stats")); - SERIAL_ECHOPGM(" MMU "); serialprintln_onoff(mmu3.mmu_hw_enabled); - SERIAL_ECHOPGM(" Stealth Mode "); serialprintln_onoff(mmu3.stealth_mode); + SERIAL_ECHOLNPGM(" MMU ", ON_OFF(mmu3.mmu_hw_enabled)); + SERIAL_ECHOLNPGM(" Stealth Mode ", ON_OFF(mmu3.stealth_mode)); #if ENABLED(MMU3_HAS_CUTTER) - SERIAL_ECHOPGM(" Cutter "); - serialprintln_onoff(mmu3.cutter_mode != 0); + SERIAL_ECHOLNPGM(" Cutter ", ON_OFF(mmu3.cutter_mode != 0)); #endif - SERIAL_ECHOPGM(" SpoolJoin "); serialprintln_onoff(spooljoin.enabled); + SERIAL_ECHOLNPGM(" SpoolJoin ", ON_OFF(spooljoin.enabled)); SERIAL_ECHOLNPGM(" Tool Changes ", operation_statistics.tool_change_counter); SERIAL_ECHOLNPGM(" Total Tool Changes ", operation_statistics.tool_change_total_counter); SERIAL_ECHOLNPGM(" Fails ", operation_statistics.fail_num); diff --git a/Marlin/src/gcode/feature/runout/M412.cpp b/Marlin/src/gcode/feature/runout/M412.cpp index 4cfb238309..1b8936e6bd 100644 --- a/Marlin/src/gcode/feature/runout/M412.cpp +++ b/Marlin/src/gcode/feature/runout/M412.cpp @@ -53,14 +53,12 @@ void GcodeSuite::M412() { } else { SERIAL_ECHO_START(); - SERIAL_ECHOPGM("Filament runout "); - serialprint_onoff(runout.enabled); + SERIAL_ECHOPGM("Filament runout ", ON_OFF(runout.enabled)); #if HAS_FILAMENT_RUNOUT_DISTANCE SERIAL_ECHOPGM(" ; Distance ", runout.runout_distance(), "mm"); #endif #if ENABLED(HOST_ACTION_COMMANDS) - SERIAL_ECHOPGM(" ; Host handling "); - serialprint_onoff(runout.host_handling); + SERIAL_ECHOPGM(" ; Host handling ", ON_OFF(runout.host_handling)); #endif SERIAL_EOL(); } @@ -70,14 +68,13 @@ void GcodeSuite::M412_report(const bool forReplay/*=true*/) { TERN_(MARLIN_SMALL_BUILD, return); report_heading_etc(forReplay, F(STR_FILAMENT_RUNOUT_SENSOR)); - SERIAL_ECHOPGM( + SERIAL_ECHOLNPGM( " M412 S", runout.enabled #if HAS_FILAMENT_RUNOUT_DISTANCE , " D", LINEAR_UNIT(runout.runout_distance()) #endif - , " ; Sensor " + , " ; Sensor ", ON_OFF(runout.enabled) ); - serialprintln_onoff(runout.enabled); } #endif // HAS_FILAMENT_SENSOR diff --git a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp index 52622a5e7e..336e881372 100644 --- a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp +++ b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp @@ -76,9 +76,7 @@ template static void tmc_report_otpw(TMC &st) { st.printLabel(); - SERIAL_ECHOPGM(" temperature prewarn triggered: "); - serialprint_truefalse(st.getOTPW()); - SERIAL_EOL(); + SERIAL_ECHOLNPGM(" temperature prewarn triggered: ", TRUE_FALSE(st.getOTPW())); } template diff --git a/Marlin/src/gcode/probe/M401_M402.cpp b/Marlin/src/gcode/probe/M401_M402.cpp index 05230e05ea..237f841212 100644 --- a/Marlin/src/gcode/probe/M401_M402.cpp +++ b/Marlin/src/gcode/probe/M401_M402.cpp @@ -47,9 +47,7 @@ void GcodeSuite::M401() { seenS = parser.seen('S'); if (seenH || seenS) { if (seenS) bltouch.high_speed_mode = parser.value_bool(); - SERIAL_ECHO_START(); - SERIAL_ECHOPGM("BLTouch HS mode "); - serialprintln_onoff(bltouch.high_speed_mode); + SERIAL_ECHO_MSG("BLTouch HS mode ", ON_OFF(bltouch.high_speed_mode)); return; } #endif diff --git a/Marlin/src/gcode/temp/M303.cpp b/Marlin/src/gcode/temp/M303.cpp index c08b99edc6..ffa4efb699 100644 --- a/Marlin/src/gcode/temp/M303.cpp +++ b/Marlin/src/gcode/temp/M303.cpp @@ -50,9 +50,7 @@ void GcodeSuite::M303() { #if HAS_PID_DEBUG if (parser.seen_test('D')) { FLIP(thermalManager.pid_debug_flag); - SERIAL_ECHO_START(); - SERIAL_ECHOPGM("PID Debug "); - serialprintln_onoff(thermalManager.pid_debug_flag); + SERIAL_ECHO_MSG("PID Debug ", ON_OFF(thermalManager.pid_debug_flag)); return; } #endif From 21559b0c59029524da9eeca24e75863b92874ae7 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 26 May 2025 16:33:33 -0500 Subject: [PATCH 065/102] =?UTF-8?q?=F0=9F=A9=B9=20Call=20SERIAL=5FIMPL.msg?= =?UTF-8?q?Done()=20after=20M105?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/gcode.cpp | 4 ++-- Marlin/src/gcode/gcode.h | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 469ab134d3..242972c24b 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -319,7 +319,7 @@ void GcodeSuite::dwell(const millis_t time) { /** * Process the parsed command and dispatch it to its handler */ -void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { +void GcodeSuite::process_parsed_command(bool no_ok/*=false*/) { TERN_(HAS_FANCHECK, fan_check.check_deferred_error()); KEEPALIVE_STATE(IN_HANDLER); @@ -582,7 +582,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 109: M109(); break; // M109: Wait for hotend temperature to reach target #endif - case 105: M105(); return; // M105: Report Temperatures (and say "ok") + case 105: M105(); no_ok = true; break; // M105: Report Temperatures (and say "ok") #if HAS_FAN case 106: M106(); break; // M106: Fan On diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index cfe0ec056f..ee0ccb9a0f 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -458,7 +458,7 @@ public: static int8_t get_target_e_stepper_from_command(const int8_t dval=-1); static void get_destination_from_command(); - static void process_parsed_command(const bool no_ok=false); + static void process_parsed_command(bool no_ok=false); static void process_next_command(); // Execute G-code in-place, preserving current G-code parameters From 122c4116f2e2a64017b528cd49f896c166f1dfaf Mon Sep 17 00:00:00 2001 From: Andrew <18502096+classicrocker883@users.noreply.github.com> Date: Mon, 26 May 2025 17:36:55 -0400 Subject: [PATCH 066/102] =?UTF-8?q?=F0=9F=9A=B8=20Misc.=20optimizations,?= =?UTF-8?q?=20cleanup,=20DWIN=20fixes=E2=80=A6=20(#27858)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- .../src/HAL/GD32_MFL/eeprom/eeprom_if_iic.cpp | 2 +- Marlin/src/HAL/HC32/eeprom/eeprom_if_iic.cpp | 2 +- Marlin/src/HAL/STM32/eeprom/eeprom_if_iic.cpp | 2 +- .../src/HAL/STM32F1/eeprom/eeprom_if_iic.cpp | 2 +- Marlin/src/core/types.h | 38 +++++++------- Marlin/src/gcode/bedlevel/G26.cpp | 6 ++- Marlin/src/gcode/calibrate/G33.cpp | 4 +- Marlin/src/gcode/feature/powerloss/M413.cpp | 4 +- Marlin/src/gcode/motion/G0_G1.cpp | 7 +-- Marlin/src/gcode/probe/M951.cpp | 2 +- Marlin/src/gcode/temp/M106_M107.cpp | 5 +- Marlin/src/inc/Changes.h | 12 ++--- Marlin/src/inc/Conditionals-2-LCD.h | 5 -- Marlin/src/lcd/e3v2/proui/dwin.cpp | 50 ++++++++++--------- Marlin/src/module/planner.cpp | 10 ++-- Marlin/src/module/planner.h | 3 +- ini/hc32.ini | 4 +- 17 files changed, 82 insertions(+), 76 deletions(-) diff --git a/Marlin/src/HAL/GD32_MFL/eeprom/eeprom_if_iic.cpp b/Marlin/src/HAL/GD32_MFL/eeprom/eeprom_if_iic.cpp index ea563f742c..765c997e1f 100644 --- a/Marlin/src/HAL/GD32_MFL/eeprom/eeprom_if_iic.cpp +++ b/Marlin/src/HAL/GD32_MFL/eeprom/eeprom_if_iic.cpp @@ -42,7 +42,7 @@ void eeprom_init() { void eeprom_write_byte(uint8_t *pos, uint8_t value) { const unsigned eeprom_address = (unsigned)pos; - return BL24CXX::writeOneByte(eeprom_address, value); + BL24CXX::writeOneByte(eeprom_address, value); } uint8_t eeprom_read_byte(uint8_t *pos) { diff --git a/Marlin/src/HAL/HC32/eeprom/eeprom_if_iic.cpp b/Marlin/src/HAL/HC32/eeprom/eeprom_if_iic.cpp index 85d21a972a..0a161f23f2 100644 --- a/Marlin/src/HAL/HC32/eeprom/eeprom_if_iic.cpp +++ b/Marlin/src/HAL/HC32/eeprom/eeprom_if_iic.cpp @@ -39,7 +39,7 @@ void eeprom_init() { void eeprom_write_byte(uint8_t *pos, unsigned char value) { const unsigned eeprom_address = (unsigned)pos; - return BL24CXX::writeOneByte(eeprom_address, value); + BL24CXX::writeOneByte(eeprom_address, value); } uint8_t eeprom_read_byte(uint8_t *pos) { diff --git a/Marlin/src/HAL/STM32/eeprom/eeprom_if_iic.cpp b/Marlin/src/HAL/STM32/eeprom/eeprom_if_iic.cpp index 9cabdd681b..2733c8f283 100644 --- a/Marlin/src/HAL/STM32/eeprom/eeprom_if_iic.cpp +++ b/Marlin/src/HAL/STM32/eeprom/eeprom_if_iic.cpp @@ -44,7 +44,7 @@ void eeprom_init() { BL24CXX::init(); } void eeprom_write_byte(uint8_t *pos, uint8_t value) { const unsigned eeprom_address = (unsigned)pos; - return BL24CXX::writeOneByte(eeprom_address, value); + BL24CXX::writeOneByte(eeprom_address, value); } uint8_t eeprom_read_byte(uint8_t *pos) { diff --git a/Marlin/src/HAL/STM32F1/eeprom/eeprom_if_iic.cpp b/Marlin/src/HAL/STM32F1/eeprom/eeprom_if_iic.cpp index e1d5e06b68..e7e7fc1db1 100644 --- a/Marlin/src/HAL/STM32F1/eeprom/eeprom_if_iic.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom/eeprom_if_iic.cpp @@ -42,7 +42,7 @@ void eeprom_init() { BL24CXX::init(); } void eeprom_write_byte(uint8_t *pos, uint8_t value) { const unsigned eeprom_address = (unsigned)pos; - return BL24CXX::writeOneByte(eeprom_address, value); + BL24CXX::writeOneByte(eeprom_address, value); } uint8_t eeprom_read_byte(uint8_t *pos) { diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h index 0de49771ee..86f6ae69dc 100644 --- a/Marlin/src/core/types.h +++ b/Marlin/src/core/types.h @@ -168,7 +168,7 @@ template struct IF { typedef L type; }; // Helpers #define _RECIP(N) ((N) ? 1.0f / static_cast(N) : 0.0f) -#define _ABS(N) ((N) < 0 ? -(N) : (N)) +#define _ABS(N) ((N) < decltype(N)(0) ? -(N) : (N)) #define _LS(N) T(uint32_t(N) << p) #define _RS(N) T(uint32_t(N) >> p) #define _LSE(N) N = T(uint32_t(N) << p) @@ -640,8 +640,8 @@ struct XYZval { FI void reset() { NUM_AXIS_CODE(x = 0, y = 0, z = 0, i = 0, j = 0, k = 0, u = 0, v = 0, w = 0); } // Setters taking struct types and arrays - FI void set(const XYval pxy) { XY_CODE(x = pxy.x, y = pxy.y); } - FI void set(const XYval pxy, const T pz) { XYZ_CODE(x = pxy.x, y = pxy.y, z = pz); } + FI void set(const XYval &pxy) { XY_CODE(x = pxy.x, y = pxy.y); } + FI void set(const XYval &pxy, const T pz) { XYZ_CODE(x = pxy.x, y = pxy.y, z = pz); } FI void set(const T (&arr)[NUM_AXES]) { NUM_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); } #if LOGICAL_AXES > NUM_AXES FI void set(const T (&arr)[LOGICAL_AXES]) { NUM_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); } @@ -743,7 +743,7 @@ struct XYZval { // Absolute difference between two objects FI constexpr XYZval diff(const XYZEval &rs) const { return NUM_AXIS_ARRAY(T(_ABS(x - rs.x)), T(_ABS(y - rs.y)), T(_ABS(z - rs.z)), T(_ABS(i - rs.i)), T(_ABS(j - rs.j)), T(_ABS(k - rs.k)), T(_ABS(u - rs.u)), T(_ABS(v - rs.v)), T(_ABS(w - rs.w)) ); } - FI constexpr XYZval diff(const XYZval &rs) const { return NUM_AXIS_ARRAY(T(_ABS(x - rs.x)), T(_ABS(y - rs.y)), T(_ABS(z - rs.z)), T(_ABS(i - rs.i)), T(_ABS(j - rs.j)), T(_ABS(k - rs.k)), T(_ABS(u - rs.u)), T(_ABS(v - rs.v)), T(_ABS(w - rs.w)) ); } + FI constexpr XYZval diff(const XYZval &rs) const { return NUM_AXIS_ARRAY(T(_ABS(x - rs.x)), T(_ABS(y - rs.y)), T(_ABS(z - rs.z)), T(_ABS(i - rs.i)), T(_ABS(j - rs.j)), T(_ABS(k - rs.k)), T(_ABS(u - rs.u)), T(_ABS(v - rs.v)), T(_ABS(w - rs.w)) ); } FI constexpr XYZval diff(const XYval &rs) const { return NUM_AXIS_ARRAY(T(_ABS(x - rs.x)), T(_ABS(y - rs.y)), z, i, j, k, u, v, w ); } // Modifier operators @@ -787,17 +787,17 @@ struct XYZEval { FI void reset() { LOGICAL_AXIS_GANG(e =, x =, y =, z =, i =, j =, k =, u =, v =, w =) 0; } // Setters taking struct types and arrays - FI void set(const XYval pxy) { XY_CODE(x = pxy.x, y = pxy.y); } - FI void set(const XYval pxy, const T pz) { XYZ_CODE(x = pxy.x, y = pxy.y, z = pz); } - FI void set(const XYZval pxyz) { set(NUM_AXIS_ELEM_LC(pxyz)); } - FI void set(const T (&arr)[NUM_AXES]) { NUM_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); } + FI void set(const XYval &pxy) { XY_CODE(x = pxy.x, y = pxy.y); } + FI void set(const XYval &pxy, const T pz) { XYZ_CODE(x = pxy.x, y = pxy.y, z = pz); } + FI void set(const XYZval &pxyz) { set(NUM_AXIS_ELEM_LC(pxyz)); } + FI void set(const T (&arr)[NUM_AXES]) { NUM_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); } #if LOGICAL_AXES > NUM_AXES - FI void set(const T (&arr)[LOGICAL_AXES]) { LOGICAL_AXIS_CODE(e = arr[LOGICAL_AXES-1], x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); } - FI void set(const XYval pxy, const T pz, const T pe) { set(pxy, pz); e = pe; } - FI void set(const XYZval pxyz, const T pe) { set(pxyz); e = pe; } - FI void set(LOGICAL_AXIS_ARGS_LC(const T)) { LOGICAL_AXIS_CODE(_e = e, a = x, b = y, c = z, _i = i, _j = j, _k = k, _u = u, _v = v, _w = w); } + FI void set(const T (&arr)[LOGICAL_AXES]) { LOGICAL_AXIS_CODE(e = arr[LOGICAL_AXES-1], x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); } + FI void set(const XYval &pxy, const T pz, const T pe) { set(pxy, pz); e = pe; } + FI void set(const XYZval &pxyz, const T pe) { set(pxyz); e = pe; } + FI void set(LOGICAL_AXIS_ARGS_LC(const T)) { LOGICAL_AXIS_CODE(_e = e, a = x, b = y, c = z, _i = i, _j = j, _k = k, _u = u, _v = v, _w = w); } #if DISTINCT_AXES > LOGICAL_AXES - FI void set(const T (&arr)[DISTINCT_AXES]) { LOGICAL_AXIS_CODE(e = arr[LOGICAL_AXES-1], x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); } + FI void set(const T (&arr)[DISTINCT_AXES]) { LOGICAL_AXIS_CODE(e = arr[LOGICAL_AXES-1], x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); } #endif #endif @@ -933,9 +933,9 @@ struct XYZarray { }; FI void reset() { ZERO(data); } - FI void set(const int n, const XYval p) { NUM_AXIS_CODE(x[n]=p.x, y[n]=p.y,,,,,,,); } - FI void set(const int n, const XYZval p) { NUM_AXIS_CODE(x[n]=p.x, y[n]=p.y, z[n]=p.z, i[n]=p.i, j[n]=p.j, k[n]=p.k, u[n]=p.u, v[n]=p.v, w[n]=p.w ); } - FI void set(const int n, const XYZEval p) { NUM_AXIS_CODE(x[n]=p.x, y[n]=p.y, z[n]=p.z, i[n]=p.i, j[n]=p.j, k[n]=p.k, u[n]=p.u, v[n]=p.v, w[n]=p.w ); } + FI void set(const int n, const XYval &p) { NUM_AXIS_CODE(x[n]=p.x, y[n]=p.y,,,,,,,); } + FI void set(const int n, const XYZval &p) { NUM_AXIS_CODE(x[n]=p.x, y[n]=p.y, z[n]=p.z, i[n]=p.i, j[n]=p.j, k[n]=p.k, u[n]=p.u, v[n]=p.v, w[n]=p.w ); } + FI void set(const int n, const XYZEval &p) { NUM_AXIS_CODE(x[n]=p.x, y[n]=p.y, z[n]=p.z, i[n]=p.i, j[n]=p.j, k[n]=p.k, u[n]=p.u, v[n]=p.v, w[n]=p.w ); } // Setter for all individual args FI void set(const int n OPTARGS_NUM(const T)) { NUM_AXIS_CODE(a[n] = x, b[n] = y, c[n] = z, _i[n] = i, _j[n] = j, _k[n] = k, _u[n] = u, _v[n] = v, _w[n] = w); } @@ -981,9 +981,9 @@ struct XYZEarray { }; FI void reset() { ZERO(data); } - FI void set(const int n, const XYval p) { NUM_AXIS_CODE(x[n]=p.x, y[n]=p.y,,,,,,,); } - FI void set(const int n, const XYZval p) { NUM_AXIS_CODE(x[n]=p.x, y[n]=p.y, z[n]=p.z, i[n]=p.i, j[n]=p.j, k[n]=p.k, u[n]=p.u, v[n]=p.v, w[n]=p.w ); } - FI void set(const int n, const XYZEval p) { LOGICAL_AXIS_CODE(e[n]=p.e, x[n]=p.x, y[n]=p.y, z[n]=p.z, i[n]=p.i, j[n]=p.j, k[n]=p.k, u[n]=p.u, v[n]=p.v, w[n]=p.w ); } + FI void set(const int n, const XYval &p) { NUM_AXIS_CODE(x[n]=p.x, y[n]=p.y,,,,,,,); } + FI void set(const int n, const XYZval &p) { NUM_AXIS_CODE(x[n]=p.x, y[n]=p.y, z[n]=p.z, i[n]=p.i, j[n]=p.j, k[n]=p.k, u[n]=p.u, v[n]=p.v, w[n]=p.w ); } + FI void set(const int n, const XYZEval &p) { LOGICAL_AXIS_CODE(e[n]=p.e, x[n]=p.x, y[n]=p.y, z[n]=p.z, i[n]=p.i, j[n]=p.j, k[n]=p.k, u[n]=p.u, v[n]=p.v, w[n]=p.w ); } // Setter for all individual args FI void set(const int n OPTARGS_NUM(const T)) { NUM_AXIS_CODE(a[n] = x, b[n] = y, c[n] = z, _i[n] = i, _j[n] = j, _k[n] = k, _u[n] = u, _v[n] = v, _w[n] = w); } diff --git a/Marlin/src/gcode/bedlevel/G26.cpp b/Marlin/src/gcode/bedlevel/G26.cpp index 8c26ca4e8f..94e9b82506 100644 --- a/Marlin/src/gcode/bedlevel/G26.cpp +++ b/Marlin/src/gcode/bedlevel/G26.cpp @@ -268,8 +268,10 @@ typedef struct { // If the end point of the line is closer to the nozzle, flip the direction, // moving from the end to the start. On very small lines the optimization isn't worth it. - if (dist_end < dist_start && (INTERSECTION_CIRCLE_RADIUS) < ABS(line_length)) - return print_line_from_here_to_there(e, s); + if (dist_end < dist_start && (INTERSECTION_CIRCLE_RADIUS) < ABS(line_length)) { + print_line_from_here_to_there(e, s); + return; + } // Decide whether to retract & lift if (dist_start > 2.0) retract_lift_move(s); diff --git a/Marlin/src/gcode/calibrate/G33.cpp b/Marlin/src/gcode/calibrate/G33.cpp index 395da649d3..76bf250346 100644 --- a/Marlin/src/gcode/calibrate/G33.cpp +++ b/Marlin/src/gcode/calibrate/G33.cpp @@ -598,7 +598,7 @@ void GcodeSuite::G33() { LOOP_NUM_AXES(axis) delta_tower_angle_trim[axis] -= a_sum / 3.0f; } - // adjust delta_height and endstops by the max amount + // Adjust delta_height and endstops by the max amount const float z_temp = _MAX(delta_endstop_adj.a, delta_endstop_adj.b, delta_endstop_adj.c); delta_height -= z_temp; LOOP_NUM_AXES(axis) delta_endstop_adj[axis] -= z_temp; @@ -606,7 +606,7 @@ void GcodeSuite::G33() { recalc_delta_settings(); NOMORE(zero_std_dev_min, zero_std_dev); - // print report + // Print report if (verbose_level == 3 || verbose_level == 0) { print_calibration_results(z_at_pt, _tower_results, _opposite_results); diff --git a/Marlin/src/gcode/feature/powerloss/M413.cpp b/Marlin/src/gcode/feature/powerloss/M413.cpp index 7f0e2e2b9a..68cdc01668 100644 --- a/Marlin/src/gcode/feature/powerloss/M413.cpp +++ b/Marlin/src/gcode/feature/powerloss/M413.cpp @@ -41,10 +41,10 @@ */ void GcodeSuite::M413() { + if (!parser.seen_any()) return M413_report(); + if (parser.seen('S')) recovery.enable(parser.value_bool()); - else - M413_report(); #if HAS_PLR_BED_THRESHOLD if (parser.seenval('B')) diff --git a/Marlin/src/gcode/motion/G0_G1.cpp b/Marlin/src/gcode/motion/G0_G1.cpp index c6c1833806..b489b659ae 100644 --- a/Marlin/src/gcode/motion/G0_G1.cpp +++ b/Marlin/src/gcode/motion/G0_G1.cpp @@ -86,9 +86,10 @@ void GcodeSuite::G0_G1(TERN_(HAS_FAST_MOVES, const bool fast_move/*=false*/)) { const float echange = destination.e - current_position.e; // Is this a retract or recover move? if (WITHIN(ABS(echange), MIN_AUTORETRACT, MAX_AUTORETRACT) && fwretract.retracted[active_extruder] == (echange > 0.0)) { - current_position.e = destination.e; // Hide a G1-based retract/recover from calculations - sync_plan_position_e(); // AND from the planner - return fwretract.retract(echange < 0.0); // Firmware-based retract/recover (double-retract ignored) + current_position.e = destination.e; // Hide a G1-based retract/recover from calculations + sync_plan_position_e(); // AND from the planner + fwretract.retract(echange < 0.0); // Firmware-based retract/recover (double-retract ignored) + return; } } } diff --git a/Marlin/src/gcode/probe/M951.cpp b/Marlin/src/gcode/probe/M951.cpp index db0278e431..15d3d47af0 100644 --- a/Marlin/src/gcode/probe/M951.cpp +++ b/Marlin/src/gcode/probe/M951.cpp @@ -80,7 +80,7 @@ void GcodeSuite::M951() { if (parser.seenval('H')) mpe_settings.fast_feedrate = MMM_TO_MMS(parser.value_linear_units()); if (parser.seenval('D')) mpe_settings.travel_distance = parser.value_linear_units(); if (parser.seenval('C')) mpe_settings.compensation_factor = parser.value_float(); - if (!parser.seen("CDHIJLR")) mpe_settings_report(); + if (!parser.seen_any()) mpe_settings_report(); } #endif // MAGNETIC_PARKING_EXTRUDER diff --git a/Marlin/src/gcode/temp/M106_M107.cpp b/Marlin/src/gcode/temp/M106_M107.cpp index afa2ebfc56..ddfc8514c0 100644 --- a/Marlin/src/gcode/temp/M106_M107.cpp +++ b/Marlin/src/gcode/temp/M106_M107.cpp @@ -65,7 +65,10 @@ void GcodeSuite::M106() { #if ENABLED(EXTRA_FAN_SPEED) const uint16_t t = parser.intval('T'); - if (t > 0) return thermalManager.set_temp_fan_speed(pfan, t); + if (t > 0) { + thermalManager.set_temp_fan_speed(pfan, t); + return; + } #endif const uint16_t dspeed = parser.seen_test('A') ? thermalManager.fan_speed[active_extruder] : 255; diff --git a/Marlin/src/inc/Changes.h b/Marlin/src/inc/Changes.h index 839804d920..cbfdcfc47f 100644 --- a/Marlin/src/inc/Changes.h +++ b/Marlin/src/inc/Changes.h @@ -765,15 +765,15 @@ #endif // Consolidate TMC26X, validate migration (#24373) -#define _ISMAX_1(A) defined(A##_MAX_CURRENT) -#define _ISSNS_1(A) defined(A##_SENSE_RESISTOR) -#if DO(ISMAX,||,ALL_AXIS_NAMES) +#define _ISMAX(A) defined(A##_MAX_CURRENT) || +#define _ISSNS(A) defined(A##_SENSE_RESISTOR) || +#if MAP(_ISMAX, ALL_AXIS_NAMES) 0 #error "*_MAX_CURRENT is now set with *_CURRENT." -#elif DO(ISSNS,||,ALL_AXIS_NAMES) +#elif MAP(_ISSNS, ALL_AXIS_NAMES) 0 #error "*_SENSE_RESISTOR (in Milli-Ohms) is now set with *_RSENSE (in Ohms), so you must divide values by 1000." #endif -#undef _ISMAX_1 -#undef _ISSNS_1 +#undef _ISMAX +#undef _ISSNS // L64xx stepper drivers have been removed #define _L6470 0x6470 diff --git a/Marlin/src/inc/Conditionals-2-LCD.h b/Marlin/src/inc/Conditionals-2-LCD.h index 362ca7a714..8f92948d56 100644 --- a/Marlin/src/inc/Conditionals-2-LCD.h +++ b/Marlin/src/inc/Conditionals-2-LCD.h @@ -663,11 +663,6 @@ #define BOOT_MARLIN_LOGO_SMALL #endif -// Flow and feedrate editing -#if HAS_EXTRUDERS && ANY(HAS_MARLINUI_MENU, DWIN_CREALITY_LCD, DWIN_LCD_PROUI, MALYAN_LCD, TOUCH_SCREEN) - #define HAS_FLOW_EDIT 1 -#endif - /** * TFT Displays * diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 08782553ba..9d857f1e3a 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -2382,6 +2382,7 @@ void setMoveZ() { hmiValue.axis = Z_AXIS; setPFloatOnClick(Z_MIN_POS, Z_MAX_POS, #endif void setSpeed() { setPIntOnClick(SPEED_EDIT_MIN, SPEED_EDIT_MAX); } +void setFlow() { setPIntOnClick(FLOW_EDIT_MIN, FLOW_EDIT_MAX, []{ planner.refresh_e_factor(0); }); } #if HAS_HOTEND void applyHotendTemp() { thermalManager.setTargetHotend(menuData.value, 0); } @@ -2426,8 +2427,6 @@ void setSpeed() { setPIntOnClick(SPEED_EDIT_MIN, SPEED_EDIT_MAX); } #endif // ADVANCED_PAUSE_FEATURE -void setFlow() { setPIntOnClick(FLOW_EDIT_MIN, FLOW_EDIT_MAX, []{ planner.refresh_e_factor(0); }); } - // Bed Tramming #if ENABLED(LCD_BED_TRAMMING) @@ -2596,23 +2595,25 @@ void setFlow() { setPIntOnClick(FLOW_EDIT_MIN, FLOW_EDIT_MAX, []{ planner.refres #if ENABLED(MESH_BED_LEVELING) + #define MESH_Z_FDIGITS 2 + void manualMeshStart() { LCD_MESSAGE(MSG_UBL_BUILD_MESH_MENU); gcode.process_subcommands_now(F("G28XYO\nG28Z\nM211S0\nG29S1")); #ifdef MANUAL_PROBE_START_Z const uint8_t line = currentMenu->line(mMeshMoveZItem->pos); - DWINUI::drawSignedFloat(hmiData.colorText, hmiData.colorBackground, 3, 2, VALX - 2 * DWINUI::fontWidth(DWIN_FONT_MENU), MBASE(line), MANUAL_PROBE_START_Z); + DWINUI::drawSignedFloat(hmiData.colorText, hmiData.colorBackground, 3, MESH_Z_FDIGITS, VALX - 2 * DWINUI::fontWidth(DWIN_FONT_MENU), MBASE(line), MANUAL_PROBE_START_Z); #endif } void liveMeshMoveZ() { - *menuData.floatPtr = menuData.value / POW(10, 2); + *menuData.floatPtr = menuData.value / POW(10, MESH_Z_FDIGITS); if (!planner.is_full()) { planner.synchronize(); planner.buffer_line(current_position, manual_feedrate_mm_s[Z_AXIS]); } } - void setMMeshMoveZ() { setPFloatOnClick(-1, 1, 2, planner.synchronize, liveMeshMoveZ); } + void setMMeshMoveZ() { setPFloatOnClick(-1, 1, MESH_Z_FDIGITS, planner.synchronize, liveMeshMoveZ); } void manualMeshContinue() { gcode.process_subcommands_now(F("G29S2")); @@ -2686,8 +2687,9 @@ void applyMaxAccel() { planner.set_max_acceleration(hmiValue.axis, menuData.valu #endif #if ENABLED(LIN_ADVANCE) - void applyLA_K() { planner.set_advance_k(menuData.value / MINUNITMULT); } - void setLA_K() { setPFloatOnClick(0, 10, 3, applyLA_K); } + #define LA_FDIGITS 3 + void applyLA_K() { planner.set_advance_k(menuData.value / POW(10, LA_FDIGITS)); } + void setLA_K() { setPFloatOnClick(0, 10, LA_FDIGITS, applyLA_K); } #endif #if HAS_X_AXIS @@ -3515,6 +3517,7 @@ void drawTuneMenu() { if (SET_MENU_R(tuneMenu, selrect({73, 2, 28, 12}), MSG_TUNE, items)) { BACK_ITEM(gotoPrintProcess); EDIT_ITEM(ICON_Speed, MSG_SPEED, onDrawSpeedItem, setSpeed, &feedrate_percentage); + EDIT_ITEM(ICON_Flow, MSG_FLOW, onDrawPIntMenu, setFlow, &planner.flow_percentage[0]); #if HAS_HOTEND hotendTargetItem = EDIT_ITEM(ICON_HotendTemp, MSG_UBL_SET_TEMP_HOTEND, onDrawHotendTemp, setHotendTemp, &thermalManager.temp_hotend[0].target); #endif @@ -3529,7 +3532,6 @@ void drawTuneMenu() { #elif ALL(HAS_ZOFFSET_ITEM, MESH_BED_LEVELING, BABYSTEPPING) EDIT_ITEM(ICON_Zoffset, MSG_HOME_OFFSET_Z, onDrawPFloat2Menu, setZOffset, &BABY_Z_VAR); #endif - EDIT_ITEM(ICON_Flow, MSG_FLOW, onDrawPIntMenu, setFlow, &planner.flow_percentage[0]); #if ENABLED(ADVANCED_PAUSE_FEATURE) MENU_ITEM(ICON_FilMan, MSG_FILAMENTCHANGE, onDrawMenuItem, changeFilament); #endif @@ -3546,8 +3548,8 @@ void drawTuneMenu() { EDIT_ITEM(ICON_JDmm, MSG_JUNCTION_DEVIATION, onDrawPFloat3Menu, setJDmm, &planner.junction_deviation_mm); #endif #if ENABLED(PROUI_ITEM_ADVK) - float editable_decimal = planner.get_advance_k(); - EDIT_ITEM(ICON_MaxAccelerated, MSG_ADVANCE_K, onDrawPFloat3Menu, setLA_K, &editable_decimal); + float editable_k = planner.get_advance_k(); + EDIT_ITEM(ICON_MaxAccelerated, MSG_ADVANCE_K, onDrawPFloat3Menu, setLA_K, &editable_k); #endif #if HAS_LOCKSCREEN MENU_ITEM(ICON_Lock, MSG_LOCKSCREEN, onDrawMenuItem, dwinLockScreen); @@ -3685,8 +3687,8 @@ void drawMotionMenu() { MENU_ITEM(ICON_Homing, MSG_HOMING_FEEDRATE, onDrawSubMenu, drawHomingFRMenu); #endif #if ENABLED(LIN_ADVANCE) - float editable_decimal = planner.get_advance_k(); - EDIT_ITEM(ICON_MaxAccelerated, MSG_ADVANCE_K, onDrawPFloat3Menu, setLA_K, &editable_decimal); + float editable_k = planner.get_advance_k(); + EDIT_ITEM(ICON_MaxAccelerated, MSG_ADVANCE_K, onDrawPFloat3Menu, setLA_K, &editable_k); #endif #if ENABLED(SHAPING_MENU) MENU_ITEM(ICON_InputShaping, MSG_INPUT_SHAPING, onDrawSubMenu, drawInputShaping_menu); @@ -3694,8 +3696,8 @@ void drawMotionMenu() { #if ENABLED(ADAPTIVE_STEP_SMOOTHING_TOGGLE) EDIT_ITEM(ICON_UBLActive, MSG_STEP_SMOOTHING, onDrawChkbMenu, setAdaptiveStepSmoothing, &stepper.adaptive_step_smoothing_enabled); #endif + EDIT_ITEM(ICON_Speed, MSG_SPEED, onDrawSpeedItem, setSpeed, &feedrate_percentage); EDIT_ITEM(ICON_Flow, MSG_FLOW, onDrawPIntMenu, setFlow, &planner.flow_percentage[0]); - EDIT_ITEM(ICON_Speed, MSG_SPEED, onDrawPIntMenu, setSpeed, &feedrate_percentage); } updateMenu(motionMenu); } @@ -4028,9 +4030,10 @@ void drawMaxAccelMenu() { void setSensorResponse() { setPFloatOnClick(0, 1, 4); } void setAmbientXfer() { setPFloatOnClick(0, 1, 4); } #if ENABLED(MPC_INCLUDE_FAN) - void onDrawFanAdj(MenuItem* menuitem, int8_t line) { onDrawFloatMenu(menuitem, line, 4, thermalManager.temp_hotend[0].fanCoefficient()); } - void applyFanAdj() { thermalManager.temp_hotend[0].applyFanAdjustment(menuData.value / POW(10, 4)); } - void setFanAdj() { setFloatOnClick(0, 1, 4, thermalManager.temp_hotend[0].fanCoefficient(), applyFanAdj); } + #define MPC_FAN_FDIGITS 4 + void onDrawFanAdj(MenuItem* menuitem, int8_t line) { onDrawFloatMenu(menuitem, line, MPC_FAN_FDIGITS, thermalManager.temp_hotend[0].fanCoefficient()); } + void applyFanAdj() { thermalManager.temp_hotend[0].applyFanAdjustment(menuData.value / POW(10, MPC_FAN_FDIGITS)); } + void setFanAdj() { setFloatOnClick(0, 1, MPC_FAN_FDIGITS, thermalManager.temp_hotend[0].fanCoefficient(), applyFanAdj); } #endif #endif @@ -4074,27 +4077,28 @@ void drawMaxAccelMenu() { #endif #if ENABLED(PID_EDIT_MENU) - void setKp() { setPFloatOnClick(0, 1000, 2); } + #define PID_FDIGITS 2 + void setKp() { setPFloatOnClick(0, 1000, PID_FDIGITS); } void applyPIDi() { - *menuData.floatPtr = scalePID_i(menuData.value / POW(10, 2)); + *menuData.floatPtr = scalePID_i(menuData.value / POW(10, PID_FDIGITS)); TERN_(PIDTEMP, thermalManager.updatePID()); } void applyPIDd() { - *menuData.floatPtr = scalePID_d(menuData.value / POW(10, 2)); + *menuData.floatPtr = scalePID_d(menuData.value / POW(10, PID_FDIGITS)); TERN_(PIDTEMP, thermalManager.updatePID()); } void setKi() { menuData.floatPtr = (float*)static_cast(currentMenu->selectedItem())->value; const float value = unscalePID_i(*menuData.floatPtr); - setFloatOnClick(0, 1000, 2, value, applyPIDi); + setFloatOnClick(0, 1000, PID_FDIGITS, value, applyPIDi); } void setKd() { menuData.floatPtr = (float*)static_cast(currentMenu->selectedItem())->value; const float value = unscalePID_d(*menuData.floatPtr); - setFloatOnClick(0, 1000, 2, value, applyPIDd); + setFloatOnClick(0, 1000, PID_FDIGITS, value, applyPIDd); } - void onDrawPIDi(MenuItem* menuitem, int8_t line) { onDrawFloatMenu(menuitem, line, 2, unscalePID_i(*(float*)static_cast(menuitem)->value)); } - void onDrawPIDd(MenuItem* menuitem, int8_t line) { onDrawFloatMenu(menuitem, line, 2, unscalePID_d(*(float*)static_cast(menuitem)->value)); } + void onDrawPIDi(MenuItem* menuitem, int8_t line) { onDrawFloatMenu(menuitem, line, PID_FDIGITS, unscalePID_i(*(float*)static_cast(menuitem)->value)); } + void onDrawPIDd(MenuItem* menuitem, int8_t line) { onDrawFloatMenu(menuitem, line, PID_FDIGITS, unscalePID_d(*(float*)static_cast(menuitem)->value)); } #endif // PID_EDIT_MENU #endif // HAS_PID_HEATING diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 5e1c08f863..8678c82130 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -1505,10 +1505,12 @@ void Planner::check_axes_activity() { #if HAS_LEVELING - constexpr xy_pos_t level_fulcrum = { - TERN(Z_SAFE_HOMING, Z_SAFE_HOMING_X_POINT, X_HOME_POS), - TERN(Z_SAFE_HOMING, Z_SAFE_HOMING_Y_POINT, Y_HOME_POS) - }; + #if ABL_PLANAR + constexpr xy_pos_t level_fulcrum = { + TERN(Z_SAFE_HOMING, Z_SAFE_HOMING_X_POINT, X_HOME_POS), + TERN(Z_SAFE_HOMING, Z_SAFE_HOMING_Y_POINT, Y_HOME_POS) + }; + #endif /** * rx, ry, rz - Cartesian positions in mm diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index c71a73c5be..bda5720919 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -249,7 +249,7 @@ typedef struct PlannerBlock { uint32_t cruise_time; // Cruise time in STEP timer counts int32_t e_step_ratio_q30; // Ratio of e steps to block steps. #if ENABLED(INPUT_SHAPING_E_SYNC) - uint32_t xy_length_inv_q30; // inverse of block->steps.x + block.steps.y + uint32_t xy_length_inv_q30; // Inverse of block->steps.x + block.steps.y #endif #endif #if ANY(S_CURVE_ACCELERATION, SMOOTH_LIN_ADVANCE) @@ -370,7 +370,6 @@ typedef struct PlannerSettings { }; #undef _EASU #undef _DASU - #undef _DLIM #endif feedRate_t max_feedrate_mm_s[DISTINCT_AXES]; // (mm/s) M203 XYZE - Max speeds diff --git a/ini/hc32.ini b/ini/hc32.ini index 8a55e3b495..19baeda210 100644 --- a/ini/hc32.ini +++ b/ini/hc32.ini @@ -27,8 +27,8 @@ # Base Environment for all HC32F460 variants # [HC32F460_base] -platform = https://github.com/shadow578/platform-hc32f46x/archive/1.1.0.zip -platform_packages = framework-hc32f46x-ddl@https://github.com/shadow578/framework-hc32f46x-ddl/archive/2.2.2.zip +platform = https://github.com/shadow578/platform-hc32f46x/archive/1.1.1.zip +platform_packages = framework-hc32f46x-ddl@https://github.com/shadow578/framework-hc32f46x-ddl/archive/2.2.3.zip framework-arduino-hc32f46x@https://github.com/shadow578/framework-arduino-hc32f46x/archive/1.2.0.zip board = generic_hc32f460 build_src_filter = ${common.default_src_filter} + + From fde0eaf1e7e9a42d22f7dfb4d48f905e07949384 Mon Sep 17 00:00:00 2001 From: narno2202 <130909513+narno2202@users.noreply.github.com> Date: Tue, 27 May 2025 00:36:14 +0200 Subject: [PATCH 067/102] =?UTF-8?q?=E2=9A=A1=EF=B8=8F=20Remove=20FT=20Moti?= =?UTF-8?q?on=20extraneous=20code=20(#27881)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/stepper.cpp | 23 ++++++++++------------- 1 file changed, 10 insertions(+), 13 deletions(-) diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index a6931c8d0d..ad7995bfc7 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -1541,7 +1541,7 @@ void Stepper::isr() { uint8_t max_loops = 10; #if ENABLED(FT_MOTION) - static uint32_t ftMotion_nextAuxISR = 0U; // Storage for the next ISR of the auxilliary tasks. + static uint32_t ftMotion_nextAuxISR = 0U; // Storage for the next ISR of the auxiliary tasks. const bool using_ftMotion = ftMotion.cfg.active; #else constexpr bool using_ftMotion = false; @@ -1556,21 +1556,18 @@ void Stepper::isr() { #if ENABLED(FT_MOTION) if (using_ftMotion) { - if (!nextMainISR) { // Main ISR is ready to fire during this iteration? - nextMainISR = FTM_MIN_TICKS; // Set to minimum interval (a limit on the top speed) - ftMotion_stepper(); // Run FTM Stepping - // Define 2.5 msec task for auxilliary functions. - if (!ftMotion_nextAuxISR) { - TERN_(BABYSTEPPING, if (babystep.has_steps()) babystepping_isr()); - ftMotion_nextAuxISR = (STEPPER_TIMER_RATE) / 400; - } + ftMotion_stepper(); // Run FTM Stepping + + // Define 2.5 msec task for auxiliary functions. + if (!ftMotion_nextAuxISR) { + TERN_(BABYSTEPPING, if (babystep.has_steps()) babystepping_isr()); + ftMotion_nextAuxISR = (STEPPER_TIMER_RATE) / 400; } - // Enable ISRs to reduce latency for higher priority ISRs, or all ISRs if no prioritization. + // Enable ISRs to reduce latency for higher priority ISRs hal.isr_on(); - - interval = _MIN(nextMainISR, ftMotion_nextAuxISR); - nextMainISR -= interval; + + interval = FTM_MIN_TICKS; ftMotion_nextAuxISR -= interval; } From e9ae5208cbf1948b92e08ee463a1ecfba53be722 Mon Sep 17 00:00:00 2001 From: Vovodroid Date: Tue, 27 May 2025 03:16:45 +0300 Subject: [PATCH 068/102] =?UTF-8?q?=E2=9C=A8=20EVENT=5FGCODE=5FAFTER=5FMPC?= =?UTF-8?q?=5FTUNE=20(#27865)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/Configuration.h | 1 + Marlin/src/module/temperature.cpp | 4 ++++ buildroot/tests/STM32F103RE_creality | 3 ++- 3 files changed, 7 insertions(+), 1 deletion(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 859f0bbd33..08216d17b8 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -767,6 +767,7 @@ #define MPC_TUNING_POS { X_CENTER, Y_CENTER, 1.0f } // (mm) M306 Autotuning position, ideally bed center at first layer height. #define MPC_TUNING_END_Z 10.0f // (mm) M306 Autotuning final Z position. + //#define EVENT_GCODE_AFTER_MPC_TUNE "M84" // G-code to execute after MPC tune finished and Z raised. #endif //=========================================================================== diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 30690345a5..5c760a7689 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -1104,6 +1104,10 @@ void Temperature::factory_reset() { do_z_clearance(MPC_TUNING_END_Z, false); + #ifdef EVENT_GCODE_AFTER_MPC_TUNE + gcode.process_subcommands_now(F(EVENT_GCODE_AFTER_MPC_TUNE)); + #endif + TERN_(TEMP_TUNING_MAINTAIN_FAN, adaptive_fan_slowing = true); } diff --git a/buildroot/tests/STM32F103RE_creality b/buildroot/tests/STM32F103RE_creality index 5681688929..0855a71ee4 100755 --- a/buildroot/tests/STM32F103RE_creality +++ b/buildroot/tests/STM32F103RE_creality @@ -20,7 +20,8 @@ exec_test $1 $2 "Ender-3 V2 - JyersUI (ABL Bilinear/Manual)" "$3" use_example_configs "Creality/Ender-3 V2/CrealityV422/CrealityUI" opt_disable DWIN_CREALITY_LCD PIDTEMP -opt_enable DWIN_MARLINUI_LANDSCAPE LCD_ENDSTOP_TEST AUTO_BED_LEVELING_UBL BLTOUCH Z_SAFE_HOMING MPCTEMP MPC_AUTOTUNE \ +opt_enable DWIN_MARLINUI_LANDSCAPE LCD_ENDSTOP_TEST AUTO_BED_LEVELING_UBL BLTOUCH Z_SAFE_HOMING \ + MPCTEMP MPC_AUTOTUNE EVENT_GCODE_AFTER_MPC_TUNE \ MARLIN_BRICKOUT MARLIN_INVADERS MARLIN_SNAKE GAMES_EASTER_EGG exec_test $1 $2 "Ender-3 V2 - MarlinUI (Games, UBL+BLTOUCH, MPCTEMP, LCD_ENDSTOP_TEST)" "$3" From 3f3c8257f7fc133471c1a86e6adc463bc9539f2c Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 27 May 2025 00:35:13 +0000 Subject: [PATCH 069/102] [cron] Bump distribution date (2025-05-27) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index b46b688339..34ac9adaa3 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-05-26" +//#define STRING_DISTRIBUTION_DATE "2025-05-27" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 06c29974a7..8d0c6361af 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-05-26" + #define STRING_DISTRIBUTION_DATE "2025-05-27" #endif /** From ebecd7649286fe12a111218dfc2a1185a48cc9aa Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Mon, 26 May 2025 20:51:41 -0700 Subject: [PATCH 070/102] =?UTF-8?q?=F0=9F=94=A7=20Update=20BIQU=20BX=20SPI?= =?UTF-8?q?=20driver=20conditionals=20(#27886)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 2 +- .../pins/stm32h7/pins_BTT_SKR_SE_BX_common.h | 21 +++++++++++-------- 2 files changed, 13 insertions(+), 10 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index fee4c452ab..7939b5cc9b 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -3470,7 +3470,7 @@ * * It is recommended to set HOMING_BUMP_MM to { 0, 0, 0 }. * - * SPI_ENDSTOPS *** TMC2130/TMC5160 Only *** + * SPI_ENDSTOPS *** TMC2130, TMC2240, and TMC5160 Only *** * Poll the driver through SPI to determine load when homing. * Removes the need for a wire from DIAG1 to an endstop pin. * diff --git a/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX_common.h b/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX_common.h index 529e610624..736f79e664 100644 --- a/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX_common.h +++ b/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX_common.h @@ -124,16 +124,19 @@ #endif // -// SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130, TMC2160, TMC2240, TMC2660, TMC5130, or TMC5160 stepper drivers // -#ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI PC6 -#endif -#ifndef TMC_SPI_MISO - #define TMC_SPI_MISO PG3 -#endif -#ifndef TMC_SPI_SCK - #define TMC_SPI_SCK PC7 +#if HAS_TMC_SPI + #define TMC_USE_SW_SPI + #ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PC6 + #endif + #ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PG3 + #endif + #ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PC7 + #endif #endif #if HAS_TMC_UART From 3572fd75b596ed99e43093d99ce360828a187a4d Mon Sep 17 00:00:00 2001 From: vehystrix Date: Tue, 27 May 2025 06:46:46 +0200 Subject: [PATCH 071/102] =?UTF-8?q?=F0=9F=90=9B=20Fix=20M201=20with=20XY?= =?UTF-8?q?=5FFREQUENCY=5FLIMIT=20(#27859)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/gcode/config/M200-M205.cpp | 29 +++++++++++++++++++++------ 1 file changed, 23 insertions(+), 6 deletions(-) diff --git a/Marlin/src/gcode/config/M200-M205.cpp b/Marlin/src/gcode/config/M200-M205.cpp index a55813aeae..7ad7de8617 100644 --- a/Marlin/src/gcode/config/M200-M205.cpp +++ b/Marlin/src/gcode/config/M200-M205.cpp @@ -124,8 +124,13 @@ * S : Speed factor percentage. */ void GcodeSuite::M201() { - if (!parser.seen("T" STR_AXES_LOGICAL TERN_(XY_FREQUENCY_LIMIT, "FS"))) + if (!parser.seen("T" STR_AXES_LOGICAL + #ifdef XY_FREQUENCY_LIMIT + "FS" + #endif + )) { return M201_report(); + } const int8_t target_extruder = get_target_extruder_from_command(); if (target_extruder < 0) return; @@ -147,7 +152,11 @@ void GcodeSuite::M201_report(const bool forReplay/*=true*/) { TERN_(MARLIN_SMALL_BUILD, return); report_heading_etc(forReplay, F(STR_MAX_ACCELERATION)); + + bool eol = false; + #if NUM_AXES + eol = true; SERIAL_ECHOPGM_P( LIST_N(DOUBLE(NUM_AXES), PSTR(" M201 X"), LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[X_AXIS]), @@ -164,13 +173,18 @@ void GcodeSuite::M201_report(const bool forReplay/*=true*/) { #endif #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS) + eol = true; SERIAL_ECHOPGM_P(SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_acceleration_mm_per_s2[E_AXIS])); #endif - #if NUM_AXES || (HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS)) - SERIAL_EOL(); + #ifdef XY_FREQUENCY_LIMIT + eol = true; + SERIAL_ECHOPGM_P(PSTR(" F"), planner.xy_freq_limit_hz); + SERIAL_ECHOPGM_P(PSTR(" S"), (planner.xy_freq_min_speed_factor * 100)); #endif + if (eol) SERIAL_EOL(); + #if ENABLED(DISTINCT_E_FACTORS) for (uint8_t i = 0; i < E_STEPPERS; ++i) { report_echo_start(forReplay); @@ -205,7 +219,11 @@ void GcodeSuite::M203_report(const bool forReplay/*=true*/) { TERN_(MARLIN_SMALL_BUILD, return); report_heading_etc(forReplay, F(STR_MAX_FEEDRATES)); + + bool eol = false; + #if NUM_AXES + eol = true; SERIAL_ECHOPGM_P( LIST_N(DOUBLE(NUM_AXES), PSTR(" M203 X"), LINEAR_UNIT(planner.settings.max_feedrate_mm_s[X_AXIS]), @@ -222,12 +240,11 @@ void GcodeSuite::M203_report(const bool forReplay/*=true*/) { #endif #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS) + eol = true; SERIAL_ECHOPGM_P(SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_feedrate_mm_s[E_AXIS])); #endif - #if NUM_AXES || (HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS)) - SERIAL_EOL(); - #endif + if (eol) SERIAL_EOL(); #if ENABLED(DISTINCT_E_FACTORS) for (uint8_t i = 0; i < E_STEPPERS; ++i) { From 3494482cb0a192024929fc14deee3cc7f329c386 Mon Sep 17 00:00:00 2001 From: Andrew <18502096+classicrocker883@users.noreply.github.com> Date: Tue, 27 May 2025 02:05:01 -0400 Subject: [PATCH 072/102] =?UTF-8?q?=F0=9F=8E=A8=20Misc.=20cleanup,=20tweak?= =?UTF-8?q?=20unused=20LED=5FGraduallyControl=20(#27422)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/lcd/e3v2/common/encoder.cpp | 17 +++++++++-------- Marlin/src/module/settings.cpp | 2 +- Marlin/src/module/stepper.cpp | 4 ++-- 3 files changed, 12 insertions(+), 11 deletions(-) diff --git a/Marlin/src/lcd/e3v2/common/encoder.cpp b/Marlin/src/lcd/e3v2/common/encoder.cpp index 889d1c61f3..2ae16f8bb1 100644 --- a/Marlin/src/lcd/e3v2/common/encoder.cpp +++ b/Marlin/src/lcd/e3v2/common/encoder.cpp @@ -137,9 +137,8 @@ EncoderState encoderReceiveAnalyze() { // LED write data void LED_WriteData() { - uint8_t tempCounter_LED, tempCounter_Bit; - for (tempCounter_LED = 0; tempCounter_LED < LED_NUM; tempCounter_LED++) { - for (tempCounter_Bit = 0; tempCounter_Bit < 24; tempCounter_Bit++) { + for (uint8_t tempCounter_LED = 0; tempCounter_LED < LED_NUM; tempCounter_LED++) { + for (uint8_t tempCounter_Bit = 0; tempCounter_Bit < 24; tempCounter_Bit++) { if (LED_DataArray[tempCounter_LED] & (0x800000 >> tempCounter_Bit)) { LED_DATA_HIGH; DELAY_NS(300); @@ -190,20 +189,22 @@ EncoderState encoderReceiveAnalyze() { } } - struct { bool g, r, b; } led_flag = { false, false, false }; + struct { bool g, r, b; } led_flag; for (uint8_t i = 0; i < LED_NUM; i++) { + led_flag = { false, false, false }; while (1) { const uint8_t g = uint8_t(LED_DataArray[i] >> 16), r = uint8_t(LED_DataArray[i] >> 8), b = uint8_t(LED_DataArray[i]); if (g == led_data[i].g) led_flag.g = true; - else LED_DataArray[i] += (g > led_data[i].g) ? -0x010000 : 0x010000; + else LED_DataArray[i] += (g > led_data[i].g) ? -_BV32(16) : _BV32(16); if (r == led_data[i].r) led_flag.r = true; - else LED_DataArray[i] += (r > led_data[i].r) ? -0x000100 : 0x000100; + else LED_DataArray[i] += (r > led_data[i].r) ? -_BV32(8) : _BV32(8); if (b == led_data[i].b) led_flag.b = true; - else LED_DataArray[i] += (b > led_data[i].b) ? -0x000001 : 0x000001; + else LED_DataArray[i] += (b > led_data[i].b) ? -_BV32(0) : _BV32(0); + LED_WriteData(); - if (led_flag.r && led_flag.g && led_flag.b) break; + if (led_flag.g && led_flag.r && led_flag.b) break; delay(change_Interval); } } diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 59cb7244e9..2161be5abc 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -655,7 +655,7 @@ typedef struct SettingsDataStruct { // Fixed-Time Motion // #if ENABLED(FT_MOTION) - ft_config_t ftMotion_cfg; // M493 + ft_config_t ftMotion_cfg; // M493 #endif // diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index ad7995bfc7..e5255246e1 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -1557,7 +1557,7 @@ void Stepper::isr() { if (using_ftMotion) { ftMotion_stepper(); // Run FTM Stepping - + // Define 2.5 msec task for auxiliary functions. if (!ftMotion_nextAuxISR) { TERN_(BABYSTEPPING, if (babystep.has_steps()) babystepping_isr()); @@ -1566,7 +1566,7 @@ void Stepper::isr() { // Enable ISRs to reduce latency for higher priority ISRs hal.isr_on(); - + interval = FTM_MIN_TICKS; ftMotion_nextAuxISR -= interval; } From 843f79589cd3f305998f217af55914e9cacb11f6 Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Tue, 27 May 2025 10:58:49 -0700 Subject: [PATCH 073/102] =?UTF-8?q?=F0=9F=94=A7=20Update=20BTT002=20SPI=20?= =?UTF-8?q?driver=20conditionals=20(#27887)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Counterpart to #27886 --- .../src/pins/stm32f4/pins_BTT_BTT002_V1_0.h | 21 +++++++++++-------- 1 file changed, 12 insertions(+), 9 deletions(-) diff --git a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h index bcbdaedcf2..0e059106b8 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h @@ -108,16 +108,19 @@ #endif // -// SPI pins for TMC2130 stepper drivers +// SPI pins for TMC2130, TMC2160, TMC2240, TMC2660, TMC5130, or TMC5160 stepper drivers // -#ifndef TMC_SPI_MOSI - #define TMC_SPI_MOSI PB15 -#endif -#ifndef TMC_SPI_MISO - #define TMC_SPI_MISO PB14 -#endif -#ifndef TMC_SPI_SCK - #define TMC_SPI_SCK PB13 +#if HAS_TMC_SPI + #define TMC_USE_SW_SPI + #ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PB15 + #endif + #ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PB14 + #endif + #ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PB13 + #endif #endif #if HAS_TMC_UART From 88d368ad9ded208c7a8f10459aa2c560eed407db Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Wed, 28 May 2025 06:01:01 +1200 Subject: [PATCH 074/102] =?UTF-8?q?=F0=9F=A9=B9=20Misc=20temp=20sensor=20f?= =?UTF-8?q?ixups=20(#27884)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/HAL/GD32_MFL/temp_soc.h | 2 +- Marlin/src/HAL/STM32/temp_soc.h | 2 +- Marlin/src/module/temperature.cpp | 90 ++++++++++++++++-------------- 3 files changed, 51 insertions(+), 43 deletions(-) diff --git a/Marlin/src/HAL/GD32_MFL/temp_soc.h b/Marlin/src/HAL/GD32_MFL/temp_soc.h index eeb144c422..5f1be64e43 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)) / ((TS_TYPICAL_SLOPE) / 1000) + TS_TYPICAL_TEMP) +#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) diff --git a/Marlin/src/HAL/STM32/temp_soc.h b/Marlin/src/HAL/STM32/temp_soc.h index 05fad695c3..cc165dd5e4 100644 --- a/Marlin/src/HAL/STM32/temp_soc.h +++ b/Marlin/src/HAL/STM32/temp_soc.h @@ -341,6 +341,6 @@ #elif defined(TS_TYPICAL_V) && defined(TS_TYPICAL_SLOPE) && defined(TS_TYPICAL_TEMP) - #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) + TS_TYPICAL_TEMP) + #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) #endif diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 5c760a7689..c1684a9fe1 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -2460,11 +2460,6 @@ void Temperature::task() { UNUSED(ms); } -// For a 5V input the AD595 returns a value scaled with 10mV per °C. (Minimum input voltage is 5V.) -#define TEMP_AD595(RAW) ((RAW) * (ADC_VREF_MV / 10) / float(HAL_ADC_RANGE) / (OVERSAMPLENR) * (TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET) -// For a 5V input the AD8495 returns a value scaled with 5mV per °C. (Minimum input voltage is 2.7V.) -#define TEMP_AD8495(RAW) ((RAW) * (ADC_VREF_MV / 5) / float(HAL_ADC_RANGE) / (OVERSAMPLENR) * (TEMP_SENSOR_AD8495_GAIN) + TEMP_SENSOR_AD8495_OFFSET) - /** * Bisect search for the range of the 'raw' value, then interpolate * proportionally between the under and over values. @@ -2604,6 +2599,22 @@ void Temperature::task() { } #endif +#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) + * (TEMP_SENSOR_AD595_GAIN) + (TEMP_SENSOR_AD595_OFFSET); + } +#endif + +#if ANY_THERMISTOR_IS(-4) + // For a 5V input the AD8495 returns a value scaled with 5mV per °C. (Minimum input voltage is 2.7V.) + static constexpr celsius_float_t temp_ad8495(const raw_adc_t raw) { + return raw * (float(ADC_VREF_MV) / 5.0f) / float(HAL_ADC_RANGE) / (OVERSAMPLENR) + * (TEMP_SENSOR_AD8495_GAIN) + (TEMP_SENSOR_AD8495_OFFSET); + } +#endif + #if HAS_HOTEND // Derived from RepRap FiveD extruder::getTemperature() // For hot end temperature measurement. @@ -2630,9 +2641,9 @@ void Temperature::task() { return (int16_t)raw * 0.25f; #endif #elif TEMP_SENSOR_0_IS_AD595 - return TEMP_AD595(raw); + return temp_ad595(raw); #elif TEMP_SENSOR_0_IS_AD8495 - return TEMP_AD8495(raw); + return temp_ad8495(raw); #else break; #endif @@ -2649,9 +2660,9 @@ void Temperature::task() { return (int16_t)raw * 0.25f; #endif #elif TEMP_SENSOR_1_IS_AD595 - return TEMP_AD595(raw); + return temp_ad595(raw); #elif TEMP_SENSOR_1_IS_AD8495 - return TEMP_AD8495(raw); + return temp_ad8495(raw); #else break; #endif @@ -2668,9 +2679,9 @@ void Temperature::task() { return (int16_t)raw * 0.25f; #endif #elif TEMP_SENSOR_2_IS_AD595 - return TEMP_AD595(raw); + return temp_ad595(raw); #elif TEMP_SENSOR_2_IS_AD8495 - return TEMP_AD8495(raw); + return temp_ad8495(raw); #else break; #endif @@ -2678,9 +2689,9 @@ void Temperature::task() { #if TEMP_SENSOR_3_IS_CUSTOM return user_thermistor_to_deg_c(CTI_HOTEND_3, raw); #elif TEMP_SENSOR_3_IS_AD595 - return TEMP_AD595(raw); + return temp_ad595(raw); #elif TEMP_SENSOR_3_IS_AD8495 - return TEMP_AD8495(raw); + return temp_ad8495(raw); #else break; #endif @@ -2688,9 +2699,9 @@ void Temperature::task() { #if TEMP_SENSOR_4_IS_CUSTOM return user_thermistor_to_deg_c(CTI_HOTEND_4, raw); #elif TEMP_SENSOR_4_IS_AD595 - return TEMP_AD595(raw); + return temp_ad595(raw); #elif TEMP_SENSOR_4_IS_AD8495 - return TEMP_AD8495(raw); + return temp_ad8495(raw); #else break; #endif @@ -2698,9 +2709,9 @@ void Temperature::task() { #if TEMP_SENSOR_5_IS_CUSTOM return user_thermistor_to_deg_c(CTI_HOTEND_5, raw); #elif TEMP_SENSOR_5_IS_AD595 - return TEMP_AD595(raw); + return temp_ad595(raw); #elif TEMP_SENSOR_5_IS_AD8495 - return TEMP_AD8495(raw); + return temp_ad8495(raw); #else break; #endif @@ -2708,9 +2719,9 @@ void Temperature::task() { #if TEMP_SENSOR_6_IS_CUSTOM return user_thermistor_to_deg_c(CTI_HOTEND_6, raw); #elif TEMP_SENSOR_6_IS_AD595 - return TEMP_AD595(raw); + return temp_ad595(raw); #elif TEMP_SENSOR_6_IS_AD8495 - return TEMP_AD8495(raw); + return temp_ad8495(raw); #else break; #endif @@ -2718,9 +2729,9 @@ void Temperature::task() { #if TEMP_SENSOR_7_IS_CUSTOM return user_thermistor_to_deg_c(CTI_HOTEND_7, raw); #elif TEMP_SENSOR_7_IS_AD595 - return TEMP_AD595(raw); + return temp_ad595(raw); #elif TEMP_SENSOR_7_IS_AD8495 - return TEMP_AD8495(raw); + return temp_ad8495(raw); #else break; #endif @@ -2754,9 +2765,9 @@ void Temperature::task() { #elif TEMP_SENSOR_BED_IS_THERMISTOR SCAN_THERMISTOR_TABLE(TEMPTABLE_BED, TEMPTABLE_BED_LEN); #elif TEMP_SENSOR_BED_IS_AD595 - return TEMP_AD595(raw); + return temp_ad595(raw); #elif TEMP_SENSOR_BED_IS_AD8495 - return TEMP_AD8495(raw); + return temp_ad8495(raw); #else UNUSED(raw); return 0; @@ -2772,9 +2783,9 @@ void Temperature::task() { #elif TEMP_SENSOR_CHAMBER_IS_THERMISTOR SCAN_THERMISTOR_TABLE(TEMPTABLE_CHAMBER, TEMPTABLE_CHAMBER_LEN); #elif TEMP_SENSOR_CHAMBER_IS_AD595 - return TEMP_AD595(raw); + return temp_ad595(raw); #elif TEMP_SENSOR_CHAMBER_IS_AD8495 - return TEMP_AD8495(raw); + return temp_ad8495(raw); #else UNUSED(raw); return 0; @@ -2790,9 +2801,9 @@ void Temperature::task() { #elif TEMP_SENSOR_COOLER_IS_THERMISTOR SCAN_THERMISTOR_TABLE(TEMPTABLE_COOLER, TEMPTABLE_COOLER_LEN); #elif TEMP_SENSOR_COOLER_IS_AD595 - return TEMP_AD595(raw); + return temp_ad595(raw); #elif TEMP_SENSOR_COOLER_IS_AD8495 - return TEMP_AD8495(raw); + return temp_ad8495(raw); #else UNUSED(raw); return 0; @@ -2808,9 +2819,9 @@ void Temperature::task() { #elif TEMP_SENSOR_PROBE_IS_THERMISTOR SCAN_THERMISTOR_TABLE(TEMPTABLE_PROBE, TEMPTABLE_PROBE_LEN); #elif TEMP_SENSOR_PROBE_IS_AD595 - return TEMP_AD595(raw); + return temp_ad595(raw); #elif TEMP_SENSOR_PROBE_IS_AD8495 - return TEMP_AD8495(raw); + return temp_ad8495(raw); #else UNUSED(raw); return 0; @@ -2826,9 +2837,9 @@ void Temperature::task() { #elif TEMP_SENSOR_BOARD_IS_THERMISTOR SCAN_THERMISTOR_TABLE(TEMPTABLE_BOARD, TEMPTABLE_BOARD_LEN); #elif TEMP_SENSOR_BOARD_IS_AD595 - return TEMP_AD595(raw); + return temp_ad595(raw); #elif TEMP_SENSOR_BOARD_IS_AD8495 - return TEMP_AD8495(raw); + return temp_ad8495(raw); #else UNUSED(raw); return 0; @@ -2839,14 +2850,11 @@ void Temperature::task() { #if HAS_TEMP_SOC // For SoC temperature measurement. celsius_float_t Temperature::analog_to_celsius_soc(const raw_adc_t raw) { - return ( - #ifdef TEMP_SOC_SENSOR - TEMP_SOC_SENSOR(raw) - #else - 0 - #error "TEMP_SENSOR_SOC requires the TEMP_SOC_SENSOR(RAW) macro to be defined for your board." - #endif - ); + #ifndef TEMP_SOC_SENSOR + #error "TEMP_SENSOR_SOC requires the TEMP_SOC_SENSOR(RAW) macro to be defined for your board." + #define TEMP_SOC_SENSOR(...) 0 + #endif + return TEMP_SOC_SENSOR(raw); } #endif @@ -2864,9 +2872,9 @@ void Temperature::task() { #elif TEMP_SENSOR_REDUNDANT_IS_THERMISTOR SCAN_THERMISTOR_TABLE(TEMPTABLE_REDUNDANT, TEMPTABLE_REDUNDANT_LEN); #elif TEMP_SENSOR_REDUNDANT_IS_AD595 - return TEMP_AD595(raw); + return temp_ad595(raw); #elif TEMP_SENSOR_REDUNDANT_IS_AD8495 - return TEMP_AD8495(raw); + return temp_ad8495(raw); #else UNUSED(raw); return 0; From d0e8edad3c5f836dd7f7c200e74bf660c587aee0 Mon Sep 17 00:00:00 2001 From: David Buezas Date: Tue, 27 May 2025 20:15:38 +0200 Subject: [PATCH 075/102] =?UTF-8?q?=F0=9F=90=9B=20More=20robust=20Smooth?= =?UTF-8?q?=20Linear=20Advance=20(#27862)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/module/stepper.cpp | 55 +++++++++++++++++------------------ 1 file changed, 27 insertions(+), 28 deletions(-) diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index e5255246e1..edfed3b8e2 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -2921,8 +2921,13 @@ hal_timer_t Stepper::block_phase_isr() { if (++index == IS_COMPENSATION_BUFFER_SIZE) index = 0; } FORCE_INLINE xy_long_t past_item(const uint16_t n) { - const int16_t i = int16_t(index) - n; - return buffer[i >= 0 ? i : i + IS_COMPENSATION_BUFFER_SIZE]; + int16_t i = int16_t(index) - n; + if (i < 0) i += IS_COMPENSATION_BUFFER_SIZE; + // The following only happens when IS Freq is set below the minimum + // configured at build time ...in which case IS will also misbehave! + // Using setters whenever possible prevents values being set too low. + if (TERN0(MARLIN_DEV_MODE, i < 0)) return {0, 0}; + return buffer[i]; } } DelayBuffer; @@ -2995,44 +3000,38 @@ hal_timer_t Stepper::block_phase_isr() { ? MULT_Q(30, curr_step_rate, current_block->e_step_ratio_q30) : 0; - int32_t total_step_rate = la_step_rate + planned_step_rate; - #if ENABLED(INPUT_SHAPING_E_SYNC) - xy_long_t pre_shaping_rate = xy_long_t({0, 0}), - first_pulse_rate = xy_long_t({0, 0}); - int32_t unshaped_rate_e = total_step_rate; - if (current_block) { - if (current_block->xy_length_inv_q30 > 0) { - unshaped_rate_e = 0; + int32_t unshaped_rate_e = la_step_rate + planned_step_rate; - pre_shaping_rate = xy_long_t({ - TERN0(INPUT_SHAPING_X, MULT_Q(30, total_step_rate * current_block->steps.x, current_block->xy_length_inv_q30)), - TERN0(INPUT_SHAPING_Y, MULT_Q(30, total_step_rate * current_block->steps.y, current_block->xy_length_inv_q30)) - }); + xy_long_t pre_shaping_rate{0}, first_pulse_rate{0}; + if (current_block && current_block->xy_length_inv_q30 > 0) { + pre_shaping_rate = xy_long_t({ + MULT_Q(30, unshaped_rate_e * current_block->steps.x, current_block->xy_length_inv_q30), + MULT_Q(30, unshaped_rate_e * current_block->steps.y, current_block->xy_length_inv_q30) + }); + unshaped_rate_e = 0; - first_pulse_rate = xy_long_t({ - TERN0(INPUT_SHAPING_X, (pre_shaping_rate.x * Stepper::shaping_x.factor1) >> 7), - TERN0(INPUT_SHAPING_Y, (pre_shaping_rate.y * Stepper::shaping_y.factor1) >> 7) - }); - } + first_pulse_rate = xy_long_t({ + TERN_(INPUT_SHAPING_X, shaping_x.enabled ? (pre_shaping_rate.x * shaping_x.factor1) >> 7 :) pre_shaping_rate.x, + TERN_(INPUT_SHAPING_Y, shaping_y.enabled ? (pre_shaping_rate.y * shaping_y.factor1) >> 7 :) pre_shaping_rate.y + }); } - const xy_long_t second_pulse_rate = { - TERN0(INPUT_SHAPING_X, (smooth_lin_adv_lookback(ShapingQueue::get_delay_x()).x * Stepper::shaping_x.factor2)) >> 7, - TERN0(INPUT_SHAPING_Y, (smooth_lin_adv_lookback(ShapingQueue::get_delay_y()).y * Stepper::shaping_y.factor2)) >> 7 - }; + const xy_long_t second_pulse_rate = xy_long_t({ + TERN0(INPUT_SHAPING_X, shaping_x.enabled ? (smooth_lin_adv_lookback(ShapingQueue::get_delay_x()).x * shaping_x.factor2) >> 7 : 0), + TERN0(INPUT_SHAPING_Y, shaping_y.enabled ? (smooth_lin_adv_lookback(ShapingQueue::get_delay_y()).y * shaping_y.factor2) >> 7 : 0) + }); delayBuffer.add(pre_shaping_rate); - const int32_t x = TERN0(INPUT_SHAPING_X, first_pulse_rate.x + second_pulse_rate.x), - y = TERN0(INPUT_SHAPING_Y, first_pulse_rate.y + second_pulse_rate.y); + set_la_interval(unshaped_rate_e + first_pulse_rate.x + second_pulse_rate.x + first_pulse_rate.y + second_pulse_rate.y); - total_step_rate = unshaped_rate_e + x + y; + #else // !INPUT_SHAPING_E_SYNC - #endif // INPUT_SHAPING_E_SYNC + set_la_interval(la_step_rate + planned_step_rate); - set_la_interval(total_step_rate); + #endif curr_timer_tick += SMOOTH_LIN_ADV_INTERVAL; return SMOOTH_LIN_ADV_INTERVAL; From c20c6b61f1a9222f0550356eeadb7007e5c78f5a Mon Sep 17 00:00:00 2001 From: staff1010 <132726146+staff1010@users.noreply.github.com> Date: Wed, 28 May 2025 03:49:19 +0800 Subject: [PATCH 076/102] =?UTF-8?q?=F0=9F=9A=B8=20Improve=20MKS=20UI=20wit?= =?UTF-8?q?h=20LVGL=20v6.1.2=20(#27889)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/extui/mks_ui/draw_ui.cpp | 21 +- Marlin/src/lcd/extui/mks_ui/pic_manager.cpp | 133 +- Marlin/src/lcd/extui/mks_ui/pic_manager.h | 15 +- .../extui/mks_ui/tft_lvgl_configuration.cpp | 27 +- .../lcd/extui/mks_ui/tft_lvgl_configuration.h | 2 +- Marlin/src/lcd/extui/mks_ui/uthash.h | 1137 +++++++++++++++++ ini/features.ini | 2 +- 7 files changed, 1277 insertions(+), 60 deletions(-) create mode 100644 Marlin/src/lcd/extui/mks_ui/uthash.h diff --git a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp index 4278092472..875f2d8e72 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp @@ -579,7 +579,7 @@ char *creat_title_text() { update_spi_flash(); } card.closefile(); - #endif + #endif // HAS_MEDIA } void gcode_preview(char *path, int xpos_pixel, int ypos_pixel) { @@ -662,27 +662,27 @@ char *creat_title_text() { } void draw_default_preview(int xpos_pixel, int ypos_pixel, uint8_t sel) { - int index; + static constexpr uint16_t draw_col_count = 40; // Number of rows displayed each time, determines the size of bmp_public_buf + static constexpr int draw_count = 200 / draw_col_count; // Total number of times to be displayed + static constexpr uint32_t pixel_count = (DEFAULT_VIEW_MAX_SIZE) / draw_count; // Number of pixels read per time (uint8_t) int y_off = 0; - W25QXX.init(SPI_QUARTER_SPEED); - for (index = 0; index < 10; index++) { // 200*200 + for (int index = 0; index < draw_count; index++) { // 200*200 #if HAS_BAK_VIEW_IN_FLASH if (sel == 1) { - flash_view_Read(bmp_public_buf, 8000); // 20k + flash_view_Read(bmp_public_buf, pixel_count); // 16k } else { - default_view_Read(bmp_public_buf, DEFAULT_VIEW_MAX_SIZE / 10); // 8k + default_view_Read(bmp_public_buf, pixel_count); // 16k } #else - default_view_Read(bmp_public_buf, DEFAULT_VIEW_MAX_SIZE / 10); // 8k + default_view_Read(bmp_public_buf, pixel_count); // 8k #endif - SPI_TFT.setWindow(xpos_pixel, y_off * 20 + ypos_pixel, 200, 20); // 200*200 - SPI_TFT.tftio.writeSequence((uint16_t*)(bmp_public_buf), DEFAULT_VIEW_MAX_SIZE / 20); + SPI_TFT.setWindow(xpos_pixel, y_off * draw_col_count + ypos_pixel, 200, draw_col_count); // 200 * draw_col_count + SPI_TFT.tftio.writeSequence((uint16_t*)(bmp_public_buf), uint16_t(pixel_count / 2)); y_off++; } - W25QXX.init(SPI_QUARTER_SPEED); } void disp_pre_gcode(int xpos_pixel, int ypos_pixel) { @@ -700,6 +700,7 @@ char *creat_title_text() { } #endif } + #endif // HAS_GCODE_PREVIEW void print_time_run() { diff --git a/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp b/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp index 04ea827236..5db110ec1b 100644 --- a/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp +++ b/Marlin/src/lcd/extui/mks_ui/pic_manager.cpp @@ -35,6 +35,10 @@ #include +#if ENABLED(USE_HASH_TABLE) + #include "uthash.h" +#endif + extern uint16_t DeviceCode; #if HAS_MEDIA @@ -92,7 +96,7 @@ static FSTR_P const assets[] = { F("bmp_file.bin"), // Move motor screen - // TODO: 6 equal icons, just in diffenct rotation... it may be optimized too + // TODO: 6 equal icons, just in different rotation... it may be optimized too F("bmp_xAdd.bin"), F("bmp_xDec.bin"), F("bmp_yAdd.bin"), @@ -223,42 +227,98 @@ static FSTR_P const assets[] = { static FSTR_P const fonts[] = { F("FontUNIGBK.bin") }; #endif -uint8_t currentFlashPage = 0; +#if HAS_SPI_FLASH_COMPRESSION + uint8_t currentFlashPage = 0; +#endif -uint32_t lv_get_pic_addr(uint8_t *Pname) { - uint8_t Pic_cnt; - uint8_t i, j; - PIC_MSG PIC; - uint32_t tmp_cnt = 0; - uint32_t addr = 0; +#if ENABLED(USE_HASH_TABLE) - currentFlashPage = 0; + typedef struct { + char name[PIC_NAME_MAX_LEN - PIC_NAME_OFFSET]; /* key */ + uint32_t addr; + UT_hash_handle hh; /* makes this structure hashable */ + } PicHashEntry; - #if ENABLED(MARLIN_DEV_MODE) - SERIAL_ECHOLNPGM("Getting picture SPI Flash Address: ", (const char*)Pname); - #endif + PicHashEntry* pic_hash = NULL; - W25QXX.init(SPI_QUARTER_SPEED); + // Initialize the image address hash table + void init_img_map() { + uint8_t Pic_cnt; + W25QXX.SPI_FLASH_BufferRead(&Pic_cnt, PIC_COUNTER_ADDR, 1); + if (Pic_cnt == 0xFF) Pic_cnt = 0; - W25QXX.SPI_FLASH_BufferRead(&Pic_cnt, PIC_COUNTER_ADDR, 1); - if (Pic_cnt == 0xFF) Pic_cnt = 0; - for (i = 0; i < Pic_cnt; i++) { - j = 0; - do { - W25QXX.SPI_FLASH_BufferRead(&PIC.name[j], PIC_NAME_ADDR + tmp_cnt, 1); - tmp_cnt++; - } while (PIC.name[j++] != '\0'); + uint32_t tmp_cnt = 0; + for (uint8_t i = 0; i < Pic_cnt; i++) { + char name[PIC_NAME_MAX_LEN - PIC_NAME_OFFSET]; + uint8_t j = 0; + do { + W25QXX.SPI_FLASH_BufferRead((uint8_t*)&name[j], PIC_NAME_ADDR + tmp_cnt, 1); + tmp_cnt++; + } while (name[j++] != '\0'); - if ((strcasecmp((char*)Pname, (char*)PIC.name)) == 0) { + uint32_t addr; if (DeviceCode == 0x9488 || DeviceCode == 0x5761) addr = PIC_DATA_ADDR_TFT35 + i * PER_PIC_MAX_SPACE_TFT35; else addr = PIC_DATA_ADDR_TFT32 + i * PER_PIC_MAX_SPACE_TFT32; - return addr; + + // Add to hash table, don't save "bmp_" + PicHashEntry* entry = (PicHashEntry*)malloc(sizeof(*entry)); + strncpy(entry->name, (name + PIC_NAME_OFFSET), sizeof(name)); + entry->addr = addr; + HASH_ADD_STR(pic_hash, name, entry); } + #if ENABLED(MARLIN_DEV_MODE) + SERIAL_ECHOLNPGM("Image Hash Table Count: ", HASH_COUNT(pic_hash), ", Size(Bytes): ", HASH_OVERHEAD(hh, pic_hash)); + #endif } - return addr; -} + + uint32_t lv_get_pic_addr(uint8_t *Pname) { + #if ENABLED(MARLIN_DEV_MODE) + SERIAL_ECHOLNPGM("Getting picture SPI Flash Address: ", (const char*)Pname); + #endif + + PicHashEntry* entry; + HASH_FIND_STR(pic_hash, (char*)(Pname + PIC_NAME_OFFSET), entry); + return entry ? entry->addr : 0; + } + +#else // !USE_HASH_TABLE + + uint32_t lv_get_pic_addr(uint8_t *Pname) { + uint8_t Pic_cnt; + uint8_t i, j; + PIC_MSG PIC; + uint32_t tmp_cnt = 0; + uint32_t addr = 0; + + #if ENABLED(MARLIN_DEV_MODE) + SERIAL_ECHOLNPGM("Getting picture SPI Flash Address: ", (const char*)Pname); + #endif + + W25QXX.init(SPI_QUARTER_SPEED); + + W25QXX.SPI_FLASH_BufferRead(&Pic_cnt, PIC_COUNTER_ADDR, 1); + if (Pic_cnt == 0xFF) Pic_cnt = 0; + for (i = 0; i < Pic_cnt; i++) { + j = 0; + do { + W25QXX.SPI_FLASH_BufferRead(&PIC.name[j], PIC_NAME_ADDR + tmp_cnt, 1); + tmp_cnt++; + } while (PIC.name[j++] != '\0'); + + if ((strcasecmp((char*)Pname, (char*)PIC.name)) == 0) { + if (DeviceCode == 0x9488 || DeviceCode == 0x5761) + addr = PIC_DATA_ADDR_TFT35 + i * PER_PIC_MAX_SPACE_TFT35; + else + addr = PIC_DATA_ADDR_TFT32 + i * PER_PIC_MAX_SPACE_TFT32; + break; + } + } + return addr; + } + +#endif // !USE_HASH_TABLE const char *assetsPath = "assets"; const char *bakPath = "_assets"; @@ -309,8 +369,8 @@ uint8_t picLogoWrite(uint8_t *LogoName, uint8_t *Logo_Wbuff, uint32_t LogoWriteS uint32_t TitleLogoWrite_Addroffset = 0; uint8_t picTitleLogoWrite(uint8_t *TitleLogoName, uint8_t *TitleLogo_Wbuff, uint32_t TitleLogoWriteSize) { - if (TitleLogoWriteSize <= 0) - return 0; + if (TitleLogoWriteSize <= 0) return 0; + if ((DeviceCode == 0x9488) || (DeviceCode == 0x5761)) W25QXX.SPI_FLASH_BufferWrite(TitleLogo_Wbuff, PIC_ICON_LOGO_ADDR_TFT35 + TitleLogoWrite_Addroffset, TitleLogoWriteSize); else @@ -341,9 +401,7 @@ uint32_t picInfoWrite(uint8_t *P_name, uint32_t P_size) { union union32 size_tmp; W25QXX.SPI_FLASH_BufferRead(&pic_counter, PIC_COUNTER_ADDR, 1); - - if (pic_counter == 0xFF) - pic_counter = 0; + if (pic_counter == 0xFF) pic_counter = 0; if ((DeviceCode == 0x9488) || (DeviceCode == 0x5761)) picSaveAddr = PIC_DATA_ADDR_TFT35 + pic_counter * PER_PIC_MAX_SPACE_TFT35; @@ -416,6 +474,7 @@ uint32_t picInfoWrite(uint8_t *P_name, uint32_t P_size) { } hal.watchdog_refresh(); + disp_string(100, 165, FTOP(F(" ")), 0xFFFF, 0x0000); // clean string disp_assets_update_progress(fn); W25QXX.init(SPI_QUARTER_SPEED); @@ -449,16 +508,18 @@ uint32_t picInfoWrite(uint8_t *P_name, uint32_t P_size) { } else if (assetType == ASSET_TYPE_ICON) { Pic_Write_Addr = picInfoWrite((uint8_t*)fn, pfileSize); - SPIFlash.beginWrite(Pic_Write_Addr); #if HAS_SPI_FLASH_COMPRESSION + SPIFlash.beginWrite(Pic_Write_Addr); do { hal.watchdog_refresh(); pbr = file.read(public_buf, SPI_FLASH_PageSize); TERN_(MARLIN_DEV_MODE, totalSizes += pbr); SPIFlash.writeData(public_buf, SPI_FLASH_PageSize); } while (pbr >= SPI_FLASH_PageSize); + SPIFlash.endWrite(); #else do { + hal.watchdog_refresh(); pbr = file.read(public_buf, BMP_WRITE_BUF_LEN); W25QXX.SPI_FLASH_BufferWrite(public_buf, Pic_Write_Addr, pbr); Pic_Write_Addr += pbr; @@ -468,7 +529,6 @@ uint32_t picInfoWrite(uint8_t *P_name, uint32_t P_size) { SERIAL_ECHOLNPGM("Space used: ", fn, " - ", (SPIFlash.getCurrentPage() + 1) * SPI_FLASH_PageSize / 1024, "KB"); totalCompressed += (SPIFlash.getCurrentPage() + 1) * SPI_FLASH_PageSize; #endif - SPIFlash.endWrite(); } else if (assetType == ASSET_TYPE_FONT) { Pic_Write_Addr = UNIGBK_FLASH_ADDR; @@ -557,8 +617,7 @@ void picRead(uint8_t *Pname, uint8_t *P_Rbuff) { PIC_MSG PIC; W25QXX.SPI_FLASH_BufferRead(&Pic_cnt, PIC_COUNTER_ADDR, 1); - if (Pic_cnt == 0xFF) - Pic_cnt = 0; + if (Pic_cnt == 0xFF) Pic_cnt = 0; for (i = 0; i < Pic_cnt; i++) { j = 0; @@ -578,12 +637,12 @@ void picRead(uint8_t *Pname, uint8_t *P_Rbuff) { void lv_pic_test(uint8_t *P_Rbuff, uint32_t addr, uint32_t size) { #if HAS_SPI_FLASH_COMPRESSION - if (currentFlashPage == 0) + if (currentFlashPage == 0) { + currentFlashPage = 1; SPIFlash.beginRead(addr); + } SPIFlash.readData(P_Rbuff, size); - currentFlashPage++; #else - W25QXX.init(SPI_QUARTER_SPEED); W25QXX.SPI_FLASH_BufferRead((uint8_t *)P_Rbuff, addr, size); #endif } diff --git a/Marlin/src/lcd/extui/mks_ui/pic_manager.h b/Marlin/src/lcd/extui/mks_ui/pic_manager.h index 1483b96461..30003a16d6 100644 --- a/Marlin/src/lcd/extui/mks_ui/pic_manager.h +++ b/Marlin/src/lcd/extui/mks_ui/pic_manager.h @@ -29,6 +29,9 @@ #include #include +#include "SPIFlashStorage.h" + +#define USE_HASH_TABLE #ifndef HAS_SPI_FLASH_FONT #define HAS_SPI_FLASH_FONT 1 // Disabled until fix the font load code @@ -53,7 +56,8 @@ #endif #define PIC_MAX_CN 100 // Maximum number of pictures -#define PIC_NAME_MAX_LEN 50 // Picture name maximum length +#define PIC_NAME_MAX_LEN 30 // Picture name maximum length +#define PIC_NAME_OFFSET 4 // Same picture filename section #define LOGO_MAX_SIZE_TFT35 (300 * 1024) #define LOGO_MAX_SIZE_TFT32 (150 * 1024) @@ -61,7 +65,11 @@ #define DEFAULT_VIEW_MAX_SIZE (200 * 200 * 2) #define FLASH_VIEW_MAX_SIZE (200 * 200 * 2) -#define PER_PIC_MAX_SPACE_TFT35 (9 * 1024) +#if HAS_SPI_FLASH_COMPRESSION + #define PER_PIC_MAX_SPACE_TFT35 ( 9 * 1024) +#else + #define PER_PIC_MAX_SPACE_TFT35 (32 * 1024) +#endif #define PER_PIC_MAX_SPACE_TFT32 (16 * 1024) #define PER_FONT_MAX_SPACE (16 * 1024) @@ -154,6 +162,9 @@ typedef struct pic_msg PIC_MSG; #define PIC_SIZE_xM 6 #define FONT_SIZE_xM 2 +#if ENABLED(USE_HASH_TABLE) + void init_img_map(); +#endif void picRead(uint8_t *Pname, uint8_t *P_Rbuff); void picLogoRead(uint8_t *LogoName, uint8_t *Logo_Rbuff, uint32_t LogoReadsize); void lv_pic_test(uint8_t *P_Rbuff, uint32_t addr, uint32_t size); diff --git a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp index 903afad884..0ea29dda0c 100644 --- a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp +++ b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp @@ -85,7 +85,7 @@ lv_group_t* g; uint16_t DeviceCode = 0x9488; extern uint8_t sel_id; -uint8_t bmp_public_buf[14 * 1024]; +uint8_t bmp_public_buf[16 * 1024]; uint8_t public_buf[513]; extern bool flash_preview_begin, default_preview_flg, gcode_preview_over; @@ -149,9 +149,14 @@ void tft_lvgl_init() { touch.init(); + #if ENABLED(USE_HASH_TABLE) + init_img_map(); // Initialize the image address hash table + hal.watchdog_refresh(); // Hash table init takes time + #endif + lv_init(); - lv_disp_buf_init(&disp_buf, bmp_public_buf, nullptr, LV_HOR_RES_MAX * 14); // Initialize the display buffer + lv_disp_buf_init(&disp_buf, bmp_public_buf, nullptr, LV_HOR_RES_MAX * 17); // Initialize the display buffer lv_disp_drv_t disp_drv; // Descriptor of a display driver lv_disp_drv_init(&disp_drv); // Basic initialization @@ -268,8 +273,6 @@ void my_disp_flush(lv_disp_drv_t * disp, const lv_area_t * area, lv_color_t * co SPI_TFT.tftio.writeSequence((uint16_t*)color_p, width * height); lv_disp_flush_ready(disp_drv_p); // Indicate you are ready with the flushing #endif - - W25QXX.init(SPI_QUARTER_SPEED); } #if ENABLED(USE_SPI_DMA_TC) @@ -327,20 +330,26 @@ bool my_mousewheel_read(lv_indev_drv_t * indev_drv, lv_indev_data_t * data) { return false; // No more data to read so return false } -extern uint8_t currentFlashPage; +#if HAS_SPI_FLASH_COMPRESSION + extern uint8_t currentFlashPage; +#endif // spi_flash uint32_t pic_read_base_addr = 0, pic_read_addr_offset = 0; lv_fs_res_t spi_flash_open_cb (lv_fs_drv_t * drv, void * file_p, const char * path, lv_fs_mode_t mode) { static char last_path_name[30]; + #if HAS_SPI_FLASH_COMPRESSION + currentFlashPage = 0; + #endif if (strcasecmp(last_path_name, path) != 0) { pic_read_base_addr = lv_get_pic_addr((uint8_t *)path); + // clean lvgl image cache + char cache_path_name[30 + 3] = {0}; + strcat(cache_path_name, "F:/"); + strcat(cache_path_name, (const char *)last_path_name); + lv_img_cache_invalidate_src(cache_path_name); strcpy(last_path_name, path); } - else { - W25QXX.init(SPI_QUARTER_SPEED); - currentFlashPage = 0; - } pic_read_addr_offset = pic_read_base_addr; return LV_FS_RES_OK; } diff --git a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.h b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.h index 43e82bd34d..606fdb50e0 100644 --- a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.h +++ b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.h @@ -32,7 +32,7 @@ #include -extern uint8_t bmp_public_buf[14 * 1024]; +extern uint8_t bmp_public_buf[16 * 1024]; extern uint8_t public_buf[513]; void tft_lvgl_init(); diff --git a/Marlin/src/lcd/extui/mks_ui/uthash.h b/Marlin/src/lcd/extui/mks_ui/uthash.h new file mode 100644 index 0000000000..06c2eebdb8 --- /dev/null +++ b/Marlin/src/lcd/extui/mks_ui/uthash.h @@ -0,0 +1,1137 @@ +/* +Copyright (c) 2003-2025, Troy D. Hanson https://troydhanson.github.io/uthash/ +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS +IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A +PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER +OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, +EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, +PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR +PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF +LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING +NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ + +#ifndef UTHASH_H +#define UTHASH_H + +#define UTHASH_VERSION 2.3.0 + +#include /* memcmp, memset, strlen */ +#include /* ptrdiff_t */ +#include /* exit */ + +#if defined(HASH_NO_STDINT) && HASH_NO_STDINT +/* The user doesn't have , and must figure out their own way + to provide definitions for uint8_t and uint32_t. */ +#else +#include /* uint8_t, uint32_t */ +#endif + +/* These macros use decltype or the earlier __typeof GNU extension. + As decltype is only available in newer compilers (VS2010 or gcc 4.3+ + when compiling c++ source) this code uses whatever method is needed + or, for VS2008 where neither is available, uses casting workarounds. */ +#if !defined(DECLTYPE) && !defined(NO_DECLTYPE) +#if defined(_MSC_VER) /* MS compiler */ +#if _MSC_VER >= 1600 && defined(__cplusplus) /* VS2010 or newer in C++ mode */ +#define DECLTYPE(x) (decltype(x)) +#else /* VS2008 or older (or VS2010 in C mode) */ +#define NO_DECLTYPE +#endif +#elif defined(__MCST__) /* Elbrus C Compiler */ +#define DECLTYPE(x) (__typeof(x)) +#elif defined(__BORLANDC__) || defined(__ICCARM__) || defined(__LCC__) || defined(__WATCOMC__) +#define NO_DECLTYPE +#else /* GNU, Sun and other compilers */ +#define DECLTYPE(x) (__typeof(x)) +#endif +#endif + +#ifdef NO_DECLTYPE +#define DECLTYPE(x) +#define DECLTYPE_ASSIGN(dst,src) \ +do { \ + char **_da_dst = (char**)(&(dst)); \ + *_da_dst = (char*)(src); \ +} while (0) +#else +#define DECLTYPE_ASSIGN(dst,src) \ +do { \ + (dst) = DECLTYPE(dst)(src); \ +} while (0) +#endif + +#ifndef uthash_malloc +#define uthash_malloc(sz) malloc(sz) /* malloc fcn */ +#endif +#ifndef uthash_free +#define uthash_free(ptr,sz) free(ptr) /* free fcn */ +#endif +#ifndef uthash_bzero +#define uthash_bzero(a,n) memset(a,'\0',n) +#endif +#ifndef uthash_strlen +#define uthash_strlen(s) strlen(s) +#endif + +#ifndef HASH_FUNCTION +#define HASH_FUNCTION(keyptr,keylen,hashv) HASH_JEN(keyptr, keylen, hashv) +#endif + +#ifndef HASH_KEYCMP +#define HASH_KEYCMP(a,b,n) memcmp(a,b,n) +#endif + +#ifndef uthash_noexpand_fyi +#define uthash_noexpand_fyi(tbl) /* can be defined to log noexpand */ +#endif +#ifndef uthash_expand_fyi +#define uthash_expand_fyi(tbl) /* can be defined to log expands */ +#endif + +#ifndef HASH_NONFATAL_OOM +#define HASH_NONFATAL_OOM 0 +#endif + +#if HASH_NONFATAL_OOM +/* malloc failures can be recovered from */ + +#ifndef uthash_nonfatal_oom +#define uthash_nonfatal_oom(obj) do {} while (0) /* non-fatal OOM error */ +#endif + +#define HASH_RECORD_OOM(oomed) do { (oomed) = 1; } while (0) +#define IF_HASH_NONFATAL_OOM(x) x + +#else +/* malloc failures result in lost memory, hash tables are unusable */ + +#ifndef uthash_fatal +#define uthash_fatal(msg) exit(-1) /* fatal OOM error */ +#endif + +#define HASH_RECORD_OOM(oomed) uthash_fatal("out of memory") +#define IF_HASH_NONFATAL_OOM(x) + +#endif + +/* initial number of buckets */ +#define HASH_INITIAL_NUM_BUCKETS 32U /* initial number of buckets */ +#define HASH_INITIAL_NUM_BUCKETS_LOG2 5U /* lg2 of initial number of buckets */ +#define HASH_BKT_CAPACITY_THRESH 10U /* expand when bucket count reaches */ + +/* calculate the element whose hash handle address is hhp */ +#define ELMT_FROM_HH(tbl,hhp) ((void*)(((char*)(hhp)) - ((tbl)->hho))) +/* calculate the hash handle from element address elp */ +#define HH_FROM_ELMT(tbl,elp) ((UT_hash_handle*)(void*)(((char*)(elp)) + ((tbl)->hho))) + +#define HASH_ROLLBACK_BKT(hh, head, itemptrhh) \ +do { \ + struct UT_hash_handle *_hd_hh_item = (itemptrhh); \ + unsigned _hd_bkt; \ + HASH_TO_BKT(_hd_hh_item->hashv, (head)->hh.tbl->num_buckets, _hd_bkt); \ + (head)->hh.tbl->buckets[_hd_bkt].count++; \ + _hd_hh_item->hh_next = NULL; \ + _hd_hh_item->hh_prev = NULL; \ +} while (0) + +#define HASH_VALUE(keyptr,keylen,hashv) \ +do { \ + HASH_FUNCTION(keyptr, keylen, hashv); \ +} while (0) + +#define HASH_FIND_BYHASHVALUE(hh,head,keyptr,keylen,hashval,out) \ +do { \ + (out) = NULL; \ + if (head) { \ + unsigned _hf_bkt; \ + HASH_TO_BKT(hashval, (head)->hh.tbl->num_buckets, _hf_bkt); \ + if (HASH_BLOOM_TEST((head)->hh.tbl, hashval)) { \ + HASH_FIND_IN_BKT((head)->hh.tbl, hh, (head)->hh.tbl->buckets[ _hf_bkt ], keyptr, keylen, hashval, out); \ + } \ + } \ +} while (0) + +#define HASH_FIND(hh,head,keyptr,keylen,out) \ +do { \ + (out) = NULL; \ + if (head) { \ + unsigned _hf_hashv; \ + HASH_VALUE(keyptr, keylen, _hf_hashv); \ + HASH_FIND_BYHASHVALUE(hh, head, keyptr, keylen, _hf_hashv, out); \ + } \ +} while (0) + +#ifdef HASH_BLOOM +#define HASH_BLOOM_BITLEN (1UL << HASH_BLOOM) +#define HASH_BLOOM_BYTELEN (HASH_BLOOM_BITLEN/8UL) + (((HASH_BLOOM_BITLEN%8UL)!=0UL) ? 1UL : 0UL) +#define HASH_BLOOM_MAKE(tbl,oomed) \ +do { \ + (tbl)->bloom_nbits = HASH_BLOOM; \ + (tbl)->bloom_bv = (uint8_t*)uthash_malloc(HASH_BLOOM_BYTELEN); \ + if (!(tbl)->bloom_bv) { \ + HASH_RECORD_OOM(oomed); \ + } else { \ + uthash_bzero((tbl)->bloom_bv, HASH_BLOOM_BYTELEN); \ + (tbl)->bloom_sig = HASH_BLOOM_SIGNATURE; \ + } \ +} while (0) + +#define HASH_BLOOM_FREE(tbl) \ +do { \ + uthash_free((tbl)->bloom_bv, HASH_BLOOM_BYTELEN); \ +} while (0) + +#define HASH_BLOOM_BITSET(bv,idx) (bv[(idx)/8U] |= (1U << ((idx)%8U))) +#define HASH_BLOOM_BITTEST(bv,idx) ((bv[(idx)/8U] & (1U << ((idx)%8U))) != 0) + +#define HASH_BLOOM_ADD(tbl,hashv) \ + HASH_BLOOM_BITSET((tbl)->bloom_bv, ((hashv) & (uint32_t)((1UL << (tbl)->bloom_nbits) - 1U))) + +#define HASH_BLOOM_TEST(tbl,hashv) \ + HASH_BLOOM_BITTEST((tbl)->bloom_bv, ((hashv) & (uint32_t)((1UL << (tbl)->bloom_nbits) - 1U))) + +#else +#define HASH_BLOOM_MAKE(tbl,oomed) +#define HASH_BLOOM_FREE(tbl) +#define HASH_BLOOM_ADD(tbl,hashv) +#define HASH_BLOOM_TEST(tbl,hashv) 1 +#define HASH_BLOOM_BYTELEN 0U +#endif + +#define HASH_MAKE_TABLE(hh,head,oomed) \ +do { \ + (head)->hh.tbl = (UT_hash_table*)uthash_malloc(sizeof(UT_hash_table)); \ + if (!(head)->hh.tbl) { \ + HASH_RECORD_OOM(oomed); \ + } else { \ + uthash_bzero((head)->hh.tbl, sizeof(UT_hash_table)); \ + (head)->hh.tbl->tail = &((head)->hh); \ + (head)->hh.tbl->num_buckets = HASH_INITIAL_NUM_BUCKETS; \ + (head)->hh.tbl->log2_num_buckets = HASH_INITIAL_NUM_BUCKETS_LOG2; \ + (head)->hh.tbl->hho = (char*)(&(head)->hh) - (char*)(head); \ + (head)->hh.tbl->buckets = (UT_hash_bucket*)uthash_malloc( \ + HASH_INITIAL_NUM_BUCKETS * sizeof(struct UT_hash_bucket)); \ + (head)->hh.tbl->signature = HASH_SIGNATURE; \ + if (!(head)->hh.tbl->buckets) { \ + HASH_RECORD_OOM(oomed); \ + uthash_free((head)->hh.tbl, sizeof(UT_hash_table)); \ + } else { \ + uthash_bzero((head)->hh.tbl->buckets, \ + HASH_INITIAL_NUM_BUCKETS * sizeof(struct UT_hash_bucket)); \ + HASH_BLOOM_MAKE((head)->hh.tbl, oomed); \ + IF_HASH_NONFATAL_OOM( \ + if (oomed) { \ + uthash_free((head)->hh.tbl->buckets, \ + HASH_INITIAL_NUM_BUCKETS*sizeof(struct UT_hash_bucket)); \ + uthash_free((head)->hh.tbl, sizeof(UT_hash_table)); \ + } \ + ) \ + } \ + } \ +} while (0) + +#define HASH_REPLACE_BYHASHVALUE_INORDER(hh,head,fieldname,keylen_in,hashval,add,replaced,cmpfcn) \ +do { \ + (replaced) = NULL; \ + HASH_FIND_BYHASHVALUE(hh, head, &((add)->fieldname), keylen_in, hashval, replaced); \ + if (replaced) { \ + HASH_DELETE(hh, head, replaced); \ + } \ + HASH_ADD_KEYPTR_BYHASHVALUE_INORDER(hh, head, &((add)->fieldname), keylen_in, hashval, add, cmpfcn); \ +} while (0) + +#define HASH_REPLACE_BYHASHVALUE(hh,head,fieldname,keylen_in,hashval,add,replaced) \ +do { \ + (replaced) = NULL; \ + HASH_FIND_BYHASHVALUE(hh, head, &((add)->fieldname), keylen_in, hashval, replaced); \ + if (replaced) { \ + HASH_DELETE(hh, head, replaced); \ + } \ + HASH_ADD_KEYPTR_BYHASHVALUE(hh, head, &((add)->fieldname), keylen_in, hashval, add); \ +} while (0) + +#define HASH_REPLACE(hh,head,fieldname,keylen_in,add,replaced) \ +do { \ + unsigned _hr_hashv; \ + HASH_VALUE(&((add)->fieldname), keylen_in, _hr_hashv); \ + HASH_REPLACE_BYHASHVALUE(hh, head, fieldname, keylen_in, _hr_hashv, add, replaced); \ +} while (0) + +#define HASH_REPLACE_INORDER(hh,head,fieldname,keylen_in,add,replaced,cmpfcn) \ +do { \ + unsigned _hr_hashv; \ + HASH_VALUE(&((add)->fieldname), keylen_in, _hr_hashv); \ + HASH_REPLACE_BYHASHVALUE_INORDER(hh, head, fieldname, keylen_in, _hr_hashv, add, replaced, cmpfcn); \ +} while (0) + +#define HASH_APPEND_LIST(hh, head, add) \ +do { \ + (add)->hh.next = NULL; \ + (add)->hh.prev = ELMT_FROM_HH((head)->hh.tbl, (head)->hh.tbl->tail); \ + (head)->hh.tbl->tail->next = (add); \ + (head)->hh.tbl->tail = &((add)->hh); \ +} while (0) + +#define HASH_AKBI_INNER_LOOP(hh,head,add,cmpfcn) \ +do { \ + do { \ + if (cmpfcn(DECLTYPE(head)(_hs_iter), add) > 0) { \ + break; \ + } \ + } while ((_hs_iter = HH_FROM_ELMT((head)->hh.tbl, _hs_iter)->next)); \ +} while (0) + +#ifdef NO_DECLTYPE +#undef HASH_AKBI_INNER_LOOP +#define HASH_AKBI_INNER_LOOP(hh,head,add,cmpfcn) \ +do { \ + char *_hs_saved_head = (char*)(head); \ + do { \ + DECLTYPE_ASSIGN(head, _hs_iter); \ + if (cmpfcn(head, add) > 0) { \ + DECLTYPE_ASSIGN(head, _hs_saved_head); \ + break; \ + } \ + DECLTYPE_ASSIGN(head, _hs_saved_head); \ + } while ((_hs_iter = HH_FROM_ELMT((head)->hh.tbl, _hs_iter)->next)); \ +} while (0) +#endif + +#if HASH_NONFATAL_OOM + +#define HASH_ADD_TO_TABLE(hh,head,keyptr,keylen_in,hashval,add,oomed) \ +do { \ + if (!(oomed)) { \ + unsigned _ha_bkt; \ + (head)->hh.tbl->num_items++; \ + HASH_TO_BKT(hashval, (head)->hh.tbl->num_buckets, _ha_bkt); \ + HASH_ADD_TO_BKT((head)->hh.tbl->buckets[_ha_bkt], hh, &(add)->hh, oomed); \ + if (oomed) { \ + HASH_ROLLBACK_BKT(hh, head, &(add)->hh); \ + HASH_DELETE_HH(hh, head, &(add)->hh); \ + (add)->hh.tbl = NULL; \ + uthash_nonfatal_oom(add); \ + } else { \ + HASH_BLOOM_ADD((head)->hh.tbl, hashval); \ + HASH_EMIT_KEY(hh, head, keyptr, keylen_in); \ + } \ + } else { \ + (add)->hh.tbl = NULL; \ + uthash_nonfatal_oom(add); \ + } \ +} while (0) + +#else + +#define HASH_ADD_TO_TABLE(hh,head,keyptr,keylen_in,hashval,add,oomed) \ +do { \ + unsigned _ha_bkt; \ + (head)->hh.tbl->num_items++; \ + HASH_TO_BKT(hashval, (head)->hh.tbl->num_buckets, _ha_bkt); \ + HASH_ADD_TO_BKT((head)->hh.tbl->buckets[_ha_bkt], hh, &(add)->hh, oomed); \ + HASH_BLOOM_ADD((head)->hh.tbl, hashval); \ + HASH_EMIT_KEY(hh, head, keyptr, keylen_in); \ +} while (0) + +#endif + + +#define HASH_ADD_KEYPTR_BYHASHVALUE_INORDER(hh,head,keyptr,keylen_in,hashval,add,cmpfcn) \ +do { \ + IF_HASH_NONFATAL_OOM( int _ha_oomed = 0; ) \ + (add)->hh.hashv = (hashval); \ + (add)->hh.key = (char*) (keyptr); \ + (add)->hh.keylen = (unsigned) (keylen_in); \ + if (!(head)) { \ + (add)->hh.next = NULL; \ + (add)->hh.prev = NULL; \ + HASH_MAKE_TABLE(hh, add, _ha_oomed); \ + IF_HASH_NONFATAL_OOM( if (!_ha_oomed) { ) \ + (head) = (add); \ + IF_HASH_NONFATAL_OOM( } ) \ + } else { \ + void *_hs_iter = (head); \ + (add)->hh.tbl = (head)->hh.tbl; \ + HASH_AKBI_INNER_LOOP(hh, head, add, cmpfcn); \ + if (_hs_iter) { \ + (add)->hh.next = _hs_iter; \ + if (((add)->hh.prev = HH_FROM_ELMT((head)->hh.tbl, _hs_iter)->prev)) { \ + HH_FROM_ELMT((head)->hh.tbl, (add)->hh.prev)->next = (add); \ + } else { \ + (head) = (add); \ + } \ + HH_FROM_ELMT((head)->hh.tbl, _hs_iter)->prev = (add); \ + } else { \ + HASH_APPEND_LIST(hh, head, add); \ + } \ + } \ + HASH_ADD_TO_TABLE(hh, head, keyptr, keylen_in, hashval, add, _ha_oomed); \ + HASH_FSCK(hh, head, "HASH_ADD_KEYPTR_BYHASHVALUE_INORDER"); \ +} while (0) + +#define HASH_ADD_KEYPTR_INORDER(hh,head,keyptr,keylen_in,add,cmpfcn) \ +do { \ + unsigned _hs_hashv; \ + HASH_VALUE(keyptr, keylen_in, _hs_hashv); \ + HASH_ADD_KEYPTR_BYHASHVALUE_INORDER(hh, head, keyptr, keylen_in, _hs_hashv, add, cmpfcn); \ +} while (0) + +#define HASH_ADD_BYHASHVALUE_INORDER(hh,head,fieldname,keylen_in,hashval,add,cmpfcn) \ + HASH_ADD_KEYPTR_BYHASHVALUE_INORDER(hh, head, &((add)->fieldname), keylen_in, hashval, add, cmpfcn) + +#define HASH_ADD_INORDER(hh,head,fieldname,keylen_in,add,cmpfcn) \ + HASH_ADD_KEYPTR_INORDER(hh, head, &((add)->fieldname), keylen_in, add, cmpfcn) + +#define HASH_ADD_KEYPTR_BYHASHVALUE(hh,head,keyptr,keylen_in,hashval,add) \ +do { \ + IF_HASH_NONFATAL_OOM( int _ha_oomed = 0; ) \ + (add)->hh.hashv = (hashval); \ + (add)->hh.key = (const void*) (keyptr); \ + (add)->hh.keylen = (unsigned) (keylen_in); \ + if (!(head)) { \ + (add)->hh.next = NULL; \ + (add)->hh.prev = NULL; \ + HASH_MAKE_TABLE(hh, add, _ha_oomed); \ + IF_HASH_NONFATAL_OOM( if (!_ha_oomed) { ) \ + (head) = (add); \ + IF_HASH_NONFATAL_OOM( } ) \ + } else { \ + (add)->hh.tbl = (head)->hh.tbl; \ + HASH_APPEND_LIST(hh, head, add); \ + } \ + HASH_ADD_TO_TABLE(hh, head, keyptr, keylen_in, hashval, add, _ha_oomed); \ + HASH_FSCK(hh, head, "HASH_ADD_KEYPTR_BYHASHVALUE"); \ +} while (0) + +#define HASH_ADD_KEYPTR(hh,head,keyptr,keylen_in,add) \ +do { \ + unsigned _ha_hashv; \ + HASH_VALUE(keyptr, keylen_in, _ha_hashv); \ + HASH_ADD_KEYPTR_BYHASHVALUE(hh, head, keyptr, keylen_in, _ha_hashv, add); \ +} while (0) + +#define HASH_ADD_BYHASHVALUE(hh,head,fieldname,keylen_in,hashval,add) \ + HASH_ADD_KEYPTR_BYHASHVALUE(hh, head, &((add)->fieldname), keylen_in, hashval, add) + +#define HASH_ADD(hh,head,fieldname,keylen_in,add) \ + HASH_ADD_KEYPTR(hh, head, &((add)->fieldname), keylen_in, add) + +#define HASH_TO_BKT(hashv,num_bkts,bkt) \ +do { \ + bkt = ((hashv) & ((num_bkts) - 1U)); \ +} while (0) + +/* delete "delptr" from the hash table. + * "the usual" patch-up process for the app-order doubly-linked-list. + * The use of _hd_hh_del below deserves special explanation. + * These used to be expressed using (delptr) but that led to a bug + * if someone used the same symbol for the head and deletee, like + * HASH_DELETE(hh,users,users); + * We want that to work, but by changing the head (users) below + * we were forfeiting our ability to further refer to the deletee (users) + * in the patch-up process. Solution: use scratch space to + * copy the deletee pointer, then the latter references are via that + * scratch pointer rather than through the repointed (users) symbol. + */ +#define HASH_DELETE(hh,head,delptr) \ + HASH_DELETE_HH(hh, head, &(delptr)->hh) + +#define HASH_DELETE_HH(hh,head,delptrhh) \ +do { \ + const struct UT_hash_handle *_hd_hh_del = (delptrhh); \ + if ((_hd_hh_del->prev == NULL) && (_hd_hh_del->next == NULL)) { \ + HASH_BLOOM_FREE((head)->hh.tbl); \ + uthash_free((head)->hh.tbl->buckets, \ + (head)->hh.tbl->num_buckets * sizeof(struct UT_hash_bucket)); \ + uthash_free((head)->hh.tbl, sizeof(UT_hash_table)); \ + (head) = NULL; \ + } else { \ + unsigned _hd_bkt; \ + if (_hd_hh_del == (head)->hh.tbl->tail) { \ + (head)->hh.tbl->tail = HH_FROM_ELMT((head)->hh.tbl, _hd_hh_del->prev); \ + } \ + if (_hd_hh_del->prev != NULL) { \ + HH_FROM_ELMT((head)->hh.tbl, _hd_hh_del->prev)->next = _hd_hh_del->next; \ + } else { \ + DECLTYPE_ASSIGN(head, _hd_hh_del->next); \ + } \ + if (_hd_hh_del->next != NULL) { \ + HH_FROM_ELMT((head)->hh.tbl, _hd_hh_del->next)->prev = _hd_hh_del->prev; \ + } \ + HASH_TO_BKT(_hd_hh_del->hashv, (head)->hh.tbl->num_buckets, _hd_bkt); \ + HASH_DEL_IN_BKT((head)->hh.tbl->buckets[_hd_bkt], _hd_hh_del); \ + (head)->hh.tbl->num_items--; \ + } \ + HASH_FSCK(hh, head, "HASH_DELETE_HH"); \ +} while (0) + +/* convenience forms of HASH_FIND/HASH_ADD/HASH_DEL */ +#define HASH_FIND_STR(head,findstr,out) \ +do { \ + unsigned _uthash_hfstr_keylen = (unsigned)uthash_strlen(findstr); \ + HASH_FIND(hh, head, findstr, _uthash_hfstr_keylen, out); \ +} while (0) +#define HASH_ADD_STR(head,strfield,add) \ +do { \ + unsigned _uthash_hastr_keylen = (unsigned)uthash_strlen((add)->strfield); \ + HASH_ADD(hh, head, strfield[0], _uthash_hastr_keylen, add); \ +} while (0) +#define HASH_REPLACE_STR(head,strfield,add,replaced) \ +do { \ + unsigned _uthash_hrstr_keylen = (unsigned)uthash_strlen((add)->strfield); \ + HASH_REPLACE(hh, head, strfield[0], _uthash_hrstr_keylen, add, replaced); \ +} while (0) +#define HASH_FIND_INT(head,findint,out) \ + HASH_FIND(hh,head,findint,sizeof(int),out) +#define HASH_ADD_INT(head,intfield,add) \ + HASH_ADD(hh,head,intfield,sizeof(int),add) +#define HASH_REPLACE_INT(head,intfield,add,replaced) \ + HASH_REPLACE(hh,head,intfield,sizeof(int),add,replaced) +#define HASH_FIND_PTR(head,findptr,out) \ + HASH_FIND(hh,head,findptr,sizeof(void *),out) +#define HASH_ADD_PTR(head,ptrfield,add) \ + HASH_ADD(hh,head,ptrfield,sizeof(void *),add) +#define HASH_REPLACE_PTR(head,ptrfield,add,replaced) \ + HASH_REPLACE(hh,head,ptrfield,sizeof(void *),add,replaced) +#define HASH_DEL(head,delptr) \ + HASH_DELETE(hh,head,delptr) + +/* HASH_FSCK checks hash integrity on every add/delete when HASH_DEBUG is defined. + * This is for uthash developer only; it compiles away if HASH_DEBUG isn't defined. + */ +#ifdef HASH_DEBUG +#include /* fprintf, stderr */ +#define HASH_OOPS(...) do { fprintf(stderr, __VA_ARGS__); exit(-1); } while (0) +#define HASH_FSCK(hh,head,where) \ +do { \ + struct UT_hash_handle *_thh; \ + if (head) { \ + unsigned _bkt_i; \ + unsigned _count = 0; \ + char *_prev; \ + for (_bkt_i = 0; _bkt_i < (head)->hh.tbl->num_buckets; ++_bkt_i) { \ + unsigned _bkt_count = 0; \ + _thh = (head)->hh.tbl->buckets[_bkt_i].hh_head; \ + _prev = NULL; \ + while (_thh) { \ + if (_prev != (char*)(_thh->hh_prev)) { \ + HASH_OOPS("%s: invalid hh_prev %p, actual %p\n", \ + (where), (void*)_thh->hh_prev, (void*)_prev); \ + } \ + _bkt_count++; \ + _prev = (char*)(_thh); \ + _thh = _thh->hh_next; \ + } \ + _count += _bkt_count; \ + if ((head)->hh.tbl->buckets[_bkt_i].count != _bkt_count) { \ + HASH_OOPS("%s: invalid bucket count %u, actual %u\n", \ + (where), (head)->hh.tbl->buckets[_bkt_i].count, _bkt_count); \ + } \ + } \ + if (_count != (head)->hh.tbl->num_items) { \ + HASH_OOPS("%s: invalid hh item count %u, actual %u\n", \ + (where), (head)->hh.tbl->num_items, _count); \ + } \ + _count = 0; \ + _prev = NULL; \ + _thh = &(head)->hh; \ + while (_thh) { \ + _count++; \ + if (_prev != (char*)_thh->prev) { \ + HASH_OOPS("%s: invalid prev %p, actual %p\n", \ + (where), (void*)_thh->prev, (void*)_prev); \ + } \ + _prev = (char*)ELMT_FROM_HH((head)->hh.tbl, _thh); \ + _thh = (_thh->next ? HH_FROM_ELMT((head)->hh.tbl, _thh->next) : NULL); \ + } \ + if (_count != (head)->hh.tbl->num_items) { \ + HASH_OOPS("%s: invalid app item count %u, actual %u\n", \ + (where), (head)->hh.tbl->num_items, _count); \ + } \ + } \ +} while (0) +#else +#define HASH_FSCK(hh,head,where) +#endif + +/* When compiled with -DHASH_EMIT_KEYS, length-prefixed keys are emitted to + * the descriptor to which this macro is defined for tuning the hash function. + * The app can #include to get the prototype for write(2). */ +#ifdef HASH_EMIT_KEYS +#define HASH_EMIT_KEY(hh,head,keyptr,fieldlen) \ +do { \ + unsigned _klen = fieldlen; \ + write(HASH_EMIT_KEYS, &_klen, sizeof(_klen)); \ + write(HASH_EMIT_KEYS, keyptr, (unsigned long)fieldlen); \ +} while (0) +#else +#define HASH_EMIT_KEY(hh,head,keyptr,fieldlen) +#endif + +/* The Bernstein hash function, used in Perl prior to v5.6. Note (x<<5+x)=x*33. */ +#define HASH_BER(key,keylen,hashv) \ +do { \ + unsigned _hb_keylen = (unsigned)keylen; \ + const unsigned char *_hb_key = (const unsigned char*)(key); \ + (hashv) = 0; \ + while (_hb_keylen-- != 0U) { \ + (hashv) = (((hashv) << 5) + (hashv)) + *_hb_key++; \ + } \ +} while (0) + + +/* SAX/FNV/OAT/JEN hash functions are macro variants of those listed at + * http://eternallyconfuzzled.com/tuts/algorithms/jsw_tut_hashing.aspx + * (archive link: https://archive.is/Ivcan ) + */ +#define HASH_SAX(key,keylen,hashv) \ +do { \ + unsigned _sx_i; \ + const unsigned char *_hs_key = (const unsigned char*)(key); \ + hashv = 0; \ + for (_sx_i=0; _sx_i < keylen; _sx_i++) { \ + hashv ^= (hashv << 5) + (hashv >> 2) + _hs_key[_sx_i]; \ + } \ +} while (0) +/* FNV-1a variation */ +#define HASH_FNV(key,keylen,hashv) \ +do { \ + unsigned _fn_i; \ + const unsigned char *_hf_key = (const unsigned char*)(key); \ + (hashv) = 2166136261U; \ + for (_fn_i=0; _fn_i < keylen; _fn_i++) { \ + hashv = hashv ^ _hf_key[_fn_i]; \ + hashv = hashv * 16777619U; \ + } \ +} while (0) + +#define HASH_OAT(key,keylen,hashv) \ +do { \ + unsigned _ho_i; \ + const unsigned char *_ho_key=(const unsigned char*)(key); \ + hashv = 0; \ + for(_ho_i=0; _ho_i < keylen; _ho_i++) { \ + hashv += _ho_key[_ho_i]; \ + hashv += (hashv << 10); \ + hashv ^= (hashv >> 6); \ + } \ + hashv += (hashv << 3); \ + hashv ^= (hashv >> 11); \ + hashv += (hashv << 15); \ +} while (0) + +#define HASH_JEN_MIX(a,b,c) \ +do { \ + a -= b; a -= c; a ^= ( c >> 13 ); \ + b -= c; b -= a; b ^= ( a << 8 ); \ + c -= a; c -= b; c ^= ( b >> 13 ); \ + a -= b; a -= c; a ^= ( c >> 12 ); \ + b -= c; b -= a; b ^= ( a << 16 ); \ + c -= a; c -= b; c ^= ( b >> 5 ); \ + a -= b; a -= c; a ^= ( c >> 3 ); \ + b -= c; b -= a; b ^= ( a << 10 ); \ + c -= a; c -= b; c ^= ( b >> 15 ); \ +} while (0) + +#define HASH_JEN(key,keylen,hashv) \ +do { \ + unsigned _hj_i,_hj_j,_hj_k; \ + unsigned const char *_hj_key=(unsigned const char*)(key); \ + hashv = 0xfeedbeefu; \ + _hj_i = _hj_j = 0x9e3779b9u; \ + _hj_k = (unsigned)(keylen); \ + while (_hj_k >= 12U) { \ + _hj_i += (_hj_key[0] + ( (unsigned)_hj_key[1] << 8 ) \ + + ( (unsigned)_hj_key[2] << 16 ) \ + + ( (unsigned)_hj_key[3] << 24 ) ); \ + _hj_j += (_hj_key[4] + ( (unsigned)_hj_key[5] << 8 ) \ + + ( (unsigned)_hj_key[6] << 16 ) \ + + ( (unsigned)_hj_key[7] << 24 ) ); \ + hashv += (_hj_key[8] + ( (unsigned)_hj_key[9] << 8 ) \ + + ( (unsigned)_hj_key[10] << 16 ) \ + + ( (unsigned)_hj_key[11] << 24 ) ); \ + \ + HASH_JEN_MIX(_hj_i, _hj_j, hashv); \ + \ + _hj_key += 12; \ + _hj_k -= 12U; \ + } \ + hashv += (unsigned)(keylen); \ + switch ( _hj_k ) { \ + case 11: hashv += ( (unsigned)_hj_key[10] << 24 ); /* FALLTHROUGH */ \ + case 10: hashv += ( (unsigned)_hj_key[9] << 16 ); /* FALLTHROUGH */ \ + case 9: hashv += ( (unsigned)_hj_key[8] << 8 ); /* FALLTHROUGH */ \ + case 8: _hj_j += ( (unsigned)_hj_key[7] << 24 ); /* FALLTHROUGH */ \ + case 7: _hj_j += ( (unsigned)_hj_key[6] << 16 ); /* FALLTHROUGH */ \ + case 6: _hj_j += ( (unsigned)_hj_key[5] << 8 ); /* FALLTHROUGH */ \ + case 5: _hj_j += _hj_key[4]; /* FALLTHROUGH */ \ + case 4: _hj_i += ( (unsigned)_hj_key[3] << 24 ); /* FALLTHROUGH */ \ + case 3: _hj_i += ( (unsigned)_hj_key[2] << 16 ); /* FALLTHROUGH */ \ + case 2: _hj_i += ( (unsigned)_hj_key[1] << 8 ); /* FALLTHROUGH */ \ + case 1: _hj_i += _hj_key[0]; /* FALLTHROUGH */ \ + default: ; \ + } \ + HASH_JEN_MIX(_hj_i, _hj_j, hashv); \ +} while (0) + +/* The Paul Hsieh hash function */ +#undef get16bits +#if (defined(__GNUC__) && defined(__i386__)) || defined(__WATCOMC__) \ + || defined(_MSC_VER) || defined (__BORLANDC__) || defined (__TURBOC__) +#define get16bits(d) (*((const uint16_t *) (d))) +#endif + +#if !defined (get16bits) +#define get16bits(d) ((((uint32_t)(((const uint8_t *)(d))[1])) << 8) \ + +(uint32_t)(((const uint8_t *)(d))[0]) ) +#endif +#define HASH_SFH(key,keylen,hashv) \ +do { \ + unsigned const char *_sfh_key=(unsigned const char*)(key); \ + uint32_t _sfh_tmp, _sfh_len = (uint32_t)keylen; \ + \ + unsigned _sfh_rem = _sfh_len & 3U; \ + _sfh_len >>= 2; \ + hashv = 0xcafebabeu; \ + \ + /* Main loop */ \ + for (;_sfh_len > 0U; _sfh_len--) { \ + hashv += get16bits (_sfh_key); \ + _sfh_tmp = ((uint32_t)(get16bits (_sfh_key+2)) << 11) ^ hashv; \ + hashv = (hashv << 16) ^ _sfh_tmp; \ + _sfh_key += 2U*sizeof (uint16_t); \ + hashv += hashv >> 11; \ + } \ + \ + /* Handle end cases */ \ + switch (_sfh_rem) { \ + case 3: hashv += get16bits (_sfh_key); \ + hashv ^= hashv << 16; \ + hashv ^= (uint32_t)(_sfh_key[sizeof (uint16_t)]) << 18; \ + hashv += hashv >> 11; \ + break; \ + case 2: hashv += get16bits (_sfh_key); \ + hashv ^= hashv << 11; \ + hashv += hashv >> 17; \ + break; \ + case 1: hashv += *_sfh_key; \ + hashv ^= hashv << 10; \ + hashv += hashv >> 1; \ + break; \ + default: ; \ + } \ + \ + /* Force "avalanching" of final 127 bits */ \ + hashv ^= hashv << 3; \ + hashv += hashv >> 5; \ + hashv ^= hashv << 4; \ + hashv += hashv >> 17; \ + hashv ^= hashv << 25; \ + hashv += hashv >> 6; \ +} while (0) + +/* iterate over items in a known bucket to find desired item */ +#define HASH_FIND_IN_BKT(tbl,hh,head,keyptr,keylen_in,hashval,out) \ +do { \ + if ((head).hh_head != NULL) { \ + DECLTYPE_ASSIGN(out, ELMT_FROM_HH(tbl, (head).hh_head)); \ + } else { \ + (out) = NULL; \ + } \ + while ((out) != NULL) { \ + if ((out)->hh.hashv == (hashval) && (out)->hh.keylen == (keylen_in)) { \ + if (HASH_KEYCMP((out)->hh.key, keyptr, keylen_in) == 0) { \ + break; \ + } \ + } \ + if ((out)->hh.hh_next != NULL) { \ + DECLTYPE_ASSIGN(out, ELMT_FROM_HH(tbl, (out)->hh.hh_next)); \ + } else { \ + (out) = NULL; \ + } \ + } \ +} while (0) + +/* add an item to a bucket */ +#define HASH_ADD_TO_BKT(head,hh,addhh,oomed) \ +do { \ + UT_hash_bucket *_ha_head = &(head); \ + _ha_head->count++; \ + (addhh)->hh_next = _ha_head->hh_head; \ + (addhh)->hh_prev = NULL; \ + if (_ha_head->hh_head != NULL) { \ + _ha_head->hh_head->hh_prev = (addhh); \ + } \ + _ha_head->hh_head = (addhh); \ + if ((_ha_head->count >= ((_ha_head->expand_mult + 1U) * HASH_BKT_CAPACITY_THRESH)) \ + && !(addhh)->tbl->noexpand) { \ + HASH_EXPAND_BUCKETS(addhh,(addhh)->tbl, oomed); \ + IF_HASH_NONFATAL_OOM( \ + if (oomed) { \ + HASH_DEL_IN_BKT(head,addhh); \ + } \ + ) \ + } \ +} while (0) + +/* remove an item from a given bucket */ +#define HASH_DEL_IN_BKT(head,delhh) \ +do { \ + UT_hash_bucket *_hd_head = &(head); \ + _hd_head->count--; \ + if (_hd_head->hh_head == (delhh)) { \ + _hd_head->hh_head = (delhh)->hh_next; \ + } \ + if ((delhh)->hh_prev) { \ + (delhh)->hh_prev->hh_next = (delhh)->hh_next; \ + } \ + if ((delhh)->hh_next) { \ + (delhh)->hh_next->hh_prev = (delhh)->hh_prev; \ + } \ +} while (0) + +/* Bucket expansion has the effect of doubling the number of buckets + * and redistributing the items into the new buckets. Ideally the + * items will distribute more or less evenly into the new buckets + * (the extent to which this is true is a measure of the quality of + * the hash function as it applies to the key domain). + * + * With the items distributed into more buckets, the chain length + * (item count) in each bucket is reduced. Thus by expanding buckets + * the hash keeps a bound on the chain length. This bounded chain + * length is the essence of how a hash provides constant time lookup. + * + * The calculation of tbl->ideal_chain_maxlen below deserves some + * explanation. First, keep in mind that we're calculating the ideal + * maximum chain length based on the *new* (doubled) bucket count. + * In fractions this is just n/b (n=number of items,b=new num buckets). + * Since the ideal chain length is an integer, we want to calculate + * ceil(n/b). We don't depend on floating point arithmetic in this + * hash, so to calculate ceil(n/b) with integers we could write + * + * ceil(n/b) = (n/b) + ((n%b)?1:0) + * + * and in fact a previous version of this hash did just that. + * But now we have improved things a bit by recognizing that b is + * always a power of two. We keep its base 2 log handy (call it lb), + * so now we can write this with a bit shift and logical AND: + * + * ceil(n/b) = (n>>lb) + ( (n & (b-1)) ? 1:0) + * + */ +#define HASH_EXPAND_BUCKETS(hh,tbl,oomed) \ +do { \ + unsigned _he_bkt; \ + unsigned _he_bkt_i; \ + struct UT_hash_handle *_he_thh, *_he_hh_nxt; \ + UT_hash_bucket *_he_new_buckets, *_he_newbkt; \ + _he_new_buckets = (UT_hash_bucket*)uthash_malloc( \ + sizeof(struct UT_hash_bucket) * (tbl)->num_buckets * 2U); \ + if (!_he_new_buckets) { \ + HASH_RECORD_OOM(oomed); \ + } else { \ + uthash_bzero(_he_new_buckets, \ + sizeof(struct UT_hash_bucket) * (tbl)->num_buckets * 2U); \ + (tbl)->ideal_chain_maxlen = \ + ((tbl)->num_items >> ((tbl)->log2_num_buckets+1U)) + \ + ((((tbl)->num_items & (((tbl)->num_buckets*2U)-1U)) != 0U) ? 1U : 0U); \ + (tbl)->nonideal_items = 0; \ + for (_he_bkt_i = 0; _he_bkt_i < (tbl)->num_buckets; _he_bkt_i++) { \ + _he_thh = (tbl)->buckets[ _he_bkt_i ].hh_head; \ + while (_he_thh != NULL) { \ + _he_hh_nxt = _he_thh->hh_next; \ + HASH_TO_BKT(_he_thh->hashv, (tbl)->num_buckets * 2U, _he_bkt); \ + _he_newbkt = &(_he_new_buckets[_he_bkt]); \ + if (++(_he_newbkt->count) > (tbl)->ideal_chain_maxlen) { \ + (tbl)->nonideal_items++; \ + if (_he_newbkt->count > _he_newbkt->expand_mult * (tbl)->ideal_chain_maxlen) { \ + _he_newbkt->expand_mult++; \ + } \ + } \ + _he_thh->hh_prev = NULL; \ + _he_thh->hh_next = _he_newbkt->hh_head; \ + if (_he_newbkt->hh_head != NULL) { \ + _he_newbkt->hh_head->hh_prev = _he_thh; \ + } \ + _he_newbkt->hh_head = _he_thh; \ + _he_thh = _he_hh_nxt; \ + } \ + } \ + uthash_free((tbl)->buckets, (tbl)->num_buckets * sizeof(struct UT_hash_bucket)); \ + (tbl)->num_buckets *= 2U; \ + (tbl)->log2_num_buckets++; \ + (tbl)->buckets = _he_new_buckets; \ + (tbl)->ineff_expands = ((tbl)->nonideal_items > ((tbl)->num_items >> 1)) ? \ + ((tbl)->ineff_expands+1U) : 0U; \ + if ((tbl)->ineff_expands > 1U) { \ + (tbl)->noexpand = 1; \ + uthash_noexpand_fyi(tbl); \ + } \ + uthash_expand_fyi(tbl); \ + } \ +} while (0) + + +/* This is an adaptation of Simon Tatham's O(n log(n)) mergesort */ +/* Note that HASH_SORT assumes the hash handle name to be hh. + * HASH_SRT was added to allow the hash handle name to be passed in. */ +#define HASH_SORT(head,cmpfcn) HASH_SRT(hh,head,cmpfcn) +#define HASH_SRT(hh,head,cmpfcn) \ +do { \ + unsigned _hs_i; \ + unsigned _hs_looping,_hs_nmerges,_hs_insize,_hs_psize,_hs_qsize; \ + struct UT_hash_handle *_hs_p, *_hs_q, *_hs_e, *_hs_list, *_hs_tail; \ + if (head != NULL) { \ + _hs_insize = 1; \ + _hs_looping = 1; \ + _hs_list = &((head)->hh); \ + while (_hs_looping != 0U) { \ + _hs_p = _hs_list; \ + _hs_list = NULL; \ + _hs_tail = NULL; \ + _hs_nmerges = 0; \ + while (_hs_p != NULL) { \ + _hs_nmerges++; \ + _hs_q = _hs_p; \ + _hs_psize = 0; \ + for (_hs_i = 0; _hs_i < _hs_insize; ++_hs_i) { \ + _hs_psize++; \ + _hs_q = ((_hs_q->next != NULL) ? \ + HH_FROM_ELMT((head)->hh.tbl, _hs_q->next) : NULL); \ + if (_hs_q == NULL) { \ + break; \ + } \ + } \ + _hs_qsize = _hs_insize; \ + while ((_hs_psize != 0U) || ((_hs_qsize != 0U) && (_hs_q != NULL))) { \ + if (_hs_psize == 0U) { \ + _hs_e = _hs_q; \ + _hs_q = ((_hs_q->next != NULL) ? \ + HH_FROM_ELMT((head)->hh.tbl, _hs_q->next) : NULL); \ + _hs_qsize--; \ + } else if ((_hs_qsize == 0U) || (_hs_q == NULL)) { \ + _hs_e = _hs_p; \ + if (_hs_p != NULL) { \ + _hs_p = ((_hs_p->next != NULL) ? \ + HH_FROM_ELMT((head)->hh.tbl, _hs_p->next) : NULL); \ + } \ + _hs_psize--; \ + } else if ((cmpfcn( \ + DECLTYPE(head)(ELMT_FROM_HH((head)->hh.tbl, _hs_p)), \ + DECLTYPE(head)(ELMT_FROM_HH((head)->hh.tbl, _hs_q)) \ + )) <= 0) { \ + _hs_e = _hs_p; \ + if (_hs_p != NULL) { \ + _hs_p = ((_hs_p->next != NULL) ? \ + HH_FROM_ELMT((head)->hh.tbl, _hs_p->next) : NULL); \ + } \ + _hs_psize--; \ + } else { \ + _hs_e = _hs_q; \ + _hs_q = ((_hs_q->next != NULL) ? \ + HH_FROM_ELMT((head)->hh.tbl, _hs_q->next) : NULL); \ + _hs_qsize--; \ + } \ + if ( _hs_tail != NULL ) { \ + _hs_tail->next = ((_hs_e != NULL) ? \ + ELMT_FROM_HH((head)->hh.tbl, _hs_e) : NULL); \ + } else { \ + _hs_list = _hs_e; \ + } \ + if (_hs_e != NULL) { \ + _hs_e->prev = ((_hs_tail != NULL) ? \ + ELMT_FROM_HH((head)->hh.tbl, _hs_tail) : NULL); \ + } \ + _hs_tail = _hs_e; \ + } \ + _hs_p = _hs_q; \ + } \ + if (_hs_tail != NULL) { \ + _hs_tail->next = NULL; \ + } \ + if (_hs_nmerges <= 1U) { \ + _hs_looping = 0; \ + (head)->hh.tbl->tail = _hs_tail; \ + DECLTYPE_ASSIGN(head, ELMT_FROM_HH((head)->hh.tbl, _hs_list)); \ + } \ + _hs_insize *= 2U; \ + } \ + HASH_FSCK(hh, head, "HASH_SRT"); \ + } \ +} while (0) + +/* This function selects items from one hash into another hash. + * The end result is that the selected items have dual presence + * in both hashes. There is no copy of the items made; rather + * they are added into the new hash through a secondary hash + * hash handle that must be present in the structure. */ +#define HASH_SELECT(hh_dst, dst, hh_src, src, cond) \ +do { \ + unsigned _src_bkt, _dst_bkt; \ + void *_last_elt = NULL, *_elt; \ + UT_hash_handle *_src_hh, *_dst_hh, *_last_elt_hh=NULL; \ + ptrdiff_t _dst_hho = ((char*)(&(dst)->hh_dst) - (char*)(dst)); \ + if ((src) != NULL) { \ + for (_src_bkt=0; _src_bkt < (src)->hh_src.tbl->num_buckets; _src_bkt++) { \ + for (_src_hh = (src)->hh_src.tbl->buckets[_src_bkt].hh_head; \ + _src_hh != NULL; \ + _src_hh = _src_hh->hh_next) { \ + _elt = ELMT_FROM_HH((src)->hh_src.tbl, _src_hh); \ + if (cond(_elt)) { \ + IF_HASH_NONFATAL_OOM( int _hs_oomed = 0; ) \ + _dst_hh = (UT_hash_handle*)(void*)(((char*)_elt) + _dst_hho); \ + _dst_hh->key = _src_hh->key; \ + _dst_hh->keylen = _src_hh->keylen; \ + _dst_hh->hashv = _src_hh->hashv; \ + _dst_hh->prev = _last_elt; \ + _dst_hh->next = NULL; \ + if (_last_elt_hh != NULL) { \ + _last_elt_hh->next = _elt; \ + } \ + if ((dst) == NULL) { \ + DECLTYPE_ASSIGN(dst, _elt); \ + HASH_MAKE_TABLE(hh_dst, dst, _hs_oomed); \ + IF_HASH_NONFATAL_OOM( \ + if (_hs_oomed) { \ + uthash_nonfatal_oom(_elt); \ + (dst) = NULL; \ + continue; \ + } \ + ) \ + } else { \ + _dst_hh->tbl = (dst)->hh_dst.tbl; \ + } \ + HASH_TO_BKT(_dst_hh->hashv, _dst_hh->tbl->num_buckets, _dst_bkt); \ + HASH_ADD_TO_BKT(_dst_hh->tbl->buckets[_dst_bkt], hh_dst, _dst_hh, _hs_oomed); \ + (dst)->hh_dst.tbl->num_items++; \ + IF_HASH_NONFATAL_OOM( \ + if (_hs_oomed) { \ + HASH_ROLLBACK_BKT(hh_dst, dst, _dst_hh); \ + HASH_DELETE_HH(hh_dst, dst, _dst_hh); \ + _dst_hh->tbl = NULL; \ + uthash_nonfatal_oom(_elt); \ + continue; \ + } \ + ) \ + HASH_BLOOM_ADD(_dst_hh->tbl, _dst_hh->hashv); \ + _last_elt = _elt; \ + _last_elt_hh = _dst_hh; \ + } \ + } \ + } \ + } \ + HASH_FSCK(hh_dst, dst, "HASH_SELECT"); \ +} while (0) + +#define HASH_CLEAR(hh,head) \ +do { \ + if ((head) != NULL) { \ + HASH_BLOOM_FREE((head)->hh.tbl); \ + uthash_free((head)->hh.tbl->buckets, \ + (head)->hh.tbl->num_buckets*sizeof(struct UT_hash_bucket)); \ + uthash_free((head)->hh.tbl, sizeof(UT_hash_table)); \ + (head) = NULL; \ + } \ +} while (0) + +#define HASH_OVERHEAD(hh,head) \ + (((head) != NULL) ? ( \ + (size_t)(((head)->hh.tbl->num_items * sizeof(UT_hash_handle)) + \ + ((head)->hh.tbl->num_buckets * sizeof(UT_hash_bucket)) + \ + sizeof(UT_hash_table) + \ + (HASH_BLOOM_BYTELEN))) : 0U) + +#ifdef NO_DECLTYPE +#define HASH_ITER(hh,head,el,tmp) \ +for(((el)=(head)), ((*(char**)(&(tmp)))=(char*)((head!=NULL)?(head)->hh.next:NULL)); \ + (el) != NULL; ((el)=(tmp)), ((*(char**)(&(tmp)))=(char*)((tmp!=NULL)?(tmp)->hh.next:NULL))) +#else +#define HASH_ITER(hh,head,el,tmp) \ +for(((el)=(head)), ((tmp)=DECLTYPE(el)((head!=NULL)?(head)->hh.next:NULL)); \ + (el) != NULL; ((el)=(tmp)), ((tmp)=DECLTYPE(el)((tmp!=NULL)?(tmp)->hh.next:NULL))) +#endif + +/* obtain a count of items in the hash */ +#define HASH_COUNT(head) HASH_CNT(hh,head) +#define HASH_CNT(hh,head) ((head != NULL)?((head)->hh.tbl->num_items):0U) + +typedef struct UT_hash_bucket { + struct UT_hash_handle *hh_head; + unsigned count; + + /* expand_mult is normally set to 0. In this situation, the max chain length + * threshold is enforced at its default value, HASH_BKT_CAPACITY_THRESH. (If + * the bucket's chain exceeds this length, bucket expansion is triggered). + * However, setting expand_mult to a non-zero value delays bucket expansion + * (that would be triggered by additions to this particular bucket) + * until its chain length reaches a *multiple* of HASH_BKT_CAPACITY_THRESH. + * (The multiplier is simply expand_mult+1). The whole idea of this + * multiplier is to reduce bucket expansions, since they are expensive, in + * situations where we know that a particular bucket tends to be overused. + * It is better to let its chain length grow to a longer yet-still-bounded + * value, than to do an O(n) bucket expansion too often. + */ + unsigned expand_mult; + +} UT_hash_bucket; + +/* random signature used only to find hash tables in external analysis */ +#define HASH_SIGNATURE 0xa0111fe1u +#define HASH_BLOOM_SIGNATURE 0xb12220f2u + +typedef struct UT_hash_table { + UT_hash_bucket *buckets; + unsigned num_buckets, log2_num_buckets; + unsigned num_items; + struct UT_hash_handle *tail; /* tail hh in app order, for fast append */ + ptrdiff_t hho; /* hash handle offset (byte pos of hash handle in element */ + + /* in an ideal situation (all buckets used equally), no bucket would have + * more than ceil(#items/#buckets) items. that's the ideal chain length. */ + unsigned ideal_chain_maxlen; + + /* nonideal_items is the number of items in the hash whose chain position + * exceeds the ideal chain maxlen. these items pay the penalty for an uneven + * hash distribution; reaching them in a chain traversal takes >ideal steps */ + unsigned nonideal_items; + + /* ineffective expands occur when a bucket doubling was performed, but + * afterward, more than half the items in the hash had nonideal chain + * positions. If this happens on two consecutive expansions we inhibit any + * further expansion, as it's not helping; this happens when the hash + * function isn't a good fit for the key domain. When expansion is inhibited + * the hash will still work, albeit no longer in constant time. */ + unsigned ineff_expands, noexpand; + + uint32_t signature; /* used only to find hash tables in external analysis */ +#ifdef HASH_BLOOM + uint32_t bloom_sig; /* used only to test bloom exists in external analysis */ + uint8_t *bloom_bv; + uint8_t bloom_nbits; +#endif + +} UT_hash_table; + +typedef struct UT_hash_handle { + struct UT_hash_table *tbl; + void *prev; /* prev element in app order */ + void *next; /* next element in app order */ + struct UT_hash_handle *hh_prev; /* previous hh in bucket order */ + struct UT_hash_handle *hh_next; /* next hh in bucket order */ + const void *key; /* ptr to enclosing struct's key */ + unsigned keylen; /* enclosing struct's key len */ + unsigned hashv; /* result of hash-fcn(key) */ +} UT_hash_handle; + +#endif /* UTHASH_H */ diff --git a/ini/features.ini b/ini/features.ini index 833fe76510..da1865ea05 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -13,7 +13,7 @@ [features] YHCB2004 = LiquidCrystal_AIP31068=https://github.com/ellensp/LiquidCrystal_AIP31068/archive/3fc43b7.zip, red-scorp/SoftSPIB@^1.1.1 -HAS_TFT_LVGL_UI = lvgl=https://github.com/makerbase-mks/LVGL-6.1.1-MKS/archive/a3ebe98bc6.zip +HAS_TFT_LVGL_UI = lvgl=https://github.com/staff1010/LVGL-6.1.1-MKS/archive/v6.1.2.zip build_src_filter=+ extra_scripts=download_mks_assets.py MARLIN_TEST_BUILD = build_src_filter=+ From 5b59424447a370473aaaa0a4f08988fc0b803ca9 Mon Sep 17 00:00:00 2001 From: Giuliano <3684609+GMagician@users.noreply.github.com> Date: Tue, 27 May 2025 22:15:55 +0200 Subject: [PATCH 077/102] =?UTF-8?q?=F0=9F=8C=90=20Fix=20Italian=20typo,=20?= =?UTF-8?q?etc.=20(#27890)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to #27877 Co-authored-by: Scott Lahteine --- Marlin/src/lcd/language/language_en.h | 3 +-- Marlin/src/lcd/language/language_it.h | 5 ++--- Marlin/src/lcd/language/language_tr.h | 1 - 3 files changed, 3 insertions(+), 6 deletions(-) diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index a74d28b82a..90948d7865 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -364,7 +364,7 @@ namespace LanguageNarrow_en { LSTR MSG_MOVE_N_MM = _UxGT("Move $mm"); LSTR MSG_MOVE_N_IN = _UxGT("Move $in"); LSTR MSG_MOVE_N_DEG = _UxGT("Move $") LCD_STR_DEGREE; - LSTR MSG_LIVE_MOVE = _UxGT("Live Move"); + LSTR MSG_LIVE_MOVE = _UxGT("Live Movement"); LSTR MSG_SPEED = _UxGT("Speed"); LSTR MSG_MESH_Z_OFFSET = _UxGT("Bed Z"); LSTR MSG_NOZZLE = _UxGT("Nozzle"); @@ -1124,7 +1124,6 @@ namespace LanguageNarrow_en { namespace LanguageWide_en { using namespace LanguageNarrow_en; #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 - LSTR MSG_LIVE_MOVE = _UxGT("Live Movement"); LSTR MSG_HOST_START_PRINT = _UxGT("Start Host Print"); LSTR MSG_PRINTING_OBJECT = _UxGT("Printing Object"); LSTR MSG_CANCEL_OBJECT = _UxGT("Cancel Object"); diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index dbf093c042..c0d717d0cc 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -341,7 +341,7 @@ namespace LanguageNarrow_it { LSTR MSG_MOVE_N_MM = _UxGT("Muovi di $mm"); LSTR MSG_MOVE_N_IN = _UxGT("Muovi di $in"); LSTR MSG_MOVE_N_DEG = _UxGT("Muovi di $") LCD_STR_DEGREE; - LSTR MSG_LIVE_MOVE = _UxGT("Modalità live"); + LSTR MSG_LIVE_MOVE = _UxGT("Movimento live"); LSTR MSG_SPEED = _UxGT("Velocità"); LSTR MSG_MESH_Z_OFFSET = _UxGT("Piatto Z"); LSTR MSG_NOZZLE = _UxGT("Ugello"); @@ -606,7 +606,7 @@ namespace LanguageNarrow_it { LSTR MSG_ATTACH_SD = _UxGT("Collega scheda SD"); LSTR MSG_ATTACH_USB = _UxGT("Collega unità USB"); LSTR MSG_RELEASE_MEDIA = _UxGT("Rilascia ") MEDIA_TYPE_IT; - LSTR MSG_RELEASE_SD = _UxGT("Rilascia sceda SD"); + LSTR MSG_RELEASE_SD = _UxGT("Rilascia scheda SD"); LSTR MSG_RELEASE_USB = _UxGT("Rilascia unità USB"); LSTR MSG_CHANGE_MEDIA = _UxGT("Selez.") MEDIA_TYPE_IT; LSTR MSG_CHANGE_SD = _UxGT("Selez. scheda SD"); @@ -1007,7 +1007,6 @@ namespace LanguageNarrow_it { namespace LanguageWide_it { using namespace LanguageNarrow_it; #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 - LSTR MSG_LIVE_MOVE = _UxGT("Movimento live"); LSTR MSG_HOST_START_PRINT = _UxGT("Avvio stampa host"); LSTR MSG_PRINTING_OBJECT = _UxGT("Stampa oggetto"); LSTR MSG_CANCEL_OBJECT = _UxGT("Cancella oggetto"); diff --git a/Marlin/src/lcd/language/language_tr.h b/Marlin/src/lcd/language/language_tr.h index 9e4f261271..77cb7bf9b8 100644 --- a/Marlin/src/lcd/language/language_tr.h +++ b/Marlin/src/lcd/language/language_tr.h @@ -891,7 +891,6 @@ namespace LanguageNarrow_tr { namespace LanguageWide_tr { using namespace LanguageNarrow_tr; #if LCD_WIDTH >= 20 || HAS_DWIN_E3V2 - LSTR MSG_LIVE_MOVE = _UxGT("Canlı Hareket"); LSTR MSG_HOST_START_PRINT = _UxGT("Host Baskıyı başlat"); LSTR MSG_PRINTING_OBJECT = _UxGT("Yazdırma Nesnesi"); LSTR MSG_CANCEL_OBJECT = _UxGT("Nesneyi İptal Et"); From 38eee768391280583bdc710630bce32a04a9be89 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 28 May 2025 00:32:03 +0000 Subject: [PATCH 078/102] [cron] Bump distribution date (2025-05-28) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 34ac9adaa3..ec6539e4fa 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-05-27" +//#define STRING_DISTRIBUTION_DATE "2025-05-28" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 8d0c6361af..745e8e40a0 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-05-27" + #define STRING_DISTRIBUTION_DATE "2025-05-28" #endif /** From fa25737a9f874999c0bb22862ad6ceeb3a1688ad Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 28 May 2025 14:08:07 -0500 Subject: [PATCH 079/102] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20TMC?= =?UTF-8?q?Stepper=20=3D>=200.8.3?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ini/features.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ini/features.ini b/ini/features.ini index da1865ea05..011163b5d9 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -20,7 +20,7 @@ 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.2.zip +HAS_TRINAMIC_CONFIG = TMCStepper=https://github.com/MarlinFirmware/TMCStepper/archive/v0.8.3.zip build_src_filter=+ + + + + HAS_STEPPER_CONTROL = build_src_filter=+ HAS_T(RINAMIC_CONFIG|MC_SPI) = build_src_filter=+ From a270cc36e69e162de1e698306b730ef0a5f3c911 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 29 May 2025 00:31:57 +0000 Subject: [PATCH 080/102] [cron] Bump distribution date (2025-05-29) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index ec6539e4fa..76d1da5dda 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-05-28" +//#define STRING_DISTRIBUTION_DATE "2025-05-29" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 745e8e40a0..154547cb93 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-05-28" + #define STRING_DISTRIBUTION_DATE "2025-05-29" #endif /** From 8f19e2d7d4450000ca9aaf8b4fb2822ebe86df2d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 29 May 2025 13:24:40 -0500 Subject: [PATCH 081/102] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20TMC?= =?UTF-8?q?Stepper=20=3D>=200.8.4?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ini/features.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ini/features.ini b/ini/features.ini index 011163b5d9..6b1e684561 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -20,7 +20,7 @@ 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.3.zip +HAS_TRINAMIC_CONFIG = TMCStepper=https://github.com/MarlinFirmware/TMCStepper/archive/v0.8.4.zip build_src_filter=+ + + + + HAS_STEPPER_CONTROL = build_src_filter=+ HAS_T(RINAMIC_CONFIG|MC_SPI) = build_src_filter=+ From e8f2430dacbf9533f916f000f57a5dbedbb6662f Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 30 May 2025 00:32:05 +0000 Subject: [PATCH 082/102] [cron] Bump distribution date (2025-05-30) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 76d1da5dda..f7598786c8 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-05-29" +//#define STRING_DISTRIBUTION_DATE "2025-05-30" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 154547cb93..5f6f7fdbf0 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-05-29" + #define STRING_DISTRIBUTION_DATE "2025-05-30" #endif /** From a6bfdf351f241955519af675f5af9dd9dd9f3a52 Mon Sep 17 00:00:00 2001 From: Vovodroid Date: Sat, 31 May 2025 06:53:21 +0300 Subject: [PATCH 083/102] =?UTF-8?q?=E2=9C=A8=20NONLINEAR=5FEXTRUSION=5FDEF?= =?UTF-8?q?AULT=5FON=20(#27819)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/Configuration_adv.h | 3 ++ Marlin/src/gcode/feature/nonlinear/M592.cpp | 20 ++++++--- Marlin/src/lcd/language/language_en.h | 1 + Marlin/src/lcd/menu/menu_advanced.cpp | 4 ++ Marlin/src/lcd/menu/menu_tune.cpp | 7 +++ Marlin/src/module/planner.cpp | 4 +- Marlin/src/module/settings.cpp | 8 ++-- Marlin/src/module/stepper.cpp | 41 +++++++----------- Marlin/src/module/stepper.h | 48 ++++++++++++++------- buildroot/tests/STM32F103RC_btt | 2 +- 10 files changed, 83 insertions(+), 55 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 7939b5cc9b..f7ab7abd94 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -2384,6 +2384,9 @@ * For better results also enable ADAPTIVE_STEP_SMOOTHING. */ //#define NONLINEAR_EXTRUSION +#if ENABLED(NONLINEAR_EXTRUSION) + //#define NONLINEAR_EXTRUSION_DEFAULT_ON // Enable if NLE should be ON by default +#endif // @section leveling diff --git a/Marlin/src/gcode/feature/nonlinear/M592.cpp b/Marlin/src/gcode/feature/nonlinear/M592.cpp index 78c15443f8..b084e326f7 100644 --- a/Marlin/src/gcode/feature/nonlinear/M592.cpp +++ b/Marlin/src/gcode/feature/nonlinear/M592.cpp @@ -30,11 +30,13 @@ void GcodeSuite::M592_report(const bool forReplay/*=true*/) { TERN_(MARLIN_SMALL_BUILD, return); report_heading_etc(forReplay, F(STR_NONLINEAR_EXTRUSION)); - SERIAL_ECHOLNPGM(" M592 A", stepper.ne.A, " B", stepper.ne.B, " C", stepper.ne.C); + const nonlinear_settings_t &sns = stepper.ne.settings; + SERIAL_ECHOLNPGM(" M592 S", sns.enabled, " A", sns.coeff.A, " B", sns.coeff.B, " C", sns.coeff.C); } /** * M592: Get or set nonlinear extrusion parameters + * S Enable / Disable Nonlinear Extrusion * A Quadratic coefficient (default 0.0) * B Linear coefficient (default 0.0) * C Constant coefficient (default 1.0) @@ -46,14 +48,18 @@ void GcodeSuite::M592_report(const bool forReplay/*=true*/) { void GcodeSuite::M592() { if (!parser.seen_any()) return M592_report(); - if (parser.seenval('A')) stepper.ne.A = parser.value_float(); - if (parser.seenval('B')) stepper.ne.B = parser.value_float(); - if (parser.seenval('C')) stepper.ne.C = parser.value_float(); + nonlinear_t &ne = stepper.ne; + nonlinear_settings_t &sns = ne.settings; + + if (parser.seen('S')) sns.enabled = parser.value_bool(); + if (parser.seenval('A')) sns.coeff.A = parser.value_float(); + if (parser.seenval('B')) sns.coeff.B = parser.value_float(); + if (parser.seenval('C')) sns.coeff.C = parser.value_float(); #if ENABLED(SMOOTH_LIN_ADVANCE) - stepper.ne_q30.A = _BV32(30) * (stepper.ne.A * planner.mm_per_step[E_AXIS_N(0)] * planner.mm_per_step[E_AXIS_N(0)]); - stepper.ne_q30.B = _BV32(30) * (stepper.ne.B * planner.mm_per_step[E_AXIS_N(0)]); - stepper.ne_q30.C = _BV32(30) * stepper.ne.C; + ne.q30.A = _BV32(30) * (sns.coeff.A * planner.mm_per_step[E_AXIS_N(0)] * planner.mm_per_step[E_AXIS_N(0)]); + ne.q30.B = _BV32(30) * (sns.coeff.B * planner.mm_per_step[E_AXIS_N(0)]); + ne.q30.C = _BV32(30) * sns.coeff.C; #endif } diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 90948d7865..be309f53d8 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -509,6 +509,7 @@ namespace LanguageNarrow_en { LSTR MSG_ADVANCE_TAU = _UxGT("Advance Tau"); LSTR MSG_ADVANCE_K_E = _UxGT("Advance K *"); LSTR MSG_ADVANCE_TAU_E = _UxGT("Advance Tau *"); + LSTR MSG_NLE_ON = _UxGT("NLE enabled"); LSTR MSG_CONTRAST = _UxGT("LCD Contrast"); LSTR MSG_BRIGHTNESS = _UxGT("LCD Brightness"); LSTR MSG_SCREEN_TIMEOUT = _UxGT("LCD Timeout (m)"); diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index b15a21fc7b..65d7a88f0d 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -138,6 +138,10 @@ void menu_backlash(); #endif #endif // LIN_ADVANCE + #if ENABLED(NONLINEAR_EXTRUSION) + EDIT_ITEM(bool, MSG_NLE_ON, &stepper.ne.settings.enabled); + #endif + #if DISABLED(NO_VOLUMETRICS) EDIT_ITEM(bool, MSG_VOLUMETRIC_ENABLED, &parser.volumetric_enabled, planner.calculate_volumetric_multipliers); diff --git a/Marlin/src/lcd/menu/menu_tune.cpp b/Marlin/src/lcd/menu/menu_tune.cpp index 7f4696a3f1..18d52bb640 100644 --- a/Marlin/src/lcd/menu/menu_tune.cpp +++ b/Marlin/src/lcd/menu/menu_tune.cpp @@ -237,6 +237,13 @@ void menu_tune() { #endif #endif + // + // Nonlinear Extrusion state + // + #if ENABLED(NONLINEAR_EXTRUSION) + EDIT_ITEM(bool, MSG_NLE_ON, &stepper.ne.settings.enabled); + #endif + // // Babystep X: // Babystep Y: diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 8678c82130..2e2b5798b7 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -3255,8 +3255,8 @@ void Planner::refresh_positioning() { #if ENABLED(EDITABLE_STEPS_PER_UNIT) LOOP_DISTINCT_AXES(i) mm_per_step[i] = 1.0f / settings.axis_steps_per_mm[i]; #if ALL(NONLINEAR_EXTRUSION, SMOOTH_LIN_ADVANCE) - stepper.ne_q30.A = _BV32(30) * (stepper.ne.A * mm_per_step[E_AXIS_N(0)] * mm_per_step[E_AXIS_N(0)]); - stepper.ne_q30.B = _BV32(30) * (stepper.ne.B * mm_per_step[E_AXIS_N(0)]); + stepper.ne.q30.A = _BV32(30) * (stepper.ne.settings.coeff.A * mm_per_step[E_AXIS_N(0)] * mm_per_step[E_AXIS_N(0)]); + stepper.ne.q30.B = _BV32(30) * (stepper.ne.settings.coeff.B * mm_per_step[E_AXIS_N(0)]); #endif #endif set_position_mm(current_position); diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 2161be5abc..0d197b2d12 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -685,7 +685,7 @@ typedef struct SettingsDataStruct { // Nonlinear Extrusion // #if ENABLED(NONLINEAR_EXTRUSION) - ne_coeff_t stepper_ne; // M592 A B C + nonlinear_settings_t stepper_ne_settings; // M592 S A B C #endif // @@ -1798,7 +1798,7 @@ void MarlinSettings::postprocess() { // Nonlinear Extrusion // #if ENABLED(NONLINEAR_EXTRUSION) - EEPROM_WRITE(stepper.ne); + EEPROM_WRITE(stepper.ne.settings); #endif // @@ -2933,7 +2933,7 @@ void MarlinSettings::postprocess() { // Nonlinear Extrusion // #if ENABLED(NONLINEAR_EXTRUSION) - EEPROM_READ(stepper.ne); + EEPROM_READ(stepper.ne.settings); #endif // @@ -3747,7 +3747,7 @@ void MarlinSettings::reset() { // // Nonlinear Extrusion // - TERN_(NONLINEAR_EXTRUSION, stepper.ne.reset()); + TERN_(NONLINEAR_EXTRUSION, stepper.ne.settings.reset()); // // Input Shaping diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index edfed3b8e2..fd3d3bd800 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -256,17 +256,7 @@ uint32_t Stepper::advance_divisor = 0, #endif #if ENABLED(NONLINEAR_EXTRUSION) - ne_coeff_t Stepper::ne; - #if NONLINEAR_EXTRUSION_Q24 - ne_q24_t Stepper::ne_q24; - #else - ne_q30_t Stepper::ne_q30; - #endif - // private: - #if NONLINEAR_EXTRUSION_Q24 - int32_t Stepper::ne_edividend; - uint32_t Stepper::ne_scale_q24; - #endif + nonlinear_t Stepper::ne; // Initialized by settings.load #endif #if HAS_ZV_SHAPING @@ -2247,11 +2237,11 @@ hal_timer_t Stepper::calc_timer_interval(uint32_t step_rate) { #if NONLINEAR_EXTRUSION_Q24 void Stepper::calc_nonlinear_e(const uint32_t step_rate) { - const uint32_t velocity_q24 = ne_scale_q24 * step_rate; // Scale step_rate first so all intermediate values stay in range of 8.24 fixed point math - int32_t vd_q24 = (((((int64_t)ne_q24.A * velocity_q24) >> 24) * velocity_q24) >> 24) + (((int64_t)ne_q24.B * velocity_q24) >> 24); + const uint32_t velocity_q24 = ne.scale_q24 * step_rate; // Scale step_rate first so all intermediate values stay in range of 8.24 fixed point math + int32_t vd_q24 = ((((int64_t(ne.q24.A) * velocity_q24) >> 24) * velocity_q24) >> 24) + ((int64_t(ne.q24.B) * velocity_q24) >> 24); NOLESS(vd_q24, 0); - advance_dividend.e = (uint64_t(ne_q24.C + vd_q24) * ne_edividend) >> 24; + advance_dividend.e = (uint64_t(ne.q24.C + vd_q24) * ne.edividend) >> 24; } #endif @@ -2834,18 +2824,19 @@ hal_timer_t Stepper::block_phase_isr() { acc_step_rate = current_block->initial_rate; #endif + // Calculate Nonlinear Extrusion fixed-point quotients #if NONLINEAR_EXTRUSION_Q24 - ne_edividend = advance_dividend.e; - const float scale = (float(ne_edividend) / advance_divisor) * planner.mm_per_step[E_AXIS_N(current_block->extruder)]; - ne_scale_q24 = _BV32(24) * scale; - if (current_block->direction_bits.e && ANY_AXIS_MOVES(current_block)) { - ne_q24.A = _BV32(24) * ne.A; - ne_q24.B = _BV32(24) * ne.B; - ne_q24.C = _BV32(24) * ne.C; + ne.edividend = advance_dividend.e; + const float scale = (float(ne.edividend) / advance_divisor) * planner.mm_per_step[E_AXIS_N(current_block->extruder)]; + ne.scale_q24 = _BV32(24) * scale; + if (ne.settings.enabled && current_block->direction_bits.e && ANY_AXIS_MOVES(current_block)) { + ne.q24.A = _BV32(24) * ne.settings.coeff.A; + ne.q24.B = _BV32(24) * ne.settings.coeff.B; + ne.q24.C = _BV32(24) * ne.settings.coeff.C; } else { - ne_q24.A = ne_q24.B = 0; - ne_q24.C = _BV32(24); + ne.q24.A = ne.q24.B = 0; + ne.q24.C = _BV32(24); } #endif @@ -2891,9 +2882,9 @@ hal_timer_t Stepper::block_phase_isr() { #if ENABLED(NONLINEAR_EXTRUSION) if (forward_e && ANY_AXIS_MOVES(current_block)) { // Maximum polynomial value is just above 1, like 1.05..1.2, less than 2 anyway, so we can use 30 bits for fractional part - int32_t vd_q30 = ne_q30.A*step_rate*step_rate + ne_q30.B*step_rate; + int32_t vd_q30 = ne.q30.A * sq(step_rate) + ne.q30.B * step_rate; NOLESS(vd_q30, 0); - step_rate = (int64_t(step_rate) * (ne_q30.C + vd_q30)) >> 30; + step_rate = (int64_t(step_rate) * (ne.q30.C + vd_q30)) >> 30; } #endif diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index 73fd28fe85..90cbedc9fc 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -283,15 +283,41 @@ constexpr ena_mask_t enable_overlap[] = { #endif // HAS_ZV_SHAPING +// +// NonLinear Extrusion data +// #if ENABLED(NONLINEAR_EXTRUSION) - typedef struct { float A, B, C; void reset() { A = B = 0.0f; C = 1.0f; } } ne_coeff_t; + #if DISABLED(SMOOTH_LIN_ADVANCE) #define NONLINEAR_EXTRUSION_Q24 1 - typedef struct { int32_t A, B, C; } ne_q24_t; - #else - typedef struct { int32_t A, B, C; } ne_q30_t; #endif -#endif + + typedef struct { + bool enabled; + struct { + float A, B, C; + void reset() { A = B = 0.0f; C = 1.0f; } + } coeff; + void reset() { + enabled = ENABLED(NONLINEAR_EXTRUSION_DEFAULT_ON); + coeff.reset(); + } + } nonlinear_settings_t; + + typedef struct { + nonlinear_settings_t settings; + union { + struct { int32_t A, B, C; } q24; + struct { int32_t A, B, C; } q30; + }; + #if NONLINEAR_EXTRUSION_Q24 + protected: + int32_t edividend; + uint32_t scale_q24; + #endif + } nonlinear_t; + +#endif // NONLINEAR_EXTRUSION // // Stepper class definition @@ -347,12 +373,7 @@ class Stepper { #endif #if ENABLED(NONLINEAR_EXTRUSION) - static ne_coeff_t ne; - #if NONLINEAR_EXTRUSION_Q24 - static ne_q24_t ne_q24; - #else - static ne_q30_t ne_q30; - #endif + static nonlinear_t ne; #endif #if ENABLED(ADAPTIVE_STEP_SMOOTHING_TOGGLE) @@ -477,11 +498,6 @@ class Stepper { #endif #endif - #if NONLINEAR_EXTRUSION_Q24 - static int32_t ne_edividend; - static uint32_t ne_scale_q24; - #endif - #if ENABLED(BABYSTEPPING) static constexpr hal_timer_t BABYSTEP_NEVER = HAL_TIMER_TYPE_MAX; static hal_timer_t nextBabystepISR; diff --git a/buildroot/tests/STM32F103RC_btt b/buildroot/tests/STM32F103RC_btt index 2b05d42922..97339d7750 100755 --- a/buildroot/tests/STM32F103RC_btt +++ b/buildroot/tests/STM32F103RC_btt @@ -15,5 +15,5 @@ opt_set MOTHERBOARD BOARD_BTT_SKR_MINI_E3_V1_0 SERIAL_PORT 1 SERIAL_PORT_2 -1 \ X_CURRENT_HOME X_CURRENT/2 Y_CURRENT_HOME Y_CURRENT/2 Z_CURRENT_HOME Y_CURRENT/2 opt_enable CR10_STOCKDISPLAY PINS_DEBUGGING Z_IDLE_HEIGHT EDITABLE_HOMING_CURRENT \ FT_MOTION FT_MOTION_MENU BIQU_MICROPROBE_V1 PROBE_ENABLE_DISABLE Z_SAFE_HOMING AUTO_BED_LEVELING_BILINEAR \ - ADAPTIVE_STEP_SMOOTHING NONLINEAR_EXTRUSION + ADAPTIVE_STEP_SMOOTHING LIN_ADVANCE SMOOTH_LIN_ADVANCE NONLINEAR_EXTRUSION INPUT_SHAPING_X INPUT_SHAPING_Y exec_test $1 $2 "BigTreeTech SKR Mini E3 1.0 - TMC2209 HW Serial, FT_MOTION" "$3" From a2452a577b38d081a79e005532b4a710213289e0 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 31 May 2025 06:08:46 +0000 Subject: [PATCH 084/102] [cron] Bump distribution date (2025-05-31) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index f7598786c8..ca7a67dba7 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-05-30" +//#define STRING_DISTRIBUTION_DATE "2025-05-31" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 5f6f7fdbf0..f6c6927508 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-05-30" + #define STRING_DISTRIBUTION_DATE "2025-05-31" #endif /** From c377237fd8a9f982d3bb54ceab98f1ec23c70925 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 31 May 2025 16:05:13 -0500 Subject: [PATCH 085/102] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Twe?= =?UTF-8?q?ak=20G90=20/=20G91=20declaration?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/gcode.cpp | 4 ++-- Marlin/src/gcode/gcode.h | 3 +++ 2 files changed, 5 insertions(+), 2 deletions(-) diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 242972c24b..1fa5c55c22 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -458,8 +458,8 @@ void GcodeSuite::process_parsed_command(bool no_ok/*=false*/) { case 80: G80(); break; // G80: Reset the current motion mode #endif - case 90: set_relative_mode(false); break; // G90: Absolute Mode - case 91: set_relative_mode(true); break; // G91: Relative Mode + case 90: G90(); break; // G90: Absolute Mode + case 91: G91(); break; // G91: Relative Mode case 92: G92(); break; // G92: Set current axis position(s) diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index ee0ccb9a0f..61782d7d3d 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -632,6 +632,9 @@ private: static void G80(); #endif + static void G90() { set_relative_mode(false); } + static void G91() { set_relative_mode(true); } + static void G92(); #if ENABLED(CALIBRATION_GCODE) From b59251c388e249ec02d0a91db653dfd04e5a59f4 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 31 May 2025 16:06:12 -0500 Subject: [PATCH 086/102] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Mac?= =?UTF-8?q?ros=20for=20larger=20sets?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/macros.h | 34 ++++++++++++++++++++++++++++++++++ 1 file changed, 34 insertions(+) diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index bef89040b3..fd6296707f 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -307,6 +307,12 @@ #define GANG_N_1(N,K) _GANG_N(N,K,K,K,K,K,K,K,K,K,K,K,K,K,K,K,K) // Expansion of some list items +#define LIST_32(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,Z,AA,BB,CC,DD,EE,FF,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,Z,AA,BB,CC,DD,EE,FF +#define LIST_31(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,Z,AA,BB,CC,DD,EE,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,Z,AA,BB,CC,DD,EE +#define LIST_30(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,Z,AA,BB,CC,DD,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,Z,AA,BB,CC,DD +#define LIST_29(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,Z,AA,BB,CC,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,Z,AA,BB,CC +#define LIST_28(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,Z,AA,BB,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,TU,V,W,X,Y,Z,AA,BB +#define LIST_27(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,Z,AA,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,Z,AA #define LIST_26(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,Z,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,Z #define LIST_25(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,Y #define LIST_24(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,U,V,W,X @@ -572,6 +578,17 @@ #define INC_18 19 #define INC_19 20 #define INC_20 21 +#define INC_21 22 +#define INC_22 23 +#define INC_23 24 +#define INC_24 25 +#define INC_25 26 +#define INC_26 27 +#define INC_27 28 +#define INC_28 29 +#define INC_29 30 +#define INC_30 31 +#define INC_31 32 #define INCREMENT_(n) INC_##n #define INCREMENT(n) INCREMENT_(n) @@ -607,6 +624,23 @@ #define DEC_13 12 #define DEC_14 13 #define DEC_15 14 +#define DEC_16 15 +#define DEC_17 16 +#define DEC_18 17 +#define DEC_19 18 +#define DEC_20 19 +#define DEC_21 20 +#define DEC_22 21 +#define DEC_23 22 +#define DEC_24 23 +#define DEC_25 24 +#define DEC_26 25 +#define DEC_27 26 +#define DEC_28 27 +#define DEC_29 28 +#define DEC_30 29 +#define DEC_31 30 +#define DEC_32 31 #define DECREMENT_(n) DEC_##n #define DECREMENT(n) DECREMENT_(n) From 9dbce712fccaf3792ef9503afd3a4e301419b357 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 31 May 2025 16:08:47 -0500 Subject: [PATCH 087/102] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20TMC?= =?UTF-8?q?Stepper=20=3D>=200.8.5?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ini/features.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ini/features.ini b/ini/features.ini index 6b1e684561..80663abf5b 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -20,7 +20,7 @@ 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.4.zip +HAS_TRINAMIC_CONFIG = TMCStepper=https://github.com/MarlinFirmware/TMCStepper/archive/v0.8.5.zip build_src_filter=+ + + + + HAS_STEPPER_CONTROL = build_src_filter=+ HAS_T(RINAMIC_CONFIG|MC_SPI) = build_src_filter=+ From 3ddf728333c4e5dd7d24f4842c00f48dd3980b61 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 31 May 2025 16:54:57 -0500 Subject: [PATCH 088/102] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20some=20missed=20ON?= =?UTF-8?q?BOARD=5FSDIO?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/RP2040/HAL.cpp | 2 +- Marlin/src/pins/stm32f4/pins_XTLW_CLIMBER_8TH.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/HAL/RP2040/HAL.cpp b/Marlin/src/HAL/RP2040/HAL.cpp index 8c35d45542..f0d9e4eec6 100644 --- a/Marlin/src/HAL/RP2040/HAL.cpp +++ b/Marlin/src/HAL/RP2040/HAL.cpp @@ -59,7 +59,7 @@ void MarlinHAL::init() { constexpr int cpuFreq = F_CPU; UNUSED(cpuFreq); - #if HAS_MEDIA && DISABLED(SDIO_SUPPORT) && PIN_EXISTS(SD_SS) + #if HAS_MEDIA && DISABLED(ONBOARD_SDIO) && PIN_EXISTS(SD_SS) OUT_WRITE(SD_SS_PIN, HIGH); // Try to set SD_SS_PIN inactive before any other SPI users start up #endif diff --git a/Marlin/src/pins/stm32f4/pins_XTLW_CLIMBER_8TH.h b/Marlin/src/pins/stm32f4/pins_XTLW_CLIMBER_8TH.h index 053fb19525..0b41764ec4 100644 --- a/Marlin/src/pins/stm32f4/pins_XTLW_CLIMBER_8TH.h +++ b/Marlin/src/pins/stm32f4/pins_XTLW_CLIMBER_8TH.h @@ -168,7 +168,7 @@ // Must use soft SPI because Marlin's default hardware SPI is tied to LCD's EXP2 // #if SD_CONNECTION_IS(ONBOARD) - #define SDIO_SUPPORT // Use SDIO for onboard SD + #define ONBOARD_SDIO // Use SDIO for onboard SD #define SDIO_D0_PIN PC8 #define SDIO_D1_PIN PC9 #define SDIO_D2_PIN PC10 From 7c30124f80edb0887faa49c0f904e3c68ef52a07 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 31 May 2025 17:00:27 -0500 Subject: [PATCH 089/102] =?UTF-8?q?=F0=9F=93=8C=20Versions=20for=20adafrui?= =?UTF-8?q?t=20"SdFat",=20"Adafruit=20SPIFlash"?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ini/samd51.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ini/samd51.ini b/ini/samd51.ini index cf1f9ed8c0..c2a83a0413 100644 --- a/ini/samd51.ini +++ b/ini/samd51.ini @@ -23,5 +23,5 @@ lib_deps = ${common.lib_deps} Adafruit TinyUSB Library extra_scripts = ${common.extra_scripts} pre:buildroot/share/PlatformIO/scripts/SAMD51_grandcentral_m4.py -custom_marlin.HAS_MEDIA = SdFat - Adafruit Fork, Adafruit SPIFlash +custom_marlin.HAS_MEDIA = adafruit/SdFat@~2.3.50, adafruit/Adafruit SPIFlash@~5.1.1 debug_tool = jlink From 823014868c1a9974f0f1881193a8f042577310f5 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 1 Jun 2025 01:15:51 +0000 Subject: [PATCH 090/102] [cron] Bump distribution date (2025-06-01) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index ca7a67dba7..cd9a44f5ab 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-05-31" +//#define STRING_DISTRIBUTION_DATE "2025-06-01" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index f6c6927508..33c044ebd5 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-05-31" + #define STRING_DISTRIBUTION_DATE "2025-06-01" #endif /** From cc05123a803bfbd483632443a98b236f5722d600 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 1 Jun 2025 16:09:48 -0500 Subject: [PATCH 091/102] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20EXP3=5F03=5FPIN=20?= =?UTF-8?q?for=20CREALITY=5FV24S1=5F301F4?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Fixes #27904 Co-Authored-By: Nexrem --- Marlin/src/pins/stm32f4/pins_CREALITY_V24S1_301F4.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Marlin/src/pins/stm32f4/pins_CREALITY_V24S1_301F4.h b/Marlin/src/pins/stm32f4/pins_CREALITY_V24S1_301F4.h index fa524464e3..40ea8ae9bc 100644 --- a/Marlin/src/pins/stm32f4/pins_CREALITY_V24S1_301F4.h +++ b/Marlin/src/pins/stm32f4/pins_CREALITY_V24S1_301F4.h @@ -37,4 +37,6 @@ #define EEPROM_EXCL_ZONE 916,926 // Ender-3S1 STM32F401 Bootloader EEPROM exclusion zone +#define EXP3_03_PIN PA2 + #include "../stm32f1/pins_CREALITY_V24S1_301.h" From 8c6e9526b050006d7ea9cac786a8010d6d2aa31f Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 2 Jun 2025 00:34:11 +0000 Subject: [PATCH 092/102] [cron] Bump distribution date (2025-06-02) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index cd9a44f5ab..178fa18b69 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-06-01" +//#define STRING_DISTRIBUTION_DATE "2025-06-02" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 33c044ebd5..a90e2d857a 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-06-01" + #define STRING_DISTRIBUTION_DATE "2025-06-02" #endif /** From 9f6cafbae3a38d1432f8ed68fa27501012e57230 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 1 Jun 2025 20:47:35 -0500 Subject: [PATCH 093/102] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20Nozzle=20Cleaning?= =?UTF-8?q?=20wait=20for=20pre-set=20temp?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Fixes #27882 --- Marlin/src/libs/nozzle.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/libs/nozzle.cpp b/Marlin/src/libs/nozzle.cpp index 3b982718a2..ad77e1e0ae 100644 --- a/Marlin/src/libs/nozzle.cpp +++ b/Marlin/src/libs/nozzle.cpp @@ -189,12 +189,12 @@ Nozzle nozzle; #if ENABLED(NOZZLE_CLEAN_HEATUP) SERIAL_ECHOLNPGM("Nozzle too Cold - Heating"); thermalManager.setTargetHotend(NOZZLE_CLEAN_MIN_TEMP, arrPos); - thermalManager.wait_for_hotend(arrPos); #else SERIAL_ECHOLNPGM("Nozzle too cold - Skipping wipe"); return; #endif } + thermalManager.wait_for_hotend(arrPos); #endif #if HAS_SOFTWARE_ENDSTOPS From 6ea4a16212cc94b1665d057af8c504731d97f21e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 2 Jun 2025 16:47:50 -0500 Subject: [PATCH 094/102] =?UTF-8?q?=F0=9F=8C=90=20Automated=20README=20tra?= =?UTF-8?q?nslations?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- README-PT-BR.md | 81 ------------------------------------------------- README.md | 65 +++++++++++++++++++++++++++++++++------ 2 files changed, 56 insertions(+), 90 deletions(-) delete mode 100644 README-PT-BR.md diff --git a/README-PT-BR.md b/README-PT-BR.md deleted file mode 100644 index 3c730967ae..0000000000 --- a/README-PT-BR.md +++ /dev/null @@ -1,81 +0,0 @@ - -

Logo do MarlinFirmware

- -

Firmware de Impressora 3D Marlin

- -

- Licença GPL-V3.0 - Contribuidores - Data do Último Lançamento - Status do CI - Patrocínios no GitHub -
- Siga marlinfw.org no Bluesky - Siga MarlinFirmware no Mastodon -

- -Documentação adicional pode ser encontrada na [Página Inicial do Marlin](//marlinfw.org/). -Por favor, teste este firmware e nos avise se encontrar algum problema. Voluntários estão prontos para ajudar! - -## Branch de Correções do Marlin 2.1 - -__Não é para uso em produção. Use com cautela!__ - -O Marlin 2.1 continua oferecendo suporte a placas ARM 32 bits e AVR 8 bits, além de adicionar suporte para até 9 eixos coordenados e até 8 extrusoras. - -Este branch é para correções da versão mais recente 2.1.x. Periodicamente, ele servirá de base para o próximo lançamento menor da linha 2.1.x. - -Versões anteriores do Marlin podem ser baixadas na [página de lançamentos](//github.com/MarlinFirmware/Marlin/releases). - -## Configurações de Exemplo - -Antes de compilar o Marlin para sua máquina, você precisará de uma configuração específica para o seu hardware. Ao solicitar, seu fornecedor deve fornecer o código-fonte completo e as configurações da sua máquina. No entanto, se quiser instalar uma versão mais recente do Marlin, você precisará de arquivos de configuração atualizados. Felizmente, a comunidade do Marlin já contribuiu com dezenas de configurações testadas para ajudar no início. Visite o repositório [MarlinFirmware/Configurations](//github.com/MarlinFirmware/Configurations) para encontrar a configuração mais próxima da sua impressora. - -## Compilando o Marlin 2.1 - -Para compilar e enviar o Marlin você pode usar uma destas ferramentas: - -- O [Visual Studio Code](//code.visualstudio.com/download) com a extensão [Auto Build Marlin](//marlinfw.org/docs/basics/auto_build_marlin.html). -- A [IDE do Arduino](//www.arduino.cc/en/main/software): Veja [Compilando Marlin com Arduino](//marlinfw.org/docs/basics/install_arduino.html). -- Também é possível usar VSCode com devcontainer: Veja [Instalando Marlin (VSCode devcontainer)](http://marlinfw.org/docs/basics/install_devcontainer_vscode.html). - -O Marlin é otimizado para ser compilado com a extensão **PlatformIO IDE** no **Visual Studio Code**. Ainda é possível compilar com a **IDE do Arduino**, e temos planos para melhorar essa experiência, mas por enquanto o PlatformIO é a melhor escolha. - -## Placas AVR 8 Bits - -Pretendemos continuar oferecendo suporte às placas AVR 8 bits indefinidamente, mantendo uma base de código única que possa ser aplicada a todas as máquinas. Queremos que hobbystas, experimentadores e donos de máquinas antigas também se beneficiem das inovações da comunidade tanto quanto os donos de equipamentos mais modernos. Além disso, essas máquinas baseadas em AVR costumam ser ideais para testes e feedbacks! - -## Camada de Abstração de Hardware (HAL) - -O Marlin inclui uma camada de abstração de hardware para portar o firmware para uma grande variedade de chips. Essa camada trata das diferenças entre chips de forma modular, permitindo que as funcionalidades do Marlin sejam aproveitadas ao máximo. - -## Licença - -Marlin é publicado sob a licença GPL, então você pode usar, redistribuir e modificar o código-fonte, desde que o código derivado também seja publicado sob a mesma licença. Consulte o arquivo [LICENSE](https://github.com/MarlinFirmware/Marlin/blob/bugfix-2.1.x/LICENSE) para mais detalhes. - -## Ajude o Marlin! - -Você pode ajudar o projeto Marlin contribuindo com código, traduções, testes ou apoiando financeiramente no [GitHub Sponsors](https://github.com/sponsors/thinkyhead). - -...Marlin para diferentes plataformas de hardware. O HAL define as interfaces entre o núcleo do Marlin e o hardware da plataforma. O Marlin suporta atualmente as seguintes arquiteturas: - -- AVR -- SAM (Arduino Due) -- SAMD (Arduino Zero, etc.) -- STM32F1, STM32F4, STM32F7, STM32H7 -- LPC176x (Smoothieboard, ReARM, Archim, MKS Sbase, etc.) -- Teensy 3.5 e 3.6 (ARM Cortex-M4) -- ESP32 (experimental) - -## Comunicação Serial - -- **Baudrates suportados:** 250000, 115200, 57600, 38400, 19200, 9600 -- O baudrate padrão é 250000 para maior velocidade e estabilidade - -## Atualizações e Contribuições - -Aceitamos correções de bugs, melhorias de desempenho e novas funcionalidades. Veja as instruções de contribuição na [Wiki do Marlin](https://github.com/MarlinFirmware/Marlin/wiki/Contributing). - -## Licença - -Marlin é um software livre licenciado sob a [GNU General Public License v3.0](https://www.gnu.org/licenses/gpl-3.0.html). Você pode redistribuí-lo e/ou modificá-lo sob os termos da GPL. Para mais detalhes, veja o arquivo [LICENSE](LICENSE). diff --git a/README.md b/README.md index 69979f4884..cc5fa60db7 100644 --- a/README.md +++ b/README.md @@ -4,21 +4,68 @@

GPL-V3.0 License - Contributors - Last Release Date - CI Status - GitHub Sponsors + Contributors + Last Release Date + CI Status + GitHub Sponsors
- Follow marlinfw.org on Bluesky - Follow MarlinFirmware on Mastodon + Follow marlinfw.org on Bluesky + Follow MarlinFirmware on Mastodon

+### 🌍 Translations + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
AragonésБългарскиCatalàČeštinaDanskDeutschΕλληνικά
EnglishEspañolEuskaraSuomiFrançaisGalegoHrvatski
MagyarItalianoにほんご한국어NederlandsPolskiPortuguês
Português (Brasil)RomânăРусскийSlovenčinaSvenskaTürkçeУкраїнська
Tiếng Việt简体中文繁體中文
+ Additional 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! --- -This README is available in other languages -> **Versão em português:** [README-PT-BR.md](README-PT-BR.md) ## Marlin 2.1 Bugfix Branch @@ -140,7 +187,7 @@ Name|Role|Link|Donate ## Star History - + From 098e0961dcf01e9b7adf4f87e6ea92ab573ca95e Mon Sep 17 00:00:00 2001 From: David Buezas Date: Tue, 3 Jun 2025 00:34:02 +0200 Subject: [PATCH 095/102] =?UTF-8?q?=F0=9F=A9=B9=20TMC2240=20diag0=20push-p?= =?UTF-8?q?ull=20active=20HIGH=20(#27907)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/stepper/trinamic.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Marlin/src/module/stepper/trinamic.cpp b/Marlin/src/module/stepper/trinamic.cpp index 0f4a8aa89c..240adc9f4c 100644 --- a/Marlin/src/module/stepper/trinamic.cpp +++ b/Marlin/src/module/stepper/trinamic.cpp @@ -822,6 +822,8 @@ enum StealthIndex : uint8_t { st.PWMCONF(pwmconf.sr); TERN(HYBRID_THRESHOLD, st.set_pwm_thrs(hyb_thrs), UNUSED(hyb_thrs)); + + st.diag0_pushpull(true); st.GSTAT(); // Clear GSTAT } #endif // TMC2240 From 7df503de9388f2453515edd58fb5f74d01975b0a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 2 Jun 2025 18:23:07 -0500 Subject: [PATCH 096/102] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20FLY=20D5=20/=20D7?= =?UTF-8?q?=20serial=20for=20TMC2208?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit See MarlinFirmware/TMCStepper#5 --- ini/stm32f0.ini | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ini/stm32f0.ini b/ini/stm32f0.ini index a684b98871..e3762ebac2 100644 --- a/ini/stm32f0.ini +++ b/ini/stm32f0.ini @@ -62,7 +62,7 @@ platform_packages = framework-arduinoststm32@4.20500.230714 framework-cmsis@2.50700.210515 toolchain-gccarmnoneeabi@1.100301.220327 build_flags = ${stm32_variant.build_flags} - -DTIMER_SERIAL=TIM2 + -DTIMER_SERIAL=TIM2 -DTMC2208_BAUDRATE=9600 upload_protocol = stlink # @@ -77,5 +77,5 @@ platform_packages = framework-arduinoststm32@4.20500.230714 framework-cmsis@2.50700.210515 toolchain-gccarmnoneeabi@1.100301.220327 build_flags = ${stm32_variant.build_flags} - -DTIMER_SERIAL=TIM2 + -DTIMER_SERIAL=TIM2 -DTMC2208_BAUDRATE=9600 upload_protocol = dfu From 3bb9364c44131ae3680df4a35199cb67c117153b Mon Sep 17 00:00:00 2001 From: David Buezas Date: Tue, 3 Jun 2025 01:59:01 +0200 Subject: [PATCH 097/102] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Add?= =?UTF-8?q?=20TMC2240=20temperature=20reading=20(#27903)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/tmc_util.cpp | 19 ++++++++++++++++++- ini/features.ini | 2 +- 2 files changed, 19 insertions(+), 2 deletions(-) diff --git a/Marlin/src/feature/tmc_util.cpp b/Marlin/src/feature/tmc_util.cpp index d280b55854..6f53e1943c 100644 --- a/Marlin/src/feature/tmc_util.cpp +++ b/Marlin/src/feature/tmc_util.cpp @@ -526,7 +526,12 @@ TMC_HSTRT, TMC_SGT, TMC_MSCNT, - TMC_INTERPOLATE + TMC_INTERPOLATE, + TMC_VAIN, + TMC_VSUPPLY, + TMC_TEMP, + TMC_OVERTEMP, + TMC_OVERVOLT_THD }; enum TMC_drv_status_enum : char { TMC_DRV_CODES, @@ -701,6 +706,11 @@ case TMC_PWM_GRAD_AUTO: SERIAL_ECHO(st.pwm_grad_auto()); break; case TMC_STEALTHCHOP: print_true_or_false(st.stealth()); break; case TMC_INTERPOLATE: print_true_or_false(st.intpol()); break; + case TMC_VAIN: SERIAL_ECHO(st.get_ain_voltage()); break; + case TMC_VSUPPLY: SERIAL_ECHO(st.get_vsupply_voltage()); break; + case TMC_TEMP: SERIAL_ECHO(st.get_chip_temperature()); break; + case TMC_OVERTEMP: SERIAL_ECHO(st.get_overtemp_prewarn_celsius()); break; + case TMC_OVERVOLT_THD: SERIAL_ECHO(st.get_overvoltage_threshold_voltage()); break; default: break; } } @@ -978,6 +988,13 @@ DRV_REPORT("s2vsb\t", TMC_S2VSB); #endif DRV_REPORT("Driver registers:\n",TMC_DRV_STATUS_HEX); + #if HAS_DRIVER(TMC2240) + TMC_REPORT("Analog in (v)", TMC_VAIN); + TMC_REPORT("Supply (v)", TMC_VSUPPLY); + TMC_REPORT("Temp (°C)", TMC_TEMP); + TMC_REPORT("OT pre warn (°C)", TMC_OVERTEMP); + TMC_REPORT("OV theshold (v)", TMC_OVERVOLT_THD); + #endif SERIAL_EOL(); } diff --git a/ini/features.ini b/ini/features.ini index 80663abf5b..69ec43f030 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -20,7 +20,7 @@ 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.5.zip +HAS_TRINAMIC_CONFIG = TMCStepper=https://github.com/MarlinFirmware/TMCStepper/archive/v0.8.6.zip build_src_filter=+ + + + + HAS_STEPPER_CONTROL = build_src_filter=+ HAS_T(RINAMIC_CONFIG|MC_SPI) = build_src_filter=+ From f1bb46f5b8b86506ae38b29c6d323f194085f9f6 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 3 Jun 2025 00:32:58 +0000 Subject: [PATCH 098/102] [cron] Bump distribution date (2025-06-03) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 178fa18b69..b0c1c5acad 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-06-02" +//#define STRING_DISTRIBUTION_DATE "2025-06-03" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index a90e2d857a..98f11b7f3e 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-06-02" + #define STRING_DISTRIBUTION_DATE "2025-06-03" #endif /** From 951b8be3a111f7d84b6d949f37d7c45c0bd69916 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 3 Jun 2025 18:47:44 -0500 Subject: [PATCH 099/102] =?UTF-8?q?=F0=9F=A9=B9=20Update=20Creality=20CR4N?= =?UTF-8?q?S?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to #27003 --- Marlin/src/pins/stm32f1/pins_CREALITY_CR4NS.h | 22 +++++++++---------- 1 file changed, 10 insertions(+), 12 deletions(-) diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_CR4NS.h b/Marlin/src/pins/stm32f1/pins_CREALITY_CR4NS.h index 7d19aec51d..ce019e0039 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_CR4NS.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_CR4NS.h @@ -62,6 +62,8 @@ // // Limit Switches // +#define X_DIAG_PIN PB10 +#define Y_DIAG_PIN PB11 #ifndef Z_STOP_PIN #define Z_STOP_PIN PC14 #endif @@ -79,23 +81,19 @@ #define HEATER_BED_PIN PB2 // HOT BED #define FAN1_PIN PC1 // extruder fan -// -// Steppers -// + #if HAS_TMC_UART - - // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 - // Software serial #define X_SERIAL_TX_PIN PB12 - #define X_DIAG_PIN PB10 - #define Y_SERIAL_TX_PIN PB13 - #define Y_DIAG_PIN PB11 - #define Z_SERIAL_TX_PIN PB14 -#endif // HAS_TMC_UART + #define E0_SERIAL_TX_PIN PB15 + + // Reduce baud rate to improve software serial reliability + #ifndef TMC_BAUD_RATE + #define TMC_BAUD_RATE 19200 + #endif +#endif // // SD Card From 27621290b820f67df2755587601ff7d84ddc326f Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 4 Jun 2025 00:33:43 +0000 Subject: [PATCH 100/102] [cron] Bump distribution date (2025-06-04) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index b0c1c5acad..9ad04135eb 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-06-03" +//#define STRING_DISTRIBUTION_DATE "2025-06-04" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 98f11b7f3e..f3c366113f 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-06-03" + #define STRING_DISTRIBUTION_DATE "2025-06-04" #endif /** From fca60335e145ec6a1cbb154ef22a754e610faa86 Mon Sep 17 00:00:00 2001 From: Andrew <18502096+classicrocker883@users.noreply.github.com> Date: Tue, 3 Jun 2025 20:54:22 -0400 Subject: [PATCH 101/102] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20Nonlinear=20Extrus?= =?UTF-8?q?ion=20build=20(#27906)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Fixes #27902 --- Marlin/src/core/boards.h | 4 ++-- Marlin/src/module/stepper.h | 5 ++--- buildroot/tests/STM32F103RE_creality | 2 +- 3 files changed, 5 insertions(+), 6 deletions(-) diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 32ee85daab..adc03b657c 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -275,7 +275,7 @@ #define BOARD_MKS_SGEN_L_V2 2509 // MKS SGEN_L V2 #define BOARD_BTT_SKR_E3_TURBO 2510 // BigTreeTech SKR E3 Turbo #define BOARD_FLY_CDY 2511 // FLYmaker FLY CDY -#define BOARD_XTLW_CLIMBER_8TH_LPC 2512 // XTLW_CLIMBER_8TH_LPC +#define BOARD_XTLW_CLIMBER_8TH_LPC 2512 // XTLW Climber 8 // // SAM3X8E ARM Cortex-M3 @@ -283,7 +283,7 @@ #define BOARD_DUE3DOM 3000 // DUE3DOM for Arduino DUE #define BOARD_DUE3DOM_MINI 3001 // DUE3DOM MINI for Arduino DUE -#define BOARD_RADDS 3002 // RADDS +#define BOARD_RADDS 3002 // RADDS v1.5/v1.6 #define BOARD_RAMPS_FD_V1 3003 // RAMPS-FD v1 #define BOARD_RAMPS_FD_V2 3004 // RAMPS-FD v2 #define BOARD_RAMPS_SMART_EFB 3005 // RAMPS-SMART (Power outputs: Hotend, Fan, Bed) diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index 90cbedc9fc..3083ad2973 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -311,9 +311,8 @@ constexpr ena_mask_t enable_overlap[] = { struct { int32_t A, B, C; } q30; }; #if NONLINEAR_EXTRUSION_Q24 - protected: - int32_t edividend; - uint32_t scale_q24; + int32_t edividend; + uint32_t scale_q24; #endif } nonlinear_t; diff --git a/buildroot/tests/STM32F103RE_creality b/buildroot/tests/STM32F103RE_creality index 0855a71ee4..45821598e0 100755 --- a/buildroot/tests/STM32F103RE_creality +++ b/buildroot/tests/STM32F103RE_creality @@ -32,7 +32,7 @@ opt_enable DWIN_LCD_PROUI INDIVIDUAL_AXIS_HOMING_SUBMENU PID_AUTOTUNE_MENU PID_E SOUND_MENU_ITEM PRINTCOUNTER NOZZLE_PARK_FEATURE ADVANCED_PAUSE_FEATURE FILAMENT_RUNOUT_SENSOR \ BLTOUCH Z_SAFE_HOMING AUTO_BED_LEVELING_UBL MESH_EDIT_MENU LCD_BED_TRAMMING LIN_ADVANCE \ LIMITED_MAX_FR_EDITING LIMITED_MAX_ACCEL_EDITING LIMITED_JERK_EDITING BAUD_RATE_GCODE \ - CASE_LIGHT_ENABLE CASE_LIGHT_MENU CASE_LIGHT_NO_BRIGHTNESS + CASE_LIGHT_ENABLE CASE_LIGHT_MENU CASE_LIGHT_NO_BRIGHTNESS NONLINEAR_EXTRUSION opt_set PREHEAT_3_LABEL '"CUSTOM"' PREHEAT_3_TEMP_HOTEND 240 PREHEAT_3_TEMP_BED 60 PREHEAT_3_FAN_SPEED 128 BOOTSCREEN_TIMEOUT 1100 CASE_LIGHT_PIN 4 exec_test $1 $2 "Ender-3 S1 - ProUI (PIDTEMP)" "$3" From 127bc9489119dfc2204f8e3505cc9810914a1af0 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 5 Jun 2025 00:32:27 +0000 Subject: [PATCH 102/102] [cron] Bump distribution date (2025-06-05) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 9ad04135eb..3f7e62e416 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-06-04" +//#define STRING_DISTRIBUTION_DATE "2025-06-05" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index f3c366113f..c0455cbc51 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-06-04" + #define STRING_DISTRIBUTION_DATE "2025-06-05" #endif /**