Merge branch 'bugfix-2.1.x' into bugfix-2.1.x-Jan2

This commit is contained in:
Andrew 2025-12-29 02:35:51 -05:00 committed by GitHub
commit da52d1934e
No known key found for this signature in database
GPG key ID: B5690EEEBB952194
159 changed files with 1866 additions and 1534 deletions

View file

@ -121,7 +121,7 @@ Unsure where to begin contributing to Marlin? You can start by looking through t
### Pull Requests
Pull Requests should always be targeted to working branches (e.g., `bugfix-2.1.x` and/or `bugfix-1.1.x`) and never to release branches (e.g., `2.0.x` and/or `1.1.x`). If this is your first Pull Request, please read our [Guide to Pull Requests](https://marlinfw.org/docs/development/getting_started_pull_requests.html) and Github's [Pull Request](https://help.github.com/articles/creating-a-pull-request/) documentation.
Pull Requests should always be targeted to working branches (e.g., `bugfix-2.1.x` and/or `bugfix-1.1.x`) and never to release branches (e.g., `2.0.x` and/or `1.1.x`). If this is your first Pull Request, please read our [Guide to Pull Requests](https://marlinfw.org/docs/development/getting_started_pull_requests.html) and GitHub's [Pull Request](https://help.github.com/articles/creating-a-pull-request/) documentation.
* Fill in [the required template](pull_request_template.md).
* Don't include issue numbers in the PR title.

View file

@ -1,4 +1,5 @@
SCRIPTS_DIR := buildroot/share/scripts
MAKESCRIPTS_DIR := buildroot/share/make
CONTAINER_RT_BIN := docker
CONTAINER_RT_OPTS := --rm -v $(PWD):/code -v platformio-cache:/root/.platformio
CONTAINER_IMAGE := marlin-dev
@ -8,9 +9,8 @@ UNIT_TEST_CONFIG ?= default
ifeq ($(OS),Windows_NT)
# Windows: use `where` fall back through the three common names
PYTHON := $(shell which python 2>nul || which python3 2>nul || which py 2>nul)
# Windows: Use cmd tools to find pins files
PINS_RAW := $(shell cmd //c "dir /s /b Marlin\src\pins\*.h 2>nul | findstr /r ".*Marlin\\\\src\\\\pins\\\\.*\\\\pins_.*\.h"")
PINS := $(subst \,/,$(PINS_RAW))
# Windows: Use Python script to find pins files
PINS := $(shell $(PYTHON) $(MAKESCRIPTS_DIR)/find.py Marlin/src/pins -mindepth 2 -name 'pins_*.h')
else
# POSIX: use `command -v` prefer python3 over python
PYTHON := $(shell command -v python3 2>/dev/null || command -v python 2>/dev/null)
@ -36,6 +36,7 @@ help:
@echo "make validate-lines -j : Validate line endings, fails on trailing whitespace, etc."
@echo "make validate-pins -j : Validate all pins files, fails if any require reformatting"
@echo "make validate-boards -j : Validate boards.h and pins.h for standards compliance"
@echo "make validate-urls : Validate URLs in source files"
@echo "make tests-single-ci : Run a single test from inside the CI"
@echo "make tests-single-local : Run a single test locally"
@echo "make tests-single-local-docker : Run a single test locally, using docker"
@ -88,7 +89,7 @@ tests-all-local:
@$(PYTHON) -c "import yaml" 2>/dev/null || (echo 'pyyaml module is not installed. Install it with "$(PYTHON) -m pip install pyyaml"' && exit 1)
export PATH="./buildroot/bin/:./buildroot/tests/:${PATH}" \
&& export VERBOSE_PLATFORMIO=$(VERBOSE_PLATFORMIO) \
&& for TEST_TARGET in $$($(PYTHON) $(SCRIPTS_DIR)/get_test_targets.py) ; do \
&& for TEST_TARGET in $$($(PYTHON) $(MAKESCRIPTS_DIR)/get_test_targets.py) ; do \
if [ "$$TEST_TARGET" = "linux_native" ] && [ "$$(uname)" = "Darwin" ]; then \
echo "Skipping tests for $$TEST_TARGET on macOS" ; \
continue ; \
@ -151,7 +152,7 @@ validate-pins: format-pins
@echo "Validating pins files"
@git diff --exit-code || (git status && echo "\nError: Pins files are not formatted correctly. Run \"make format-pins\" to fix.\n" && exit 1)
.PHONY: format-lines validate-lines
.PHONY: format-lines validate-lines validate-urls
format-lines:
@echo "Formatting all sources"
@ -162,10 +163,14 @@ validate-lines:
@echo "Validating text formatting"
@npx prettier --check . --editorconfig --object-wrap preserve
validate-urls:
@echo "Checking URLs in source files"
@$(MAKESCRIPTS_DIR)/check-urls.sh
BOARDS_FILE := Marlin/src/core/boards.h
.PHONY: validate-boards
validate-boards:
@echo "Validating boards.h file"
@$(PYTHON) $(SCRIPTS_DIR)/validate_boards.py $(BOARDS_FILE) || (echo "\nError: boards.h file is not valid. Please check and correct it.\n" && exit 1)
@$(PYTHON) $(MAKESCRIPTS_DIR)/validate_boards.py $(BOARDS_FILE) || (echo "\nError: boards.h file is not valid. Please check and correct it.\n" && exit 1)

View file

@ -61,7 +61,7 @@
// @section info
// Author info of this build printed to the host during boot and M115
#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Original author or contributor.
#define STRING_CONFIG_H_AUTHOR "(MarlinFirmware)" // Original author or contributor.
//#define CUSTOM_VERSION_FILE Version.h // Path from the root directory (no quotes)
// @section machine
@ -468,7 +468,7 @@
//===========================================================================
//============================= Thermal Settings ============================
//===========================================================================
// @section temperature
// @section temperature sensors
/**
* Temperature Sensors:
@ -500,7 +500,7 @@
* 10 : 100 RS PRO 198-961
* 11 : 100 Keenovo AC silicone mats, most Wanhao i3 machines - beta 3950, 1%
* 12 : 100 Vishay 0603 SMD NTCS0603E3104FXT (#8) - calibrated for Makibox hot bed
* 13 : 100 Hisens up to 300°C - for "Simple ONE" & "All In ONE" hotend - beta 3950, 1%
* 13 : 100 Hisense up to 300°C - for "Simple ONE" & "All In ONE" hotend - beta 3950, 1%
* 14 : 100 (R25), 4092K (beta25), 4.7 pull-up, bed thermistor as used in Ender-5 S1
* 15 : 100 Calibrated for JGAurora A5 hotend
* 17 : 100 Dagoma NTC white thermistor
@ -652,6 +652,8 @@
#define TEMP_SENSOR_REDUNDANT_MAX_DIFF 10 // (°C) Temperature difference that will trigger a print abort.
#endif
// @section temperature
// Below this temperature the heater will be switched off
// because it probably indicates a broken thermistor wire.
#define HEATER_0_MINTEMP 5
@ -1860,15 +1862,12 @@
//#define DISABLE_V
//#define DISABLE_W
// Turn off the display blinking that warns about possible accuracy reduction
//#define DISABLE_REDUCED_ACCURACY_WARNING
// @section extruder
//#define DISABLE_E // Disable the extruder when not stepping
#define DISABLE_OTHER_EXTRUDERS // Keep only the active extruder enabled
// @section motion
// @section stepper drivers
// Invert the stepper direction. Change (or reverse the motor connector) if an axis goes the wrong way.
#define INVERT_X_DIR false
@ -1881,8 +1880,6 @@
//#define INVERT_V_DIR false
//#define INVERT_W_DIR false
// @section extruder
// For direct drive extruder v9 set to true, for geared extruder set to false.
#define INVERT_E0_DIR false
#define INVERT_E1_DIR false
@ -2527,7 +2524,7 @@
//
//#define TEMPERATURE_UNITS_SUPPORT
// @section temperature
// @section temperature presets
//
// Preheat Constants - Up to 10 are supported without changes

View file

@ -1526,6 +1526,9 @@
// @section lcd
// Turn off the display blinking that warns about possible accuracy reduction
//#define DISABLE_REDUCED_ACCURACY_WARNING
#if HAS_MANUAL_MOVE_MENU
#define MANUAL_FEEDRATE { 50*60, 50*60, 4*60, 2*60 } // (mm/min) Feedrates for manual moves along X, Y, Z, E from panel
#define FINE_MANUAL_MOVE 0.025 // (mm) Smallest manual move (< 0.1mm) applying to Z on most machines
@ -1887,17 +1890,21 @@
// SD Card Sorting options
#if ENABLED(SDCARD_SORT_ALPHA)
#define SDSORT_REVERSE false // Default to sorting file names in reverse order.
#define SDSORT_LIMIT 40 // Maximum number of sorted items (10-256). Costs 27 bytes each.
#define SDSORT_FOLDERS -1 // -1=above 0=none 1=below
#define SDSORT_GCODE false // Enable G-code M34 to set sorting behaviors: M34 S<-1|0|1> F<-1|0|1>
#define SDSORT_USES_RAM false // Pre-allocate a static array for faster pre-sorting.
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
#define SDSORT_CACHE_VFATS 2 // Maximum number of 13-byte VFAT entries to use for sorting.
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
#define SDSORT_QUICK true // Use Quick Sort as a sorting algorithm. Otherwise use Bubble Sort.
#define SDSORT_QUICK true // Use Quick Sort as a sorting algorithm. Otherwise use Bubble Sort.
#define SDSORT_REVERSE false // Default to sorting file names in reverse order.
#define SDSORT_LIMIT 40 // Maximum number of sorted items (10-256). Costs 27 bytes each.
#define SDSORT_FOLDERS -1 // -1=above 0=none 1=below
#define SDSORT_GCODE false // Enable G-code M34 to set sorting behaviors: M34 S<-1|0|1> F<-1|0|1>
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
#define SDSORT_USES_RAM false // Pre-allocate a static array for faster pre-sorting.
#if ENABLED(SDSORT_USES_RAM)
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
#if ENABLED(SDSORT_CACHE_NAMES)
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
#define SDSORT_CACHE_VFATS 2 // Maximum number of 13-byte VFAT entries to use for sorting.
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
#endif
#endif
#endif
// Allow international symbols in long filenames. To display correctly, the
@ -2351,7 +2358,7 @@
//#define WATCHDOG_RESET_MANUAL
#endif
// @section lcd
// @section baby-stepping
/**
* Babystepping enables movement of the axes by tiny increments without changing
@ -2604,13 +2611,15 @@
#endif
#endif // PTC_PROBE || PTC_BED || PTC_HOTEND
// @section extras
// @section gcode
//
// G60/G61 Position Save and Return
//
//#define SAVED_POSITIONS 1 // Each saved position slot costs 12 bytes
// @section motion
//
// G2/G3 Arc Support
//
@ -2642,6 +2651,8 @@
*/
//#define DIRECT_STEPPING
// @section calibrate
/**
* G38 Probe Target
*
@ -2848,7 +2859,7 @@
*/
//#define EXTRA_FAN_SPEED
// @section gcode
// @section firmware retraction
/**
* Firmware-based and LCD-controlled retract
@ -3665,7 +3676,7 @@
//#define PHOTO_RETRACT_MM 6.5 // (mm) E retract/recover for the photo move (M240 R S)
// Canon RC-1 or homebrew digital camera trigger
// Data from: https://www.doc-diy.net/photo/rc-1_hacked/
// Data from: https://web.archive.org/web/20250327153953/www.doc-diy.net/photo/rc-1_hacked/
//#define PHOTOGRAPH_PIN 23
// Canon Hack Development Kit
@ -4302,7 +4313,7 @@
* Developed by Chris Barr at Aus3D.
*
* Wiki: https://wiki.aus3d.com.au/Magnetic_Encoder
* Github: https://github.com/Aus3D/MagneticEncoder
* GitHub: https://github.com/Aus3D/MagneticEncoder
*
* Supplier: https://aus3d.com.au/products/magnetic-encoder-module
* Alternative Supplier: https://reliabuild3d.com/

View file

@ -41,7 +41,7 @@
* here we define this default string as the date where the latest release
* version was tagged.
*/
//#define STRING_DISTRIBUTION_DATE "2025-12-14"
//#define STRING_DISTRIBUTION_DATE "2025-12-25"
/**
* The protocol for communication to the host. Protocol indicates communication
@ -58,7 +58,7 @@
/**
* The SOURCE_CODE_URL is the location where users will find the Marlin Source
* Code which is installed on the device. In most cases unless the manufacturer
* has a distinct Github fork the Source Code URL should just be the main
* has a distinct GitHub fork the Source Code URL should just be the main
* Marlin repository.
*/
//#define SOURCE_CODE_URL "github.com/MarlinFirmware/Marlin"

View file

@ -96,7 +96,7 @@ void MarlinHAL::init() {
// Might disable other peripherals using the pin; to circumvent that please undefine one of the above things!
// The true culprit is the AVR ArduinoCore that enables peripherals redundantly.
// (USART1 on the GeeeTech GT2560)
// https://www.youtube.com/watch?v=jMgCvRXkexk
// https://youtube.be/jMgCvRXkexk
_ATmega_savePinAlternate(BEEPER_PIN);
OUT_WRITE(BEEPER_PIN, LOW);

View file

@ -24,7 +24,7 @@
/**
* Description: Tone function for Arduino Due and compatible (SAM3X8E)
* Derived from https://forum.arduino.cc/index.php?topic=136500.msg2903012#msg2903012
* Derived from https://forum.arduino.cc/t/arduino-due-and-tone/133302/13
*/
#ifdef ARDUINO_ARCH_SAM

View file

@ -24,7 +24,7 @@
/**
* Description: Tone function for ESP32
* Derived from https://forum.arduino.cc/index.php?topic=136500.msg2903012#msg2903012
* Derived from https://forum.arduino.cc/t/arduino-due-and-tone/133302/13
*/
#ifdef ARDUINO_ARCH_ESP32

View file

@ -69,10 +69,6 @@
#endif
#endif
#ifndef HAL_TIMER_RATE
#define HAL_TIMER_RATE GetStepperTimerClkFreq()
#endif
#ifndef STEP_TIMER
#define STEP_TIMER MF_TIMER_STEP
#endif

View file

@ -37,15 +37,18 @@
typedef uint32_t hal_timer_t;
#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT16_MAX)
extern uint32_t GetStepperTimerClkFreq();
#ifndef HAL_TIMER_RATE
extern uint32_t GetStepperTimerClkFreq();
#define HAL_TIMER_RATE GetStepperTimerClkFreq()
#endif
// Timer configuration constants
#define STEPPER_TIMER_RATE 2000000
#define TEMP_TIMER_FREQUENCY 1000
// Timer prescaler calculations
#define STEPPER_TIMER_PRESCALE (GetStepperTimerClkFreq() / STEPPER_TIMER_RATE) // Prescaler = 30
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) // (MHz) Stepper Timer ticks per µs
#define STEPPER_TIMER_PRESCALE ((HAL_TIMER_RATE) / (STEPPER_TIMER_RATE)) // Prescaler = 30
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) // (MHz) Stepper Timer ticks per µs
// Pulse Timer (counter) calculations
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer

View file

@ -53,7 +53,7 @@ Just searching for `SCB->VTOR` should yield some results. From there, you just n
> Some vendors publish incomplete source code. But they sometimes leave version control related files in the repo, which can contain previous version of files that were removed. Find these by including folders like `.git` or `.svn` in your search.
> [!NOTE]
> The example is based on the [Voxelab-64/Aquila_X2](https://github.com/Voxelab-64/Aquila_X2/blob/d1f23adf96920996b979bc31023d1dce236d05db/firmware/Sources/.svn/pristine/ec/ec82bcb480b511906bc3e6658450e3a803ab9813.svn-base#L96) which actually includes deleted files in its repo.
> The example is based on the [Voxelab-64/Aquila_X2](https://github.com/Voxelab-64/Aquila_X2/blob/main/firmware/Sources/.svn/pristine/ec/ec82bcb480b511906bc3e6658450e3a803ab9813.svn-base#L96) which actually includes deleted files in its repo.
2. Using a linker script

View file

@ -40,10 +40,6 @@
* SPI sharing pins. The SCK, MOSI & MISO pins can NOT be set/cleared with
* WRITE nor digitalWrite when the hardware SPI module within the LPC17xx is
* active. If any of these pins are shared then the software SPI must be used.
*
* A more sophisticated hardware SPI can be found at the following link.
* This implementation has not been fully debugged.
* https://github.com/MarlinFirmware/Marlin/tree/071c7a78f27078fd4aee9a3ef365fcf5e143531e
*/
#ifdef TARGET_LPC1768

View file

@ -22,7 +22,7 @@
/**
* digipot_mcp4451_I2C_routines.c
* Adapted from https://www-users.cs.york.ac.uk/~pcc/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html
* Adapted from https://www-users.york.ac.uk/~pcc1/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html
*/
#ifdef TARGET_LPC1768

View file

@ -23,7 +23,7 @@
/**
* digipot_mcp4451_I2C_routines.h
* Adapted from https://www-users.cs.york.ac.uk/~pcc/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html
* Adapted from https://www-users.york.ac.uk/~pcc1/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html
*/
#ifdef __cplusplus

View file

@ -21,7 +21,7 @@
*/
// adapted from I2C/master/master.c example
// https://www-users.cs.york.ac.uk/~pcc/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html
// https://www-users.york.ac.uk/~pcc1/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html
#ifdef TARGET_LPC1768

View file

@ -41,8 +41,8 @@ if pioutil.is_pio_build():
from ctypes import windll
from pathlib import PureWindowsPath
# getting list of drives
# https://stackoverflow.com/questions/827371/is-there-a-way-to-list-all-the-available-drive-letters-in-python
# Getting a list of drives
# https://stackoverflow.com/questions/827371/is-there-a-way-to-list-all-the-available-windows-drives
drives = []
bitmask = windll.kernel32.GetLogicalDrives()
for letter in string.ascii_uppercase:

View file

@ -21,7 +21,7 @@
*/
// adapted from I2C/master/master.c example
// https://www-users.cs.york.ac.uk/~pcc/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html
// https://www-users.york.ac.uk/~pcc1/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html
#ifdef __PLAT_NATIVE_SIM__

View file

@ -28,6 +28,7 @@
#include "../../inc/MarlinConfig.h"
#include "../shared/Delay.h"
#include "../../module/temperature.h" // For OVERSAMPLENR
extern "C" {
#include "pico/bootrom.h"
@ -41,50 +42,38 @@ extern "C" {
#include "msc_sd.h"
#endif
// Core 1 watchdog configuration
#define CORE1_MAX_RESETS 5 // Maximum number of Core 1 resets before halting system
// ------------------------
// Public Variables
// ------------------------
volatile uint32_t adc_accumulators[5] = {0}; // Accumulators for oversampling (sum of readings)
volatile uint8_t adc_counts[5] = {0}; // Count of readings accumulated per channel
volatile uint16_t adc_values[5] = {512, 512, 512, 512, 512}; // Final oversampled ADC values (averages) - initialized to mid-range
volatile uint16_t adc_values[5] = {4095, 4095, 4095, 4095, 4095}; // Averaged ADC values (single reading equivalent) - initialized to max (open circuit)
// Core 1 watchdog monitoring
// Core monitoring for watchdog
volatile uint32_t core0_last_heartbeat = 0; // Timestamp of Core 0's last activity
volatile uint32_t core1_last_heartbeat = 0; // Timestamp of Core 1's last activity
volatile bool core1_watchdog_triggered = false; // Flag to indicate Core 1 reset
volatile uint8_t core1_reset_count = 0; // Count of Core 1 resets - halt system if >= CORE1_MAX_RESETS
#if ENABLED(MARLIN_DEV_MODE)
volatile bool core1_freeze_test = false; // Flag to freeze Core 1 for watchdog testing
#endif
volatile uint8_t current_pin;
volatile bool MarlinHAL::adc_has_result;
volatile uint8_t adc_channels_enabled[5] = {false}; // Track which ADC channels are enabled
// Helper function for LED blinking patterns
void blink_led_pattern(uint8_t blink_count, uint32_t blink_duration_us = 100000) {
#if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED)
for (uint8_t i = 0; i < blink_count; i++) {
WRITE(LED_PIN, HIGH);
busy_wait_us(blink_duration_us);
WRITE(LED_PIN, LOW);
if (i < blink_count - 1) { // Don't delay after the last blink
busy_wait_us(blink_duration_us);
}
}
#endif
}
// Core 1 ADC reading task - dynamically reads all enabled channels with oversampling
void core1_adc_task() {
static uint32_t last_led_toggle = 0;
const uint8_t OVERSAMPLENR = 16; // Standard Marlin oversampling count
// Signal successful Core 1 startup/restart
SERIAL_ECHO_MSG("Core 1 ADC task started");
static uint32_t last_temp_update = 0;
while (true) {
// Update heartbeat timestamp at start of each scan cycle
core1_last_heartbeat = time_us_32();
#if ENABLED(MARLIN_DEV_MODE)
// Check if we should freeze for watchdog test
if (core1_freeze_test) {
// Stop updating heartbeat and spin forever
while (core1_freeze_test) {
busy_wait_us(100000); // 100ms delay
}
}
#endif
// Scan all enabled ADC channels
for (uint8_t channel = 0; channel < 5; channel++) {
@ -114,11 +103,9 @@ void core1_adc_task() {
adc_accumulators[channel] += reading;
adc_counts[channel]++;
// Update the averaged value with current accumulation (provides immediate valid data)
adc_values[channel] = adc_accumulators[channel] / adc_counts[channel];
// When we reach the full oversampling count, reset accumulator for next cycle
// When we reach the full oversampling count, calculate averaged value (Marlin ISR does its own oversampling)
if (adc_counts[channel] >= OVERSAMPLENR) {
adc_values[channel] = adc_accumulators[channel] / OVERSAMPLENR; // Return single-reading equivalent
adc_accumulators[channel] = 0;
adc_counts[channel] = 0;
}
@ -129,17 +116,19 @@ void core1_adc_task() {
}
}
// Core 1 LED indicator: Double blink every 2 seconds to show Core 1 is active
// Core 1 just provides ADC readings - don't trigger temperature updates from here
// Let Marlin's main temperature ISR on Core 0 handle the timing and updates
uint32_t now = time_us_32();
if (now - last_led_toggle >= 2000000) { // 2 seconds
last_led_toggle = now;
#if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED)
// Triple blink pattern if watchdog was triggered (shows Core 1 was reset)
if (core1_watchdog_triggered) {
core1_watchdog_triggered = false; // Clear flag
blink_led_pattern(3); // Triple blink for watchdog reset
} else {
blink_led_pattern(2); // Normal double blink
if (now - last_temp_update >= 100000) { // 100ms = 100000 microseconds
last_temp_update = now;
#if ENABLED(USE_WATCHDOG)
// Refresh watchdog here like AVR ISR does indirectly via temperature updates
// Use 2 second delay to allow watchdog_init to be called during boot
static uint32_t core1_start_time = 0;
if (core1_start_time == 0) core1_start_time = time_us_32();
if (time_us_32() - core1_start_time > 2000000) {
hal.watchdog_refresh(1); // Refresh from Core 1
}
#endif
}
@ -219,37 +208,42 @@ void MarlinHAL::reboot() { watchdog_reboot(0, 0, 1); }
void MarlinHAL::watchdog_init() {
#if DISABLED(DISABLE_WATCHDOG_INIT)
static_assert(WDT_TIMEOUT_US > 1000, "WDT Timeout is too small, aborting");
// Initialize Core 0 heartbeat
core0_last_heartbeat = time_us_32();
watchdog_enable(WDT_TIMEOUT_US/1000, true);
#endif
}
void MarlinHAL::watchdog_refresh() {
// If Core 1 has reset CORE1_MAX_RESETS+ times, stop updating watchdog to halt system
if (core1_reset_count >= CORE1_MAX_RESETS) {
SERIAL_ECHO_MSG("Core 1 reset limit exceeded (", core1_reset_count, " resets) - halting system for safety");
return; // Don't update watchdog - system will halt
void MarlinHAL::watchdog_refresh(const uint8_t core/*=0*/) {
if (core == 0) {
// Update Core 0 heartbeat
core0_last_heartbeat = time_us_32();
// Check if Core 1 is alive (2 second timeout)
if (time_us_32() - core1_last_heartbeat < 2000000) {
watchdog_update(); // Only refresh if Core 1 is responding
#if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED)
TOGGLE(LED_PIN); // Heartbeat indicator
#endif
}
// If Core 1 is stuck, don't refresh - let watchdog reset the system
}
else {
// Update Core 1 heartbeat
core1_last_heartbeat = time_us_32();
watchdog_update();
// Check Core 1 watchdog (15 second timeout)
uint32_t now = time_us_32();
if (now - core1_last_heartbeat > 15000000) { // 15 seconds
// Core 1 appears stuck - reset it
multicore_reset_core1();
multicore_launch_core1(core1_adc_task);
core1_watchdog_triggered = true; // Signal for LED indicator
core1_reset_count++; // Increment reset counter
SERIAL_ECHO_MSG("Core 1 ADC watchdog triggered - resetting Core 1 (attempt ", core1_reset_count, ")");
// Check if Core 0 is alive (2 second timeout)
if (time_us_32() - core0_last_heartbeat < 2000000) {
watchdog_update(); // Only refresh if Core 0 is responding
#if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED)
TOGGLE(LED_PIN); // Heartbeat indicator
#endif
}
// If Core 0 is stuck, don't refresh - let watchdog reset the system
}
#if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED)
// Core 0 LED indicator: Single toggle every watchdog refresh (shows Core 0 activity)
TOGGLE(LED_PIN);
#endif
}
#endif
#endif // USE_WATCHDOG
// ------------------------
// ADC
@ -290,13 +284,15 @@ void flashFirmware(const int16_t) { hal.reboot(); }
extern "C" {
void * _sbrk(int incr);
extern unsigned int __bss_end__; // end of bss section
extern unsigned int __StackLimit; // Lowest address the stack can grow to
}
// Return free memory between end of heap (or end bss) and whatever is current
// Return free memory between end of heap and start of stack
int freeMemory() {
int free_memory, heap_end = (int)_sbrk(0);
return (int)&free_memory - (heap_end ?: (int)&__bss_end__);
void* heap_end = _sbrk(0);
// Use the linker-provided stack limit instead of a local variable
// __StackLimit is the lowest address the stack can grow to
return (char*)&__StackLimit - (char*)heap_end;
}
#endif // __PLAT_RP2040__

View file

@ -51,6 +51,28 @@
#include "MarlinSerial.h"
#if !WITHIN(SERIAL_PORT, -1, 1)
#error "SERIAL_PORT must be from -1 to 1."
#endif
#ifdef SERIAL_PORT_2
#if !WITHIN(SERIAL_PORT_2, -1, 1)
#error "SERIAL_PORT_2 must be from -1 to 1."
#endif
#endif
#ifdef SERIAL_PORT_3
#if !WITHIN(SERIAL_PORT_3, -1, 1)
#error "SERIAL_PORT_3 must be from -1 to 1."
#endif
#endif
#ifdef LCD_SERIAL_PORT
#if !WITHIN(LCD_SERIAL_PORT, -1, 1)
#error "LCD_SERIAL_PORT must be from -1 to 1."
#endif
#endif
// ------------------------
// Defines
// ------------------------
@ -131,7 +153,7 @@ public:
// Watchdog
static void watchdog_init() IF_DISABLED(USE_WATCHDOG, {});
static void watchdog_refresh() IF_DISABLED(USE_WATCHDOG, {});
static void watchdog_refresh(const uint8_t=0) IF_DISABLED(USE_WATCHDOG, {});
static void init(); // Called early in setup()
static void init_board() {} // Called less early in setup()

View file

@ -30,10 +30,40 @@
#include "../../feature/e_parser.h"
#endif
#define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X)
#define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X)
#if WITHIN(SERIAL_PORT, 0, 3)
IMPLEMENT_SERIAL(SERIAL_PORT);
#include <HardwareSerial.h>
// Marlin uses: -1=USB, 0=UART0, 1=UART1
// Arduino uses: Serial=USB, Serial1=UART0, Serial2=UART1
//
// To remap Arduino's numbering to Marlin's convention, we create MarlinSerial0/MarlinSerial1
// as new UART instances with custom pins.
//
// We use distinct names (MarlinSerial0/MarlinSerial1) to avoid symbol conflicts with
// the Arduino framework's pre-defined Serial1/Serial2 objects, which use the same
// underlying hardware (_UART0_ and _UART1_).
// Create Serial0 as UART0 with custom or default pins
arduino::UART MarlinSerial0(
#if PINS_EXIST(SERIAL0_TX, SERIAL0_RX)
SERIAL0_TX_PIN, SERIAL0_RX_PIN // Custom pins for UART0 (Marlin Serial0)
#else
0, 1 // Default UART0 pins (GP0/GP1)
#endif
);
// Not using PINS_EXIST(SERIAL1_TX, SERIAL1_RX) because SERIAL1_TX and SERIAL1_RX
// are defined in framework-arduino-mbed/variants/RASPBERRY_PI_PICO/pins_arduino.h
// Create Serial1 as UART1 with custom or default pins
#if defined(SERIAL1_TX_PIN) && defined(SERIAL1_RX_PIN)
arduino::UART MarlinSerial1(SERIAL1_TX_PIN, SERIAL1_RX_PIN); // Custom pins for UART1 (Marlin Serial1)
#endif
// Wrap the serial ports for Marlin
DefaultSerial0 MSerial0(false, MarlinSerial0); // Marlin Serial0 = UART0
#if defined(SERIAL1_TX_PIN) && defined(SERIAL1_RX_PIN)
DefaultSerial1 MSerial1(false, MarlinSerial1); // Marlin Serial1 = UART1
#endif
DefaultSerial2 MSerial2(false, Serial); // Marlin Serial2 = USB (-1)
#endif // __PLAT_RP2040__

View file

@ -29,20 +29,50 @@
#include "../../core/serial_hook.h"
typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial1;
extern DefaultSerial1 MSerial0;
/**
* Serial Port Configuration for RP2040 (Raspberry Pi Pico)
*
* Arduino-Pico Core Serial Objects:
* - Serial: USB Serial (CDC ACM)
* - Serial1: Hardware UART0
* - Serial2: Hardware UART1
* - SerialUSB: Alias for Serial (USB)
*
* Marlin Serial Wrappers:
* - MSerial0: Wrapper for MarlinSerial0 (UART0), used as Serial0
* - MSerial1: Wrapper for MarlinSerial1 (UART1), declared dynamically if used
* - MSerial2: Wrapper for Serial (USB)
* - USBSerial: Wrapper for SerialUSB (USB)
*
* How it all joins together:
* - Configuration defines SERIAL_PORT, SERIAL_PORT_2, etc. (-1 to 1 range)
* - shared/serial_ports.h maps these to MYSERIAL1, MYSERIAL2, etc.
* - MYSERIAL1 uses MSerialX based on the port index
* - USB ports (-1) use USB_SERIAL_PORT (MSerial2)
*/
// Forward declare our custom Serial objects (defined in MarlinSerial.cpp)
namespace arduino { class UART; }
extern arduino::UART MarlinSerial0; // Always declared
extern arduino::UART MarlinSerial1; // Custom Marlin Serial1 to avoid conflict
typedef ForwardSerial1Class< decltype(MarlinSerial0) > DefaultSerial0;
extern DefaultSerial0 MSerial0;
typedef ForwardSerial1Class< decltype(MarlinSerial1) > DefaultSerial1;
extern DefaultSerial1 MSerial1;
typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial2;
extern DefaultSerial2 MSerial2;
typedef ForwardSerial1Class<decltype(SerialUSB)> USBSerialType;
extern USBSerialType USBSerial;
#define Serial0 Serial
#define _DECLARE_SERIAL(X) \
typedef ForwardSerial1Class<decltype(Serial##X)> DefaultSerial##X; \
typedef ForwardSerial1Class<decltype(MarlinSerial##X)> DefaultSerial##X; \
extern DefaultSerial##X MSerial##X
#define DECLARE_SERIAL(X) _DECLARE_SERIAL(X)
#define SERIAL_INDEX_MIN 0
#define SERIAL_INDEX_MAX 6
#define USB_SERIAL_PORT(...) MSerial0
#define SERIAL_INDEX_MAX 1
#define USB_SERIAL_PORT(...) MSerial2
#include "../shared/serial_ports.h"
#if defined(LCD_SERIAL_PORT) && ANY(HAS_DGUS_LCD, EXTENSIBLE_UI)

View file

@ -25,7 +25,7 @@
* Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician)
*/
// adapted from I2C/master/master.c example
// https://www-users.cs.york.ac.uk/~pcc/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html
// https://www-users.york.ac.uk/~pcc1/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html
#ifdef __SAMD21__

View file

@ -81,10 +81,6 @@
#define MCU_TEMP_TIMER 14 // TIM7 is consumed by Software Serial if used.
#endif
#ifndef HAL_TIMER_RATE
#define HAL_TIMER_RATE GetStepperTimerClkFreq()
#endif
#ifndef STEP_TIMER
#define STEP_TIMER MCU_STEP_TIMER
#endif

View file

@ -48,13 +48,18 @@
#define TIMER_INDEX_(T) TIMER##T##_INDEX // TIMER#_INDEX enums (timer_index_t) depend on TIM#_BASE defines.
#define TIMER_INDEX(T) TIMER_INDEX_(T) // Convert Timer ID to HardwareTimer_Handle index.
#define TEMP_TIMER_FREQUENCY 1000 // Temperature::isr() is expected to be called at around 1kHz
#ifndef HAL_TIMER_RATE
extern uint32_t GetStepperTimerClkFreq();
#define HAL_TIMER_RATE GetStepperTimerClkFreq()
#endif
// TODO: get rid of manual rate/prescale/ticks/cycles taken for procedures in stepper.cpp
#define STEPPER_TIMER_RATE 2'000'000 // 2 Mhz
extern uint32_t GetStepperTimerClkFreq();
#define STEPPER_TIMER_PRESCALE (GetStepperTimerClkFreq() / (STEPPER_TIMER_RATE))
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) // (MHz) Stepper Timer ticks per µs
// Timer configuration constants
#define STEPPER_TIMER_RATE 2000000
#define TEMP_TIMER_FREQUENCY 1000 // Temperature::isr() should run at ~1kHz
// Timer prescaler calculations
#define STEPPER_TIMER_PRESCALE ((HAL_TIMER_RATE) / (STEPPER_TIMER_RATE))
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) // (ticks/μs) Stepper Timer ticks per µs
// Pulse Timer (counter) calculations
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer

View file

@ -85,7 +85,7 @@
}
else {
// Enable DWT counter
// From https://stackoverflow.com/a/41188674/1469714
// From https://stackoverflow.com/questions/36378280/stm32-how-to-enable-dwt-cycle-counter/41188674#41188674
HW_REG(_DEM_CR) = HW_REG(_DEM_CR) | 0x01000000; // Enable trace
#if __CORTEX_M == 7
HW_REG(_LAR) = 0xC5ACCE55; // Unlock access to DWT registers, see https://developer.arm.com/documentation/ihi0029/e/ section B2.3.10

View file

@ -66,7 +66,7 @@ void * hook_get_usagefault_vector_address(unsigned vtor) { return (void*)(vtor +
void * hook_get_reserved_vector_address(unsigned vtor) { return (void*)(vtor + 0x07); }
// Common exception frame for ARM, should work for all ARM CPU
// Described here (modified for convenience): https://interrupt.memfault.com/blog/cortex-m-fault-debug
// Described here (modified for convenience): https://interrupt.memfault.com/blog/cortex-m-hardfault-debug
struct __attribute__((packed)) ContextStateFrame {
uint32_t r0;
uint32_t r1;

View file

@ -158,16 +158,16 @@ public:
MString& append_P(PGM_P const s) { int sz = length(); if (sz < SIZE) strlcpy_P(str + sz, s, SIZE - sz + 1); debug(F("pstring")); return *this; }
MString& append(FSTR_P const f) { return append_P(FTOP(f)); }
MString& append(const bool &b) { return append(b ? F("true") : F("false")); }
MString& append(const char c) { int sz = length(); if (sz < SIZE) { str[sz] = c; if (sz < SIZE - 1) str[sz + 1] = '\0'; } return *this; }
MString& append(const char c) { int sz = length(); if (sz < SIZE) { str[sz] = c; if (sz < SIZE - 1) str[sz + 1] = '\0'; } debug(F("char")); return *this; }
#if ENABLED(FASTER_APPEND)
MString& append(const int8_t &i) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%d", i); return *this; }
MString& append(const short &i) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%d", i); return *this; }
MString& append(const int &i) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%d", i); return *this; }
MString& append(const long &l) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%ld", l); return *this; }
MString& append(const unsigned char &i) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%u", i); return *this; }
MString& append(const unsigned short &i) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%u", i); return *this; }
MString& append(const unsigned int &i) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%u", i); return *this; }
MString& append(const unsigned long &l) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%lu", l); return *this; }
MString& append(const int8_t &i) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%d", i); debug(F("int8_t")); return *this; }
MString& append(const short &i) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%d", i); debug(F("short")); return *this; }
MString& append(const int &i) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%d", i); debug(F("int")); return *this; }
MString& append(const long &l) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%ld", l); debug(F("long")); return *this; }
MString& append(const unsigned char &i) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%u", i); debug(F("uchar")); return *this; }
MString& append(const unsigned short &i) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%u", i); debug(F("ushort")); return *this; }
MString& append(const unsigned int &i) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%u", i); debug(F("uint")); return *this; }
MString& append(const unsigned long &l) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%lu", l); debug(F("ulong")); return *this; }
#else
MString& append(const int8_t &i) { char buf[ 5]; sprintf(buf, "%d", i); return append(buf); }
MString& append(const short &i) { char buf[12]; sprintf(buf, "%d", i); return append(buf); }

View file

@ -557,7 +557,7 @@ struct XYval {
#endif
// Length reduced to one dimension
FI constexpr T magnitude() const { return (T)sqrtf(x*x + y*y); }
FI constexpr T magnitude() const { return (T)SQRT(x*x + y*y); }
// Pointer to the data as a simple array
explicit FI operator T* () { return pos; }
// If any element is true then it's true
@ -734,7 +734,7 @@ struct XYZval {
#endif
// Length reduced to one dimension
FI constexpr T magnitude() const { return (T)TERN(HAS_X_AXIS, sqrtf(NUM_AXIS_GANG(x*x, + y*y, + z*z, + i*i, + j*j, + k*k, + u*u, + v*v, + w*w)), 0); }
FI constexpr T magnitude() const { return (T)TERN(HAS_X_AXIS, SQRT(NUM_AXIS_GANG(x*x, + y*y, + z*z, + i*i, + j*j, + k*k, + u*u, + v*v, + w*w)), 0); }
// Pointer to the data as a simple array
explicit FI operator T* () { return pos; }
// If any element is true then it's true
@ -905,7 +905,7 @@ struct XYZEval {
#endif
// Length reduced to one dimension
FI constexpr T magnitude() const { return (T)sqrtf(LOGICAL_AXIS_GANG(+ e*e, + x*x, + y*y, + z*z, + i*i, + j*j, + k*k, + u*u, + v*v, + w*w)); }
FI constexpr T magnitude() const { return (T)SQRT(LOGICAL_AXIS_GANG(+ e*e, + x*x, + y*y, + z*z, + i*i, + j*j, + k*k, + u*u, + v*v, + w*w)); }
// Pointer to the data as a simple array
explicit FI operator T* () { return pos; }
// If any element is true then it's true

View file

@ -38,7 +38,6 @@
#include "mmu3_progress_converter.h"
#include "mmu3_reporting.h"
#include "strlen_cx.h"
#include "SpoolJoin.h"
#include "../../inc/MarlinConfig.h"

View file

@ -39,26 +39,26 @@
namespace MMU3 {
// On MK3 we cannot do actual power cycle on HW. Instead trigger a hardware reset.
void power_on() {
#if PIN_EXISTS(MMU_RST)
OUT_WRITE(MMU_RST_PIN, HIGH);
#endif
power_reset();
}
// On MK3 we cannot do actual power cycle on HW. Instead trigger a hardware reset.
void power_on() {
#if PIN_EXISTS(MMU_RST)
OUT_WRITE(MMU_RST_PIN, HIGH);
#endif
power_reset();
}
void power_off() {}
void power_off() {}
void power_reset() {
#if PIN_EXISTS(MMU_RST) // HW - pulse reset pin
WRITE(MMU_RST_PIN, LOW);
safe_delay(100);
WRITE(MMU_RST_PIN, HIGH);
#else
mmu3.reset(MMU3::Software); // TODO: Needs redesign. This power implementation shouldn't know anything about the MMU itself
#endif
// otherwise HW reset is not available
}
void power_reset() {
#if PIN_EXISTS(MMU_RST) // HW - pulse reset pin
WRITE(MMU_RST_PIN, LOW);
safe_delay(100);
WRITE(MMU_RST_PIN, HIGH);
#else
mmu3.reset(MMU3::Software); // TODO: Needs redesign. This power implementation shouldn't know anything about the MMU itself
#endif
// otherwise HW reset is not available
}
} // MMU3

View file

@ -26,11 +26,7 @@
*/
namespace MMU3 {
void power_on();
void power_off();
void power_reset();
} // MMU3
void power_on();
void power_off();
void power_reset();
}

View file

@ -353,17 +353,18 @@ namespace MMU3 {
// Render the choices
//if (two_choices) {
// lcd_show_choices_prompt_P(
// LCD_LEFT_BUTTON_CHOICE,
// PrusaErrorButtonTitle(button_op_middle),
// GET_TEXT(MSG_BTN_MORE),
// 18, nullptr
// LCD_LEFT_BUTTON_CHOICE,
// PrusaErrorButtonTitle(button_op_middle),
// GET_TEXT(MSG_BTN_MORE),
// 18, nullptr
// );
//}
//else {
// lcd_show_choices_prompt_P(LCD_MIDDLE_BUTTON_CHOICE,
// PrusaErrorButtonTitle(button_op_middle),
// PrusaErrorButtonTitle(button_op_right),
// 9, GET_TEXT(MSG_BTN_MORE)
// lcd_show_choices_prompt_P(
// LCD_MIDDLE_BUTTON_CHOICE,
// PrusaErrorButtonTitle(button_op_middle),
// PrusaErrorButtonTitle(button_op_right),
// 9, GET_TEXT(MSG_BTN_MORE)
// );
//}
@ -526,7 +527,7 @@ namespace MMU3 {
#if HAS_WIRED_LCD
// Set the cursor position each time in case some other
// part of the firmware changes the cursor position
lcd_insert_char_into_status(col, sensorState ? LCD_STR_SOLID_BLOCK[0] : '-');
lcd_replace_status_char(col, sensorState ? LCD_STR_SOLID_BLOCK[0] : '-');
if (ui.lcdDrawUpdate == LCDViewAction::LCDVIEW_NONE)
ui.draw_status_message(false);
#endif
@ -535,7 +536,7 @@ namespace MMU3 {
void TryLoadUnloadReporter::Progress(bool sensorState) {
// Always round up, you can only have 'whole' pixels. (floor is also an option)
dpixel1 = ceil((stepper_get_machine_position_E_mm() - planner_get_current_position_E()) * pixel_per_mm);
if (dpixel1 - dpixel0) {
if (dpixel1 != dpixel0) {
dpixel0 = dpixel1;
if (lcd_cursor_col > (LCD_WIDTH - 1)) lcd_cursor_col = LCD_WIDTH - 1;
Render(lcd_cursor_col++, sensorState);

View file

@ -37,7 +37,6 @@
#include <avr/pgmspace.h>
#endif
#include "buttons.h"
#include "../strlen_cx.h"
#include "../ultralcd.h"
namespace MMU3 {

View file

@ -1,30 +0,0 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* strlen_cx.h
*/
constexpr inline int strlen_constexpr(const char *str) {
return *str ? 1 + strlen_constexpr(str + 1) : 0;
}

View file

@ -37,181 +37,175 @@
#include "../../gcode/gcode.h"
#include "../../lcd/marlinui.h"
//! @brief Show a two-choice prompt on the last line of the LCD
//! @param selected Show first choice as selected if true, the second otherwise
//! @param first_choice text caption of first possible choice
//! @param second_choice text caption of second possible choice
//! @param second_col column on LCD where second choice is rendered.
//! @param third_choice text caption of third, optional, choice.
void lcd_show_choices_prompt_P(uint8_t selected, const char *first_choice, const char *second_choice, uint8_t second_col, const char *third_choice) {
lcd_put_lchar(0, 3, selected == LCD_LEFT_BUTTON_CHOICE ? '>' : ' ');
lcd_put_u8str(first_choice);
lcd_put_lchar(second_col, 3, selected == LCD_MIDDLE_BUTTON_CHOICE ? '>' : ' ');
lcd_put_u8str(second_choice);
if (third_choice) {
lcd_put_lchar(18, 3, selected == LCD_RIGHT_BUTTON_CHOICE ? '>' : ' ');
lcd_put_u8str(third_choice);
//! @brief Show a two-choice prompt on the last line of the LCD
//! @param selected Show first choice as selected if true, the second otherwise
//! @param first_choice text caption of first possible choice
//! @param second_choice text caption of second possible choice
//! @param second_col column on LCD where second choice is rendered.
//! @param third_choice text caption of third, optional, choice.
void lcd_show_choices_prompt_P(uint8_t selected, const char *first_choice, const char *second_choice, uint8_t second_col, const char *third_choice) {
lcd_put_lchar(0, 3, selected == LCD_LEFT_BUTTON_CHOICE ? '>' : ' ');
lcd_put_u8str(first_choice);
lcd_put_lchar(second_col, 3, selected == LCD_MIDDLE_BUTTON_CHOICE ? '>' : ' ');
lcd_put_u8str(second_choice);
if (third_choice) {
lcd_put_lchar(18, 3, selected == LCD_RIGHT_BUTTON_CHOICE ? '>' : ' ');
lcd_put_u8str(third_choice);
}
}
void lcd_space(uint8_t n) {
while (n--) lcd_put_lchar(' ');
}
// Print extruder status (5 chars total)
// Scenario 1: "F?"
// There is no filament loaded and no tool change is in progress
// Scenario 2: "F[nr.]"
// [nr.] ranges from 1 to 5.
// Shows which filament is loaded. No tool change is in progress
// Scenario 3: "?>[nr.]"
// [nr.] ranges from 1 to 5.
// There is no filament currently loaded, but [nr.] is currently being loaded via tool change
// Scenario 4: "[nr.]>?"
// [nr.] ranges from 1 to 5.
// This scenario indicates a bug in the firmware if ? is on the right side
// Scenario 5: "[nr1.]>[nr2.]"
// [nr1.] ranges from 1 to 5.
// [nr2.] ranges from 1 to 5.
// Filament [nr1.] was loaded, but [nr2.] is currently being loaded via tool change
// Scenario 6: "?>?"
// This scenario should not be possible and indicates a bug in the firmware
uint8_t lcdui_print_extruder(void) {
uint8_t chars = 1;
lcd_space(1);
if (mmu3.get_current_tool() == mmu3.get_tool_change_tool()) {
lcd_put_lchar('F');
lcd_put_lchar(mmu3.get_current_tool() == (uint8_t)MMU3::FILAMENT_UNKNOWN ? '?' : mmu3.get_current_tool() + '1');
chars += 2;
}
else {
lcd_put_lchar(mmu3.get_current_tool() == (uint8_t)MMU3::FILAMENT_UNKNOWN ? '?' : mmu3.get_current_tool() + '1');
lcd_put_lchar('>');
lcd_put_lchar(mmu3.get_tool_change_tool() == (uint8_t)MMU3::FILAMENT_UNKNOWN ? '?' : mmu3.get_tool_change_tool() + '1');
chars += 3;
}
return chars;
}
bool is_whitespace_P(const char *c_addr) {
const char c = pgm_read_byte(c_addr);
return c == ' ' || c == '\t' || c == '\r' || c == '\n';
}
bool is_punctuation_P(const char *c_addr) {
const char c = pgm_read_byte(c_addr);
return c == '.' || c == ',' || c == ':' || c == ';' || c == '?' || c == '!' || c == '/';
}
/**
* @brief show full screen message
*
* This function is non-blocking
* @param msg message to be displayed from PROGMEM
* @return rest of the text (to be displayed on next page)
*/
static FSTR_P const lcd_display_message_fullscreen_async(FSTR_P const fmsg) {
PGM_P msg = FTOP(fmsg);
PGM_P msgend = msg;
//bool multi_screen = false;
for (uint8_t row = 0; row < LCD_HEIGHT; ++row) {
if (pgm_read_byte(msgend) == 0) break;
SETCURSOR(0, row);
// Previous row ended with a complete word, so the first character in the
// next row is a whitespace. We can skip the whitespace on a new line.
if (is_whitespace_P(msg) && ++msg == nullptr) break; // End of the message.
uint8_t linelen = (strlen_P(msg) > LCD_WIDTH) ? LCD_WIDTH : strlen_P(msg);
PGM_P const msgend2 = msg + linelen;
msgend = msgend2;
if (row == 3 && linelen == LCD_WIDTH) {
// Last line of the display, full line should be displayed.
// Find out, whether this message will be split into multiple screens.
//multi_screen = pgm_read_byte(msgend) != 0;
// We do not need this...
//if (multi_screen) msgend = (msgend2 -= 2);
}
}
void lcd_space(uint8_t n) {
while (n--) lcd_put_lchar(' ');
}
// Print extruder status (5 chars total)
// Scenario 1: "F?"
// There is no filament loaded and no tool change is in progress
// Scenario 2: "F[nr.]"
// [nr.] ranges from 1 to 5.
// Shows which filament is loaded. No tool change is in progress
// Scenario 3: "?>[nr.]"
// [nr.] ranges from 1 to 5.
// There is no filament currently loaded, but [nr.] is currently being loaded via tool change
// Scenario 4: "[nr.]>?"
// [nr.] ranges from 1 to 5.
// This scenario indicates a bug in the firmware if ? is on the right side
// Scenario 5: "[nr1.]>[nr2.]"
// [nr1.] ranges from 1 to 5.
// [nr2.] ranges from 1 to 5.
// Filament [nr1.] was loaded, but [nr2.] is currently being loaded via tool change
// Scenario 6: "?>?"
// This scenario should not be possible and indicates a bug in the firmware
uint8_t lcdui_print_extruder(void) {
uint8_t chars = 1;
lcd_space(1);
if (mmu3.get_current_tool() == mmu3.get_tool_change_tool()) {
lcd_put_lchar('F');
lcd_put_lchar(mmu3.get_current_tool() == (uint8_t)MMU3::FILAMENT_UNKNOWN ? '?' : mmu3.get_current_tool() + '1');
chars += 2;
if (pgm_read_byte(msgend) != 0 && !is_whitespace_P(msgend) && !is_punctuation_P(msgend)) {
// Splitting a word. Find the start of the current word.
while (msgend > msg && !is_whitespace_P(msgend - 1)) --msgend;
if (msgend == msg) msgend = msgend2; // Found a single long word, which cannot be split. Just cut it.
}
else {
lcd_put_lchar(mmu3.get_current_tool() == (uint8_t)MMU3::FILAMENT_UNKNOWN ? '?' : mmu3.get_current_tool() + '1');
lcd_put_lchar('>');
lcd_put_lchar(mmu3.get_tool_change_tool() == (uint8_t)MMU3::FILAMENT_UNKNOWN ? '?' : mmu3.get_tool_change_tool() + '1');
chars += 3;
}
return chars;
}
bool pgm_is_whitespace(const char *c_addr) {
const char c = pgm_read_byte(c_addr);
return c == ' ' || c == '\t' || c == '\r' || c == '\n';
}
bool pgm_is_interpunction(const char *c_addr) {
const char c = pgm_read_byte(c_addr);
return c == '.' || c == ',' || c == ':' || c == ';' || c == '?' || c == '!' || c == '/';
}
/**
* @brief show full screen message
*
* This function is non-blocking
* @param msg message to be displayed from PROGMEM
* @return rest of the text (to be displayed on next page)
*/
static FSTR_P const lcd_display_message_fullscreen_nonBlocking(FSTR_P const fmsg) {
PGM_P msg = FTOP(fmsg);
PGM_P msgend = msg;
//bool multi_screen = false;
for (uint8_t row = 0; row < LCD_HEIGHT; ++row) {
if (pgm_read_byte(msgend) == 0) break;
SETCURSOR(0, row);
// Previous row ended with a complete word, so the first character in the
// next row is a whitespace. We can skip the whitespace on a new line.
if (pgm_is_whitespace(msg) && ++msg == nullptr) break; // End of the message.
uint8_t linelen = (strlen_P(msg) > LCD_WIDTH) ? LCD_WIDTH : strlen_P(msg);
PGM_P const msgend2 = msg + linelen;
msgend = msgend2;
if (row == 3 && linelen == LCD_WIDTH) {
// Last line of the display, full line should be displayed.
// Find out, whether this message will be split into multiple screens.
//multi_screen = pgm_read_byte(msgend) != 0;
// We do not need this...
//if (multi_screen) msgend = (msgend2 -= 2);
for (; msg < msgend; ++msg) {
const char c = char(pgm_read_byte(msg));
if (c == '\n') {
// Abort early if '\n' is encountered.
// This character is used to force the following words to be printed on the next line.
break;
}
if (pgm_read_byte(msgend) != 0 && !pgm_is_whitespace(msgend) && !pgm_is_interpunction(msgend)) {
// Splitting a word. Find the start of the current word.
while (msgend > msg && !pgm_is_whitespace(msgend - 1)) --msgend;
if (msgend == msg) msgend = msgend2; // Found a single long word, which cannot be split. Just cut it.
}
for (; msg < msgend; ++msg) {
const char c = char(pgm_read_byte(msg));
if (c == '\n') {
// Abort early if '\n' is encountered.
// This character is used to force the following words to be printed on the next line.
break;
lcd_put_lchar(c);
}
}
return FPSTR(msgend);
}
FSTR_P const lcd_display_message_fullscreen(FSTR_P const fmsg) {
// Disable update of the screen by the usual lcd_update(0) routine.
#if HAS_WIRED_LCD
//ui.lcdDrawUpdate = LCDViewAction::LCDVIEW_NONE;
ui.clear_lcd();
return lcd_display_message_fullscreen_async(fmsg);
#else
return fmsg
#endif
}
/**
* @brief show full screen message and wait
*
* This function is blocking.
* @param msg message to be displayed from PROGMEM
*/
void lcd_show_fullscreen_message_and_wait(FSTR_P const fmsg) {
LcdUpdateDisabler lcdUpdateDisabler;
FSTR_P fmsg_next = lcd_display_message_fullscreen(fmsg);
const bool multi_screen = fmsg_next != nullptr;
ui.use_click();
KEEPALIVE_STATE(PAUSED_FOR_USER);
// Until confirmed by a button click.
for (;;) {
if (fmsg_next == nullptr) {
// Display the confirm char.
//lcd_put_lchar(LCD_WIDTH - 2, LCD_HEIGHT - 2, LCD_STR_CONFIRM[0]);
}
// Wait for 5 seconds before displaying the next text.
for (uint8_t i = 0; i < 100; ++i) {
marlin.idle(true);
safe_delay(50);
if (ui.use_click()) {
if (fmsg_next == nullptr) {
KEEPALIVE_STATE(IN_HANDLER);
return ui.go_back();
}
lcd_put_lchar(c);
if (!multi_screen) break;
if (fmsg_next == nullptr) fmsg_next = fmsg;
fmsg_next = lcd_display_message_fullscreen(fmsg_next);
}
}
// We do not need this part...
//if (multi_screen) {
// // Display the double down arrow.
// lcd_put_lchar(LCD_WIDTH - 2, LCD_HEIGHT - 2, LCD_STR_ARROW_2_DOWN[0]);
// if (fmsg_next == nullptr) fmsg_next = fmsg;
// fmsg_next = lcd_display_message_fullscreen(fmsg_next);
//}
//return multi_screen ? msgend : nullptr;
return FPSTR(msgend);
}
}
FSTR_P const lcd_display_message_fullscreen(FSTR_P const fmsg) {
// Disable update of the screen by the usual lcd_update(0) routine.
#if HAS_WIRED_LCD
//ui.lcdDrawUpdate = LCDViewAction::LCDVIEW_NONE;
ui.clear_lcd();
return lcd_display_message_fullscreen_nonBlocking(fmsg);
#else
return fmsg
#endif
}
/**
* @brief show full screen message and wait
*
* This function is blocking.
* @param msg message to be displayed from PROGMEM
*/
void lcd_show_fullscreen_message_and_wait(FSTR_P const fmsg) {
LcdUpdateDisabler lcdUpdateDisabler;
FSTR_P fmsg_next = lcd_display_message_fullscreen(fmsg);
const bool multi_screen = fmsg_next != nullptr;
ui.use_click();
KEEPALIVE_STATE(PAUSED_FOR_USER);
// Until confirmed by a button click.
for (;;) {
if (fmsg_next == nullptr) {
// Display the confirm char.
//lcd_put_lchar(LCD_WIDTH - 2, LCD_HEIGHT - 2, LCD_STR_CONFIRM[0]);
}
// Wait for 5 seconds before displaying the next text.
for (uint8_t i = 0; i < 100; ++i) {
marlin.idle(true);
safe_delay(50);
if (ui.use_click()) {
if (fmsg_next == nullptr) {
KEEPALIVE_STATE(IN_HANDLER);
return ui.go_back();
}
if (!multi_screen) break;
if (fmsg_next == nullptr) fmsg_next = fmsg;
fmsg_next = lcd_display_message_fullscreen(fmsg_next);
}
}
//if (multi_screen) {
// if (fmsg_next == nullptr) fmsg_next = fmsg;
// fmsg_next = lcd_display_message_fullscreen(fmsg_next);
//}
}
}
void lcd_insert_char_into_status(uint8_t position, const char message) {
if (position >= LCD_WIDTH) return;
//int size = ui.status_message.length();
char *str = ui.status_message.buffer();
str[position] = message;
ui.refresh(LCDVIEW_REDRAW_NOW); // force redraw
}
void lcd_replace_status_char(const uint8_t position, const char message) {
if (position >= MAX_MESSAGE_SIZE) return;
//int size = ui.status_message.length();
char *str = ui.status_message.buffer();
str[position] = message;
ui.refresh(LCDVIEW_REDRAW_NOW); // force redraw
}
#endif // HAS_PRUSA_MMU3

View file

@ -48,11 +48,11 @@
class LcdUpdateDisabler {
public:
LcdUpdateDisabler() : m_updateEnabled(ui.lcdDrawUpdate) {
TERN_(HAS_WIRED_LCD, ui.lcdDrawUpdate = LCDViewAction::LCDVIEW_NONE);
TERN_(HAS_WIRED_LCD, ui.refresh(LCDViewAction::LCDVIEW_NONE));
}
~LcdUpdateDisabler() {
#if HAS_WIRED_LCD
ui.lcdDrawUpdate = m_updateEnabled;
ui.refresh(m_updateEnabled);
ui.clear_lcd();
ui.update();
#endif
@ -62,11 +62,11 @@ class LcdUpdateDisabler {
LCDViewAction m_updateEnabled;
};
bool pgm_is_whitespace(const char *c_addr);
bool pgm_is_interpunction(const char *c_addr);
bool is_whitespace_P(const char *c_addr);
bool is_punctuation_P(const char *c_addr);
FSTR_P const lcd_display_message_fullscreen(FSTR_P const pmsg);
void lcd_show_choices_prompt_P(uint8_t selected, const char *first_choice, const char *second_choice, uint8_t second_col, const char *third_choice=nullptr);
void lcd_show_fullscreen_message_and_wait(FSTR_P const fmsg);
uint8_t lcdui_print_extruder(void);
void lcd_space(uint8_t n);
void lcd_insert_char_into_status(uint8_t position, const char message);
void lcd_replace_status_char(uint8_t position, const char message);

View file

@ -96,9 +96,9 @@
* M240: Trigger a camera by...
*
* - CHDK : Emulate a Canon RC-1 with a configurable ON duration.
* https://captain-slow.dk/2014/03/09/3d-printing-timelapses/
* https://youtube.be/UqZ8Um5MZEA
* - PHOTOGRAPH_PIN : Pulse a digital pin 16 times.
* See https://www.doc-diy.net/photo/rc-1_hacked/
* See https://web.archive.org/web/20250327153953/www.doc-diy.net/photo/rc-1_hacked/
* - PHOTO_SWITCH_POSITION : Bump a physical switch with the X-carriage using a
* configured position, delay, and retract length.
*

View file

@ -27,20 +27,21 @@
#include "../../gcode.h"
#include "../../../module/ft_motion.h"
#include "../../../module/stepper.h"
#include "../../../lcd/marlinui.h"
void say_shaper_type(const AxisEnum a, bool &sep, const char axis_name) {
if (sep) SERIAL_ECHOPGM(" ; ");
SERIAL_CHAR(axis_name, '=');
switch (ftMotion.cfg.shaper[a]) {
default: break;
case ftMotionShaper_ZV: SERIAL_ECHOPGM("ZV"); break;
case ftMotionShaper_ZVD: SERIAL_ECHOPGM("ZVD"); break;
case ftMotionShaper_ZVDD: SERIAL_ECHOPGM("ZVDD"); break;
case ftMotionShaper_ZVDDD: SERIAL_ECHOPGM("ZVDDD"); break;
case ftMotionShaper_EI: SERIAL_ECHOPGM("EI"); break;
case ftMotionShaper_2HEI: SERIAL_ECHOPGM("2 Hump EI"); break;
case ftMotionShaper_3HEI: SERIAL_ECHOPGM("3 Hump EI"); break;
case ftMotionShaper_MZV: SERIAL_ECHOPGM("MZV"); break;
TERN_(FTM_SHAPER_ZV, case ftMotionShaper_ZV: SERIAL_ECHOPGM("ZV"); break);
TERN_(FTM_SHAPER_ZVD, case ftMotionShaper_ZVD: SERIAL_ECHOPGM("ZVD"); break);
TERN_(FTM_SHAPER_ZVDD, case ftMotionShaper_ZVDD: SERIAL_ECHOPGM("ZVDD"); break);
TERN_(FTM_SHAPER_ZVDDD, case ftMotionShaper_ZVDDD: SERIAL_ECHOPGM("ZVDDD"); break);
TERN_(FTM_SHAPER_EI, case ftMotionShaper_EI: SERIAL_ECHOPGM("EI"); break);
TERN_(FTM_SHAPER_2HEI, case ftMotionShaper_2HEI: SERIAL_ECHOPGM("2 Hump EI"); break);
TERN_(FTM_SHAPER_3HEI, case ftMotionShaper_3HEI: SERIAL_ECHOPGM("3 Hump EI"); break);
TERN_(FTM_SHAPER_MZV, case ftMotionShaper_MZV: SERIAL_ECHOPGM("MZV"); break);
}
sep = true;
}
@ -87,7 +88,7 @@ void say_shaping() {
#if HAS_X_AXIS
SERIAL_CHAR(STEPPER_A_NAME);
SERIAL_ECHO_TERNARY(dynamic, " ", "base dynamic", "static", " shaper frequency: ");
SERIAL_ECHO(p_float_t(c.baseFreq.x, 2), F("Hz"));
SERIAL_ECHO(p_float_t(c.baseFreq.x, 2), F(" Hz"));
#if HAS_DYNAMIC_FREQ
if (dynamic) SERIAL_ECHO(F(" scaling: "), p_float_t(c.dynFreqK.x, 2), F("Hz/"), z_based ? F("mm") : F("g"));
#endif
@ -113,6 +114,16 @@ void say_shaping() {
#endif
SERIAL_EOL();
#endif
#if ENABLED(FTM_SHAPER_E)
SERIAL_CHAR('E');
SERIAL_ECHO_TERNARY(dynamic, " ", "base dynamic", "static", " shaper frequency: ");
SERIAL_ECHO(p_float_t(c.baseFreq.e, 2), F(" Hz"));
#if HAS_DYNAMIC_FREQ
if (dynamic) SERIAL_ECHO(F(" scaling: "), p_float_t(c.dynFreqK.e, 2), F("Hz/"), z_based ? F("mm") : F("g"));
#endif
SERIAL_EOL();
#endif
}
}
@ -236,10 +247,8 @@ void GcodeSuite::M493() {
return;
}
auto set_shaper = [&](const AxisEnum axis, ftMotionShaper_t newsh) {
if (newsh != c.shaper[axis]) {
c.shaper[axis] = newsh;
if (c.setShaper(axis, newsh))
flag.update = flag.report = true;
}
};
if (seenC) {
#define _SET_SHAPER(A) set_shaper(_AXIS(A), shaperVal);
@ -248,14 +257,9 @@ void GcodeSuite::M493() {
#endif // NUM_AXES_SHAPED > 0
// Parse 'H' Axis Synchronization parameter.
if (parser.seenval('H')) {
const bool enabled = parser.value_bool();
if (enabled != c.axis_sync_enabled) {
c.axis_sync_enabled = enabled;
flag.report = true;
}
}
// Parse bool 'H' Axis Synchronization parameter.
if (parser.seen('H') && c.setAxisSync(parser.value_bool()))
flag.report = true;
#if HAS_DYNAMIC_FREQ
@ -296,7 +300,7 @@ void GcodeSuite::M493() {
const float zetaVal = seenI ? parser.value_float() : 0.0f;
const bool goodZeta = seenI && c.goodZeta(zetaVal);
if (seenI && !goodZeta)
SERIAL_ECHOLN(F("?Invalid "), F("(I) Zeta value. (0.01-1.0)")); // Zeta out of range
SERIAL_ECHOLN(F("?Invalid "), F("(I) Zeta value. (0.01-" STRINGIFY(FTM_MAX_DAMPENING) ")")); // Zeta out of range
#if HAS_FTM_EI_SHAPING
// Vibration Tolerance parameter
@ -317,10 +321,8 @@ void GcodeSuite::M493() {
if (seenA) {
if (AXIS_IS_SHAPING(X)) {
// TODO: Frequency minimum is dependent on the shaper used; the above check isn't always correct.
if (goodBaseFreq) {
c.baseFreq.x = baseFreqVal;
if (goodBaseFreq && c.setBaseFreq(X_AXIS, baseFreqVal))
flag.update = flag.report = true;
}
}
else // Mode doesn't use frequency.
SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_A_NAME), " (A) frequency.");
@ -328,19 +330,15 @@ void GcodeSuite::M493() {
#if HAS_DYNAMIC_FREQ
// Parse X frequency scaling parameter
if (seenF && modeUsesDynFreq) {
c.dynFreqK.x = baseDynFreqVal;
if (seenF && c.setDynFreqK(X_AXIS, baseDynFreqVal))
flag.report = true;
}
#endif
// Parse X zeta parameter
if (seenI) {
if (AXIS_IS_SHAPING(X)) {
if (goodZeta) {
c.zeta.x = zetaVal;
if (goodZeta && c.setZeta(X_AXIS, zetaVal))
flag.update = true;
}
}
else
SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_A_NAME), " (I) zeta parameter.");
@ -350,10 +348,8 @@ void GcodeSuite::M493() {
// Parse X vtol parameter
if (seenQ) {
if (AXIS_IS_EISHAPING(X)) {
if (goodVtol) {
c.vtol.x = vtolVal;
if (goodVtol && c.setVtol(X_AXIS, vtolVal))
flag.update = true;
}
}
else
SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_A_NAME), " (Q) vtol parameter.");
@ -370,10 +366,8 @@ void GcodeSuite::M493() {
// Parse Y frequency parameter
if (seenA) {
if (AXIS_IS_SHAPING(Y)) {
if (goodBaseFreq) {
c.baseFreq.y = baseFreqVal;
if (goodBaseFreq && c.setBaseFreq(Y_AXIS, baseFreqVal))
flag.update = flag.report = true;
}
}
else // Mode doesn't use frequency.
SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_B_NAME), " (A) frequency.");
@ -381,32 +375,26 @@ void GcodeSuite::M493() {
#if HAS_DYNAMIC_FREQ
// Parse Y frequency scaling parameter
if (seenF && modeUsesDynFreq) {
c.dynFreqK.y = baseDynFreqVal;
if (seenF && c.setDynFreqK(Y_AXIS, baseDynFreqVal))
flag.report = true;
}
#endif
// Parse Y zeta parameter
if (seenI) {
if (AXIS_IS_SHAPING(Y)) {
if (goodZeta) {
c.zeta.y = zetaVal;
if (goodZeta && c.setZeta(Y_AXIS, zetaVal))
flag.update = true;
}
}
else
SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_B_NAME), " (I) zeta parameter.");
}
// Parse Y vtol parameter
#if HAS_FTM_EI_SHAPING
// Parse Y vtol parameter
if (seenQ) {
if (AXIS_IS_EISHAPING(Y)) {
if (goodVtol) {
c.vtol.y = vtolVal;
if (goodVtol && c.setVtol(Y_AXIS, vtolVal))
flag.update = true;
}
}
else
SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_B_NAME), " (Q) vtol parameter.");
@ -423,10 +411,8 @@ void GcodeSuite::M493() {
// Parse Z frequency parameter
if (seenA) {
if (AXIS_IS_SHAPING(Z)) {
if (goodBaseFreq) {
c.baseFreq.z = baseFreqVal;
if (goodBaseFreq && c.setBaseFreq(Z_AXIS, baseFreqVal))
flag.update = flag.report = true;
}
}
else // Mode doesn't use frequency.
SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_C_NAME), " (A) frequency.");
@ -434,32 +420,26 @@ void GcodeSuite::M493() {
#if HAS_DYNAMIC_FREQ
// Parse Z frequency scaling parameter
if (seenF && modeUsesDynFreq) {
c.dynFreqK.z = baseDynFreqVal;
if (seenF && c.setDynFreqK(Z_AXIS, baseDynFreqVal))
flag.report = true;
}
#endif
// Parse Z zeta parameter
if (seenI) {
if (AXIS_IS_SHAPING(Z)) {
if (goodZeta) {
c.zeta.z = zetaVal;
if (goodZeta && c.setZeta(Z_AXIS, zetaVal))
flag.update = true;
}
}
else
SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_C_NAME), " (I) zeta parameter.");
}
// Parse Z vtol parameter
#if HAS_FTM_EI_SHAPING
// Parse Z vtol parameter
if (seenQ) {
if (AXIS_IS_EISHAPING(Z)) {
if (goodVtol) {
c.vtol.z = vtolVal;
if (goodVtol && c.setVtol(Z_AXIS, vtolVal))
flag.update = true;
}
}
else
SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_C_NAME), " (Q) vtol parameter.");
@ -476,10 +456,8 @@ void GcodeSuite::M493() {
// Parse E frequency parameter
if (seenA) {
if (AXIS_IS_SHAPING(E)) {
if (goodBaseFreq) {
c.baseFreq.e = baseFreqVal;
if (goodBaseFreq && c.setBaseFreq(E_AXIS, baseFreqVal))
flag.update = flag.report = true;
}
}
else // Mode doesn't use frequency.
SERIAL_ECHOLNPGM("?Wrong mode for ", C('E'), " (A) frequency.");
@ -487,32 +465,26 @@ void GcodeSuite::M493() {
#if HAS_DYNAMIC_FREQ
// Parse E frequency scaling parameter
if (seenF && modeUsesDynFreq) {
c.dynFreqK.e = baseDynFreqVal;
if (seenF && c.setDynFreqK(E_AXIS, baseDynFreqVal))
flag.report = true;
}
#endif
// Parse E zeta parameter
if (seenI) {
if (AXIS_IS_SHAPING(E)) {
if (goodZeta) {
c.zeta.e = zetaVal;
if (goodZeta && c.setZeta(E_AXIS, zetaVal))
flag.update = true;
}
}
else
SERIAL_ECHOLNPGM("?Wrong mode for ", C('E'), " (I) zeta parameter.");
}
// Parse E vtol parameter
#if HAS_FTM_EI_SHAPING
// Parse E vtol parameter
if (seenQ) {
if (AXIS_IS_EISHAPING(E)) {
if (goodVtol) {
c.vtol.e = vtolVal;
if (goodVtol && c.setVtol(E_AXIS, vtolVal))
flag.update = true;
}
}
else
SERIAL_ECHOLNPGM("?Wrong mode for ", C('E'), " (Q) vtol parameter.");
@ -522,7 +494,8 @@ void GcodeSuite::M493() {
#endif // FTM_SHAPER_E
if (flag.update) ftMotion.update_shaping_params();
if (flag.update || flag.report)
ui.refresh();
if (flag.report) say_shaping();
}

View file

@ -27,6 +27,7 @@
#include "../../../module/ft_motion.h"
#include "../../../module/stepper.h"
#include "../../../module/planner.h"
#include "../../../lcd/marlinui.h"
void say_ftm_settings() {
#if ANY(FTM_POLYS, FTM_SMOOTHING)
@ -48,11 +49,13 @@ void say_ftm_settings() {
void GcodeSuite::M494_report(const bool forReplay/*=true*/) {
TERN_(MARLIN_SMALL_BUILD, return);
const ft_config_t &c = ftMotion.cfg;
report_heading_etc(forReplay, F("FT Motion"));
SERIAL_ECHOPGM(" M494 T", (uint8_t)ftMotion.getTrajectoryType());
#if ANY(FTM_POLYS, FTM_SMOOTHING)
const ft_config_t &c = ftMotion.cfg;
#endif
#if ENABLED(FTM_SMOOTHING)
SERIAL_ECHOPGM(CARTES_PAIRED_LIST(
" X", c.smoothingTime.X,
@ -109,14 +112,17 @@ void GcodeSuite::M494() {
#if ENABLED(FTM_SMOOTHING)
#define SMOOTH_SET(A,N) \
if (parser.seenval(CHARIFY(A))) { \
if (ftMotion.set_smoothing_time(_AXIS(A), parser.value_float())) \
report = true; \
else \
SERIAL_ECHOLNPGM("?Invalid ", C(N), " smoothing time (", C(CHARIFY(A)), ") value."); \
auto smooth_set = [](AxisEnum axis, char axis_name) {
if (parser.seenval(IAXIS_CHAR(axis))) {
if (ftMotion.set_smoothing_time(axis, parser.value_float()))
return true;
else
SERIAL_ECHOLNPGM("?Invalid ", C(axis_name), " smoothing time (", C(IAXIS_CHAR(axis)), ") value.");
}
return false;
};
#define SMOOTH_SET(A,N) report |= smooth_set(_AXIS(A), N);
CARTES_GANG(
SMOOTH_SET(X, STEPPER_A_NAME), SMOOTH_SET(Y, STEPPER_B_NAME),
SMOOTH_SET(Z, STEPPER_C_NAME), SMOOTH_SET(E, 'E')
@ -124,7 +130,10 @@ void GcodeSuite::M494() {
#endif // FTM_SMOOTHING
if (report) say_ftm_settings();
if (report) {
ui.refresh();
say_ftm_settings();
}
}
#endif // FT_MOTION

View file

@ -179,17 +179,43 @@ void GcodeSuite::D(const int16_t dcode) {
break;
case 100: { // D100 Disable heaters and attempt a hard hang (Watchdog Test)
#ifdef __PLAT_RP2040__
const uint8_t core = parser.byteval('C', 0); // C parameter: which core to freeze (0=Core 0, 1=Core 1)
#else
constexpr uint8_t core = 0;
#endif
SERIAL_ECHOLNPGM("Disabling heaters and attempting to trigger Watchdog");
SERIAL_ECHOLNPGM("(USE_WATCHDOG " TERN(USE_WATCHDOG, "ENABLED", "DISABLED") ")");
#ifdef __PLAT_RP2040__
SERIAL_ECHOLNPGM("Freezing Core ", core);
#endif
thermalManager.disable_all_heaters();
delay(1000); // Allow time to print
hal.isr_off();
// Use a low-level delay that does not rely on interrupts to function
// Do not spin forever, to avoid thermal risks if heaters are enabled and
// watchdog does not work.
for (int i = 10000; i--;) DELAY_US(1000UL);
hal.isr_on();
if (core == 1) {
#ifdef __PLAT_RP2040__
// Freeze Core 1 by setting a flag it will check
extern volatile bool core1_freeze_test;
core1_freeze_test = true;
delay(10000); // Wait 10 seconds for watchdog to trigger
core1_freeze_test = false;
#endif
}
else {
// Freeze Core 0 (original behavior)
hal.isr_off();
// Use a low-level delay that does not rely on interrupts to function
// Do not spin forever, to avoid thermal risks if heaters are enabled and
// watchdog does not work.
for (int i = 10000; i--;) DELAY_US(1000UL);
hal.isr_on();
}
SERIAL_ECHOLNPGM("FAILURE: Watchdog did not trigger board reset.");
} break;
#if HAS_MEDIA

View file

@ -188,7 +188,7 @@ void GCodeParser::parse(char *p) {
// Bail if there's no command code number
if (!TERN(SIGNED_CODENUM, NUMERIC_SIGNED(*p), NUMERIC(*p))) {
if (TERN0(HAS_MULTI_EXTRUDER, letter == 'T')) {
if (E_TERN0(letter == 'T')) {
p[0] = '*'; p[1] = '\0'; string_arg = p; // Convert 'T' alone into 'T*'
command_letter = letter;
}

View file

@ -26,6 +26,7 @@
#include "../gcode.h"
#include "../../sd/cardreader.h"
#include "../../lcd/marlinui.h"
/**
* M34: Media Sorting
@ -33,7 +34,7 @@
* Set Media Sorting Options
*
* Parameters:
* S<inr> Sorting Order:
* S<int> Sorting Order:
* S Default sorting (i.e., SDSORT_REVERSE)
* S-1 Reverse alpha sorting
* S0 FID Order (not always newest)
@ -46,11 +47,16 @@
* F1 Folders after files
*/
void GcodeSuite::M34() {
if (parser.seen('S')) card.setSortOn(SortFlag(parser.ushortval('S', TERN(SDSORT_REVERSE, AS_REV, AS_FWD))));
if (parser.seen('S'))
card.setSortOn(SortFlag(parser.ushortval('S', TERN(SDSORT_REVERSE, AS_REV, AS_FWD))));
if (parser.seenval('F')) {
const int v = parser.value_long();
card.setSortFolders(v < 0 ? -1 : v > 0 ? 1 : 0);
}
ui.refresh();
//if (parser.seen('R')) card.setSortReverse(parser.value_bool());
}

View file

@ -49,7 +49,7 @@
*/
void GcodeSuite::M306() {
const uint8_t e = TERN0(HAS_MULTI_EXTRUDER, parser.intval('E', active_extruder));
const uint8_t e = E_TERN0(parser.intval('E', active_extruder));
if (e >= (EXTRUDERS)) {
SERIAL_ECHOLNPGM("?(E)xtruder index out of range (0-", (EXTRUDERS) - 1, ").");
return;

View file

@ -373,8 +373,6 @@
#undef INPUT_SHAPING_Y
#undef INPUT_SHAPING_Z
#undef INPUT_SHAPING_E_SYNC
#undef MULTISTEPPING_LIMIT
#define MULTISTEPPING_LIMIT 1
#endif
// Linear advance uses Jerk since E is an isolated axis

View file

@ -3612,6 +3612,14 @@
#endif
#endif
#if ALL(SDCARD_SORT_ALPHA, SDSORT_CACHE_NAMES) && DISABLED(SDSORT_DYNAMIC_RAM)
#if SDSORT_CACHE_VFATS > VFAT_ENTRIES_LIMIT
#undef SDSORT_CACHE_VFATS
#define SDSORT_CACHE_VFATS VFAT_ENTRIES_LIMIT
#define SDSORT_CACHE_VFATS_WARNING 1
#endif
#endif
// Fallback SPI Speed for SD
#if HAS_MEDIA && !defined(SD_SPI_SPEED)
#define SD_SPI_SPEED SPI_FULL_SPEED
@ -3687,27 +3695,14 @@
// Fixed-Time Motion
#if ENABLED(FT_MOTION)
#define FTM_TS (1.0f / FTM_FS) // (s) Time step for trajectory generation. (Reciprocal of FTM_FS)
#define FTM_RATIO (FTM_FS / FTM_MIN_SHAPE_FREQ) // Factor for use in FTM_ZMAX. DON'T CHANGE.
#define FTM_SMOOTH_MAX_I uint32_t(TERN0(FTM_SMOOTHING, CEIL(FTM_FS * FTM_MAX_SMOOTHING_TIME))) // Max delays for smoothing
// Maximum delays for shaping functions (even numbers only!)
#define FTM_ZMAX (TERN(HAS_FTM_EI_SHAPING, 2, 1) * FTM_RATIO + FTM_SMOOTH_MAX_I)
#define FTM_TS (1.0f / FTM_FS) // (s) Time step for trajectory generation. (Reciprocal of FTM_FS)
#define FTM_SMOOTHING_ORDER 5 // 3 to 5 is closest to Gaussian
// Calculate as:
// ZV : FTM_RATIO / 2
// ZVD, MZV : FTM_RATIO
// 2HEI : FTM_RATIO * 3 / 2
// 3HEI : FTM_RATIO * 2
#ifndef FTM_BUFFER_SIZE
#define FTM_BUFFER_SIZE 128
#endif
#define FTM_BUFFER_MASK (FTM_BUFFER_SIZE - 1u)
#if ANY(BIQU_MICROPROBE_V1, BIQU_MICROPROBE_V2)
#ifndef PROBE_WAKEUP_TIME_MS
#define PROBE_WAKEUP_TIME_MS 30
#define PROBE_WAKEUP_TIME_WARNING 1
#endif
#if ANY(BIQU_MICROPROBE_V1, BIQU_MICROPROBE_V2) && !defined(PROBE_WAKEUP_TIME_MS)
#define PROBE_WAKEUP_TIME_MS 30
#define PROBE_WAKEUP_TIME_WARNING 1
#endif
#endif

View file

@ -429,14 +429,8 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L
#error "SDSORT_DYNAMIC_RAM requires SDSORT_CACHE_NAMES."
#endif
#if ENABLED(SDSORT_CACHE_NAMES) && DISABLED(SDSORT_DYNAMIC_RAM)
#if SDSORT_CACHE_VFATS < 2
#error "SDSORT_CACHE_VFATS must be 2 or greater!"
#elif SDSORT_CACHE_VFATS > VFAT_ENTRIES_LIMIT
#undef SDSORT_CACHE_VFATS
#define SDSORT_CACHE_VFATS VFAT_ENTRIES_LIMIT
#define SDSORT_CACHE_VFATS_WARNING 1
#endif
#if ENABLED(SDSORT_CACHE_NAMES) && DISABLED(SDSORT_DYNAMIC_RAM) && SDSORT_CACHE_VFATS < 2
#error "SDSORT_CACHE_VFATS must be 2 or greater!"
#endif
#endif
@ -4479,7 +4473,7 @@ static_assert(_PLUS_TEST(3), "DEFAULT_MAX_ACCELERATION values must be positive."
* Fixed-Time Motion limitations
*/
#if ENABLED(FT_MOTION)
static_assert(FTM_BUFFER_SIZE >= 4 && (FTM_BUFFER_SIZE & FTM_BUFFER_MASK) == 0, "FTM_BUFFER_SIZE must be a power of two (128, 256, 512, ...).");
static_assert(FTM_BUFFER_SIZE >= 4 && (FTM_BUFFER_SIZE & (FTM_BUFFER_SIZE - 1u)) == 0, "FTM_BUFFER_SIZE must be a power of two (128, 256, 512, ...).");
#if ENABLED(MIXING_EXTRUDER)
#error "FT_MOTION does not currently support MIXING_EXTRUDER."
#endif

View file

@ -42,7 +42,7 @@
* version was tagged.
*/
#ifndef STRING_DISTRIBUTION_DATE
#define STRING_DISTRIBUTION_DATE "2025-12-14"
#define STRING_DISTRIBUTION_DATE "2025-12-25"
#endif
/**

View file

@ -799,7 +799,7 @@
#if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) && DISABLED(RGB_LED)
#warning "Your FYSETC Mini Panel works best with RGB_LED."
#elif ANY(FYSETC_MINI_12864_2_0, FYSETC_MINI_12864_2_1) && DISABLED(LED_USER_PRESET_STARTUP)
#elif ENABLED(FYSETC_MINI_12864_2_0) && DISABLED(LED_USER_PRESET_STARTUP)
#warning "Your FYSETC/MKS/BTT/BEEZ Mini Panel works best with LED_USER_PRESET_STARTUP."
#endif

View file

@ -365,7 +365,7 @@ private:
const auto end_x_px = start_x_px + cell_width_px - 1 - gridline_width;
const auto start_y_px = padding_y_top + (GRID_MAX_POINTS_Y - y - 1) * cell_height_px;
const auto end_y_px = start_y_px + cell_height_px - 1 - gridline_width;
dwinDrawRectangle(1, // RGB565 colors: http://www.barth-dev.de/online/rgb565-color-picker/
dwinDrawRectangle(1, // RGB565 colors: https://barth-dev.de/online/rgb565-color-picker/
isnan(bedlevel.z_values[x][y]) ? COLOR_GREY : ( // gray if undefined
(bedlevel.z_values[x][y] < 0 ?
(uint16_t)LROUND(0x1F * -bedlevel.z_values[x][y] / (!viewer_asymmetric_range ? rmax : v_min)) << 11 : // red if mesh point value is negative

View file

@ -65,7 +65,7 @@ namespace Anycubic {
// Only uncomment the tunes you are using to save memory
// This will help you write tunes!
// https://www.apronus.com/music/flashpiano.htm
// https://virtualpiano.online/
const uint16_t SOS[] = {
250,

View file

@ -1088,7 +1088,7 @@ void DGUSScreenHandlerMKS::filamentUnload(DGUS_VP_Variable &var, void *val_ptr)
if (filament_data.action == 0) { // Go back to utility screen
TERN_(HAS_EXTRUDERS, thermalManager.setTargetHotend(e_temp, 0));
TERN_(HAS_MULTI_EXTRUDER, thermalManager.setTargetHotend(e_temp, 1));
E_TERN_(thermalManager.setTargetHotend(e_temp, 1));
gotoScreen(DGUS_SCREEN_UTILITY);
return;
}

View file

@ -38,7 +38,7 @@ const char DGUS_MACHINENAME[] PROGMEM = MACHINE_NAME;
const char DGUS_MARLINVERSION[] PROGMEM = SHORT_BUILD_VERSION;
const char DGUS_BOARD[] PROGMEM = BOARD_INFO_NAME;
const char DGUS_BEDSIZE[] PROGMEM = DGUS_BED_SIZE_STR;
const char DGUS_WEBSITE[] PROGMEM = "http://marlinfw.org";
const char DGUS_WEBSITE[] PROGMEM = "https://marlinfw.org";
const uint16_t DGUS_ZERO = 0;
#define VP_HELPER(ADDR, SIZE, FLAGS, EXTRA, RXHANDLER, TXHANDLER) \

View file

@ -671,4 +671,4 @@ into proprietary programs. If your program is a subroutine library, you
may consider it more useful to permit linking proprietary applications with
the library. If this is what you want to do, use the GNU Lesser General
Public License instead of this License. But first, please read
<https://www.gnu.org/philosophy/why-not-lgpl.html>.
<https://www.gnu.org/licenses/why-not-lgpl.html>.

View file

@ -64,7 +64,7 @@
/**
* Settings for the Haoyu Electronics, 4.3" Graphical LCD Touchscreen, 480x272, SPI, FT800 (FT800CB-HY43B)
* and 5" Graphical LCD Touchscreen, 480x272, SPI, FT800 (FT800CB-HY50B)
* http://www.hotmcu.com/43-graphical-lcd-touchscreen-480x272-spi-ft800-p-111.html?cPath=6_16
* https://www.hotmcu.com/43-graphical-lcd-touchscreen-480x272-spi-ft800-p-111.html?cPath=6_16
* http://www.hotmcu.com/5-graphical-lcd-touchscreen-480x272-spi-ft800-p-124.html?cPath=6_16
* Datasheet:
* https://www.hantronix.com/files/data/1278363262430-3.pdf
@ -90,7 +90,7 @@
/**
* Settings for the Haoyu Electronics, 5" Graphical LCD Touchscreen, 800x480, SPI, FT810
* http://www.hotmcu.com/5-graphical-lcd-touchscreen-800x480-spi-ft810-p-286.html
* https://www.hotmcu.com/5-graphical-lcd-touchscreen-800x480-spi-ft810-p-286.html
* Datasheet:
* https://www.haoyuelectronics.com/Attachment/HY5-LCD-HD/KD50G21-40NT-A1.pdf
*/
@ -115,7 +115,7 @@
* Settings for the 4D Systems, 4.3" Embedded SPI Display 480x272, SPI, FT800 (4DLCD-FT843)
* https://4dsystems.com.au/4dlcd-ft843
* Datasheet:
* https://4dsystems.com.au/mwdownloads/download/link/id/52/
* https://resources.4dsystems.com.au/datasheets/ft8xx/4DLCD-FT843/4DLCD-FT843_Datasheet_R_1_3.pdf
*/
#elif defined(LCD_4DSYSTEMS_4DLCD_FT843)
#if !HAS_RESOLUTION
@ -159,7 +159,7 @@
* FYSETC Color LCD
* https://www.aliexpress.com/item/4000627651757.html
* Product information:
* https://github.com/FYSETC/TFT81050
* https://github.com/FYSETC/FYSETC-TFT81050
*/
#elif defined(LCD_FYSETC_TFT81050)
#if !HAS_RESOLUTION

View file

@ -1,13 +1,13 @@
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
<svg
xmlns:dc="http://purl.org/dc/elements/1.1/"
xmlns:cc="http://creativecommons.org/ns#"
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
xmlns:cc="https://creativecommons.org/ns#"
xmlns:rdf="https://www.w3.org/1999/02/22-rdf-syntax-ns#"
xmlns:svg="http://www.w3.org/2000/svg"
xmlns="http://www.w3.org/2000/svg"
xmlns:xlink="http://www.w3.org/1999/xlink"
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
xmlns:xlink="https://www.w3.org/1999/xlink"
xmlns:sodipodi="https://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
xmlns:inkscape="http://inkscape.org/namespaces/inkscape"
width="40"
height="3234"
viewBox="0 0 10.583333 855.66248"

Before

Width:  |  Height:  |  Size: 51 KiB

After

Width:  |  Height:  |  Size: 51 KiB

Before After
Before After

View file

@ -1,15 +1,15 @@
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
<!-- Created with Inkscape (http://www.inkscape.org/) -->
<!-- Created with Inkscape (http://inkscape.org/) -->
<svg
xmlns:dc="http://purl.org/dc/elements/1.1/"
xmlns:cc="http://creativecommons.org/ns#"
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
xmlns:cc="https://creativecommons.org/ns#"
xmlns:rdf="https://www.w3.org/1999/02/22-rdf-syntax-ns#"
xmlns:svg="http://www.w3.org/2000/svg"
xmlns="http://www.w3.org/2000/svg"
xmlns:xlink="http://www.w3.org/1999/xlink"
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
xmlns:xlink="https://www.w3.org/1999/xlink"
xmlns:sodipodi="https://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
xmlns:inkscape="http://inkscape.org/namespaces/inkscape"
width="38"
height="2107"
viewBox="0 0 10.054166 557.47707"

Before

Width:  |  Height:  |  Size: 40 KiB

After

Width:  |  Height:  |  Size: 40 KiB

Before After
Before After

View file

@ -56,7 +56,7 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) {
else {
const int16_t new_flow = _MIN(MAX_EXT_SPEED_PERCENT, planner.flow_percentage[0] + uiCfg.stepPrintSpeed);
planner.set_flow(0, new_flow);
TERN_(HAS_MULTI_EXTRUDER, planner.set_flow(1, new_flow));
E_TERN_(planner.set_flow(1, new_flow));
}
disp_print_speed();
break;
@ -66,7 +66,7 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) {
else {
const int16_t new_flow = _MAX(MIN_EXT_SPEED_PERCENT, planner.flow_percentage[0] - uiCfg.stepPrintSpeed);
planner.set_flow(0, new_flow);
TERN_(HAS_MULTI_EXTRUDER, planner.set_flow(1, new_flow));
E_TERN_(planner.set_flow(1, new_flow));
}
disp_print_speed();
break;

View file

@ -103,7 +103,7 @@ static void btn_ok_event_cb(lv_obj_t *btn, lv_event_t event) {
if (card.isFileOpen()) {
feedrate_percentage = 100;
TERN_(HAS_EXTRUDERS, planner.set_flow(0, 100));
TERN_(HAS_MULTI_EXTRUDER, planner.set_flow(1, 100));
E_TERN_(planner.set_flow(1, 100));
card.startOrResumeFilePrinting();
TERN_(POWER_LOSS_RECOVERY, recovery.prepare());
once_flag = false;

View file

@ -235,7 +235,7 @@ void disp_ext_heart() {
void disp_temp_type() {
if (uiCfg.curTempType == 0) {
if (TERN0(HAS_MULTI_EXTRUDER, uiCfg.extruderIndex == 1)) {
if (E_TERN0(uiCfg.extruderIndex == 1)) {
lv_imgbtn_set_src_both(buttonType, "F:/bmp_extru2.bin");
if (gCfgItems.multiple_language) {
lv_label_set_text(labelType, preheat_menu.ext2);

View file

@ -651,7 +651,7 @@ char *creat_title_text() {
if (card.isFileOpen()) {
feedrate_percentage = 100;
TERN_(HAS_EXTRUDERS, planner.set_flow(0, 100));
TERN_(HAS_MULTI_EXTRUDER, planner.set_flow(1, 100));
E_TERN_(planner.set_flow(1, 100));
card.startOrResumeFilePrinting();
TERN_(POWER_LOSS_RECOVERY, recovery.prepare());
once_flag = false;

View file

@ -592,7 +592,7 @@ do {
/* SAX/FNV/OAT/JEN hash functions are macro variants of those listed at
* http://eternallyconfuzzled.com/tuts/algorithms/jsw_tut_hashing.aspx
* https://eternallyconfuzzled.com/tuts/algorithms/jsw_tut_hashing.aspx
* (archive link: https://archive.is/Ivcan )
*/
#define HASH_SAX(key,keylen,hashv) \

View file

@ -1072,7 +1072,7 @@ static void wifi_gcode_exec(uint8_t * const cmd_line) {
//saved_feedrate_percentage = feedrate_percentage;
feedrate_percentage = 100;
TERN_(HAS_EXTRUDERS, planner.set_flow(0, 100));
TERN_(HAS_MULTI_EXTRUDER, planner.set_flow(1, 100));
E_TERN_(planner.set_flow(1, 100));
card.startOrResumeFilePrinting();
TERN_(POWER_LOSS_RECOVERY, recovery.prepare());
once_flag = false;

View file

@ -422,7 +422,7 @@ EspUploadResult doCommand(uint8_t op, const uint8_t *data, size_t dataLen, uint3
return stat;
}
// Send a synchronising packet to the serial port in an attempt to induce
// Send a synchronizing packet to the serial port in an attempt to induce
// the ESP8266 to auto-baud lock on the baud rate.
EspUploadResult sync(uint16_t timeout) {
uint8_t buf[36];

View file

@ -36,45 +36,69 @@ namespace LanguageNarrow_sv {
constexpr uint8_t CHARSIZE = 2;
LSTR LANGUAGE = _UxGT("Swedish");
LSTR WELCOME_MSG = MACHINE_NAME_SUBST _UxGT(" Redo.");
LSTR WELCOME_MSG = MACHINE_NAME_SUBST _UxGT(" redo.");
LSTR MSG_YES = _UxGT("JA");
LSTR MSG_NO = _UxGT("NEJ");
LSTR MSG_HIGH = _UxGT("Hög");
LSTR MSG_LOW = _UxGT("låg");
LSTR MSG_BACK = _UxGT("Bakåt");
LSTR MSG_ERROR = _UxGT("Fel");
LSTR MSG_MEDIA_ABORTING = _UxGT("Avbryter...");
LSTR MSG_MEDIA_INSERTED = _UxGT("Media Instatt");
LSTR MSG_MEDIA_REMOVED = _UxGT("Media Borttaget");
LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Media init misslyckades");
LSTR MSG_MEDIA_READ_ERROR = _UxGT("Media läsningsfel");
LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("USB enhet borttagen");
LSTR MSG_USB_FD_USB_FAILED = _UxGT("USB start misslyckad");
LSTR MSG_MEDIA_INSERTED = _UxGT("Minneskort isatt");
LSTR MSG_MEDIA_REMOVED = _UxGT("Minneskort avlägsnat");
LSTR MSG_MEDIA_WAITING = _UxGT("Väntar på minneskort");
LSTR MSG_MEDIA_INIT_FAIL = _UxGT("Misslyckad läsning av minneskort");
LSTR MSG_MEDIA_READ_ERROR = _UxGT("Läsningsfel minneskort");
LSTR MSG_USB_FD_DEVICE_REMOVED = _UxGT("USB-minne avlägsnat");
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");
LSTR MSG_LCD_ENDSTOPS = _UxGT("Ändlägesbrytare"); // Max length 8 characters
LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Mjukvarugränslägen");
LSTR MSG_MAIN_MENU = _UxGT("Huvudmeny");
LSTR MSG_ADVANCED_SETTINGS = _UxGT("Advancerade inställningar");
LSTR MSG_TOOLBAR_SETUP = _UxGT("Inställningar verktygsfält");
LSTR MSG_OPTION_DISABLED = _UxGT("Alternativ avaktiverad");
LSTR MSG_CONFIGURATION = _UxGT("Konfiguration");
LSTR MSG_DISABLE_STEPPERS = _UxGT("Inaktivera Stegare");
LSTR MSG_DEBUG_MENU = _UxGT("Debug Meny");
LSTR MSG_PROGRESS_BAR_TEST = _UxGT("Framstegsindikator Test");
LSTR MSG_AUTO_HOME = _UxGT("Auto Hem");
LSTR MSG_DISABLE_STEPPERS = _UxGT("Inaktivera stegmotorer");
LSTR MSG_DEBUG_MENU = _UxGT("Debugmeny");
LSTR MSG_PROGRESS_BAR_TEST = _UxGT("Förloppindikator test");
LSTR MSG_HOMING = _UxGT("Hemkörning");
LSTR MSG_AUTO_HOME = _UxGT("Auto hem");
LSTR MSG_AUTO_HOME_A = _UxGT("Hem @");
LSTR MSG_AUTO_HOME_X = _UxGT("Hem X");
LSTR MSG_AUTO_HOME_Y = _UxGT("Hem Y");
LSTR MSG_AUTO_HOME_Z = _UxGT("Hem Z");
LSTR MSG_Z_AFTER_HOME = _UxGT("Z efter hemkörning");
LSTR MSG_FILAMENT_SET = _UxGT("Trådinställningar");
LSTR MSG_FILAMENT_MAN = _UxGT("Trådhantering");
LSTR MSG_MANUAL_LEVELING = _UxGT("Manuell höjdjustering");
LSTR MSG_LEVBED_FL = _UxGT("Övre vänster");
LSTR MSG_LEVBED_FR = _UxGT("Övre höger");
LSTR MSG_LEVBED_C = _UxGT("Mittpunkt");
LSTR MSG_LEVBED_BL = _UxGT("Nedre vänster");
LSTR MSG_LEVBED_BR = _UxGT("Nedre höger");
LSTR MSG_MANUAL_MESH = _UxGT("Manellt meshmät");
LSTR MSG_AUTO_MESH = _UxGT("Automatiskt meshnät");
LSTR MSG_AUTO_Z_ALIGN = _UxGT("Auto Z-Justering");
LSTR MSG_ITERATION = _UxGT("G34 Iteration: %i");
LSTR MSG_DECREASING_ACCURACY = _UxGT("Noggrannhet Minskar!");
LSTR MSG_ITERATION = _UxGT("G34 upprepning: %i");
LSTR MSG_DECREASING_ACCURACY = _UxGT("Noggrannhet minskar!");
LSTR MSG_ACCURACY_ACHIEVED = _UxGT("Noggrannhet uppnådd");
LSTR MSG_LEVEL_BED_HOMING = _UxGT("Hemning XYZ");
LSTR MSG_LEVEL_BED_WAITING = _UxGT("Klicka för att börja");
LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("Nästa Punkt");
LSTR MSG_LEVEL_BED_DONE = _UxGT("Nivellering Färdig!");
LSTR MSG_Z_FADE_HEIGHT = _UxGT("Falna Höjd");
LSTR MSG_SET_HOME_OFFSETS = _UxGT("Sätt Hem Offset");
LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Offset Tillämpad");
LSTR MSG_TRAMMING_WIZARD = _UxGT("Justerings Wizard");
LSTR MSG_SELECT_ORIGIN = _UxGT("Välj Origo");
LSTR MSG_LEVEL_BED_HOMING = _UxGT("Hemkörning XYZ");
LSTR MSG_LEVEL_BED_WAITING = _UxGT("Klicka för att starta");
LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("Nästa punkt");
LSTR MSG_LEVEL_BED_DONE = _UxGT("Höjdjustering klar!");
LSTR MSG_Z_FADE_HEIGHT = _UxGT("Tona höjden");
LSTR MSG_SET_HOME_OFFSETS = _UxGT("Ange offset för hemmaläge");
LSTR MSG_HOME_OFFSET_X = _UxGT("Hem offset X");
LSTR MSG_HOME_OFFSET_Y = _UxGT("Hem offset Y");
LSTR MSG_HOME_OFFSET_Z = _UxGT("Hem offset Z");
LSTR MSG_HOME_OFFSETS_APPLIED = _UxGT("Offset tillämpad");
LSTR MSG_ERR_M428_TOO_FAR = _UxGT("MIN/MAX för långt");
LSTR MSG_TRAMMING_WIZARD = _UxGT("Justerings guide");
LSTR MSG_SELECT_ORIGIN = _UxGT("Välj origo");
LSTR MSG_LAST_VALUE_SP = _UxGT("Senaste värde ");
LSTR MSG_PREHEAT_1 = _UxGT("Förvärmning ") PREHEAT_1_LABEL;
@ -93,197 +117,197 @@ namespace LanguageNarrow_sv {
LSTR MSG_PREHEAT_M_BEDONLY = _UxGT("Förvärmning $ Bädd");
LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("Förvärmning $ Donf");
LSTR MSG_PREHEAT_CUSTOM = _UxGT("Förvärmning Anpassad");
LSTR MSG_PREHEAT_CUSTOM = _UxGT("Anpassad förvärmning");
LSTR MSG_COOLDOWN = _UxGT("Nedkylning");
LSTR MSG_CUTTER_FREQUENCY = _UxGT("Frekvens");
LSTR MSG_LASER_MENU = _UxGT("Laser kontroll");
LSTR MSG_SPINDLE_MENU = _UxGT("Spindel Kontroll");
LSTR MSG_LASER_POWER = _UxGT("Laser Styrka");
LSTR MSG_SPINDLE_POWER = _UxGT("Spindel Styrka");
LSTR MSG_LASER_TOGGLE = _UxGT("Växla Laser");
LSTR MSG_LASER_PULSE_MS = _UxGT("Test Puls ms");
LSTR MSG_LASER_FIRE_PULSE = _UxGT("Avfyra Puls");
LSTR MSG_SPINDLE_TOGGLE = _UxGT("Växla Spindel");
LSTR MSG_SPINDLE_FORWARD = _UxGT("Spindel Framåt");
LSTR MSG_SPINDLE_REVERSE = _UxGT("Spindel Bakåt");
LSTR MSG_LASER_OFF = _UxGT("Laser Av");
LSTR MSG_LASER_ON = _UxGT("Laser ");
LSTR MSG_SPINDLE_OFF = _UxGT("Spindel Av");
LSTR MSG_SPINDLE_ON = _UxGT("Spindel ");
LSTR MSG_SWITCH_PS_ON = _UxGT("Sätt på ström");
LSTR MSG_SWITCH_PS_OFF = _UxGT("Stäng av ström");
LSTR MSG_LASER_MENU = _UxGT("Laserkontroll");
LSTR MSG_SPINDLE_MENU = _UxGT("Spindelkontroll");
LSTR MSG_LASER_POWER = _UxGT("Laserstyrka");
LSTR MSG_SPINDLE_POWER = _UxGT("Spindelstyrka");
LSTR MSG_LASER_TOGGLE = _UxGT("Växla laser");
LSTR MSG_LASER_PULSE_MS = _UxGT("Testpuls ms");
LSTR MSG_LASER_FIRE_PULSE = _UxGT("Aktivera puls");
LSTR MSG_SPINDLE_TOGGLE = _UxGT("Växla spindel");
LSTR MSG_SPINDLE_FORWARD = _UxGT("Spindel framåt");
LSTR MSG_SPINDLE_REVERSE = _UxGT("Spindel bakåt");
LSTR MSG_LASER_OFF = _UxGT("Laser från");
LSTR MSG_LASER_ON = _UxGT("Laser till");
LSTR MSG_SPINDLE_OFF = _UxGT("Spindel från");
LSTR MSG_SPINDLE_ON = _UxGT("Spindel till");
LSTR MSG_SWITCH_PS_ON = _UxGT("Spänning till");
LSTR MSG_SWITCH_PS_OFF = _UxGT("Spänning från");
LSTR MSG_EXTRUDE = _UxGT("Extrudera");
LSTR MSG_RETRACT = _UxGT("Dra tillbaka");
LSTR MSG_MOVE_AXIS = _UxGT("Flytta Axel");
LSTR MSG_RETRACT = _UxGT("Sug tillbaka");
LSTR MSG_MOVE_AXIS = _UxGT("Förflytta axel");
LSTR MSG_PROBE_AND_LEVEL = _UxGT("Sond och Nivellera");
LSTR MSG_BED_LEVELING = _UxGT("Bädd Nivellering");
LSTR MSG_LEVEL_BED = _UxGT("Nivellera Bädd");
LSTR MSG_BED_TRAMMING = _UxGT("Bädd Justering");
LSTR MSG_BED_TRAMMING_RAISE = _UxGT("Höj Bädd tills nästa Sond Triggad");
LSTR MSG_BED_TRAMMING_IN_RANGE = _UxGT("Alla Hörn inom Tolerans. Nivellering Bädd");
LSTR MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Bra Punkter: ");
LSTR MSG_BED_LEVELING = _UxGT("Höjdjustering av bädd");
LSTR MSG_LEVEL_BED = _UxGT("Höjdjustera bädd");
LSTR MSG_BED_TRAMMING = _UxGT("Justering av bädd");
LSTR MSG_BED_TRAMMING_RAISE = _UxGT("Höj bädden tills proben triggas");
LSTR MSG_BED_TRAMMING_IN_RANGE = _UxGT("Alla hörn inom tolerans. Bädd höjdjusterad");
LSTR MSG_BED_TRAMMING_GOOD_POINTS = _UxGT("Bra punkter: ");
LSTR MSG_BED_TRAMMING_LAST_Z = _UxGT("Senaste Z: ");
LSTR MSG_NEXT_CORNER = _UxGT("Nästa Hörn");
LSTR MSG_MESH_EDITOR = _UxGT("Nät Redigerare");
LSTR MSG_EDIT_MESH = _UxGT("Redigera Nät");
LSTR MSG_EDITING_STOPPED = _UxGT("Nätredigering Stoppad");
LSTR MSG_PROBING_POINT = _UxGT("Sonderingspunkt");
LSTR MSG_NEXT_CORNER = _UxGT("Nästa hörn");
LSTR MSG_MESH_EDITOR = _UxGT("Meshnätredigerare");
LSTR MSG_EDIT_MESH = _UxGT("Redigera meshnät");
LSTR MSG_EDITING_STOPPED = _UxGT("Meshnätredigering stoppad");
LSTR MSG_PROBING_POINT = _UxGT("Höjdmätpunkt");
LSTR MSG_MESH_X = _UxGT("Index X");
LSTR MSG_MESH_Y = _UxGT("Index Y");
LSTR MSG_MESH_EDIT_Z = _UxGT("Z Värde");
LSTR MSG_USER_MENU = _UxGT("Anpassade Kommandon");
LSTR MSG_M48_TEST = _UxGT("M48 Sond Test");
LSTR MSG_M48_POINT = _UxGT("M48 Punkt");
LSTR MSG_M48_OUT_OF_BOUNDS = _UxGT("Sond utan för gränser");
LSTR MSG_MESH_EDIT_Z = _UxGT("Z-värde");
LSTR MSG_USER_MENU = _UxGT("Anpassade kommandon");
LSTR MSG_M48_TEST = _UxGT("M48 probtest");
LSTR MSG_M48_POINT = _UxGT("M48 punkt");
LSTR MSG_M48_OUT_OF_BOUNDS = _UxGT("Mätprob utanför tolerans");
LSTR MSG_M48_DEVIATION = _UxGT("Avvikelse");
LSTR MSG_IDEX_MENU = _UxGT("IDEX Läge");
LSTR MSG_IDEX_MENU = _UxGT("IDEX läge");
LSTR MSG_OFFSETS_MENU = _UxGT("Verktygsoffset");
LSTR MSG_IDEX_MODE_AUTOPARK = _UxGT("Auto-Parkera");
LSTR MSG_IDEX_MODE_AUTOPARK = _UxGT("Autoparkera");
LSTR MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplicering");
LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Speglad Kopia");
LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Full Kontroll");
LSTR MSG_IDEX_DUPE_GAP = _UxGT("Duplicera X-Avstånd");
LSTR MSG_HOTEND_OFFSET_Z = _UxGT("2:a Munstycke Z");
LSTR MSG_HOTEND_OFFSET_N = _UxGT("2:a Munstycke @");
LSTR MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Speglad kopia");
LSTR MSG_IDEX_MODE_FULL_CTRL = _UxGT("Full kontroll");
LSTR MSG_IDEX_DUPE_GAP = _UxGT("Duplicera X-avstånd");
LSTR MSG_HOTEND_OFFSET_Z = _UxGT("2:a munstycke Z");
LSTR MSG_HOTEND_OFFSET_N = _UxGT("2:a munstycke @");
LSTR MSG_UBL_DOING_G29 = _UxGT("Utför G29");
LSTR MSG_UBL_TOOLS = _UxGT("UBL Verktyg");
LSTR MSG_UBL_TOOLS = _UxGT("UBL verktyg");
LSTR MSG_LCD_TILTING_MESH = _UxGT("Lutningspunkt");
LSTR MSG_UBL_MANUAL_MESH = _UxGT("Manuellt skapa nät");
LSTR MSG_UBL_BC_INSERT = _UxGT("Placera Shim & Mät");
LSTR MSG_UBL_MANUAL_MESH = _UxGT("Skapa manuellt meshnät");
LSTR MSG_UBL_BC_INSERT = _UxGT("Placera shims & mät");
LSTR MSG_UBL_BC_INSERT2 = _UxGT("Mät");
LSTR MSG_UBL_BC_REMOVE = _UxGT("Ta bort & Mät bädd");
LSTR MSG_UBL_MOVING_TO_NEXT = _UxGT("Flyttar till nästa");
LSTR MSG_UBL_SET_TEMP_BED = _UxGT("Bädd Temp");
LSTR MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Bädd Temp");
LSTR MSG_UBL_SET_TEMP_HOTEND = _UxGT("Hetände Temp");
LSTR MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Hetände Temp");
LSTR MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Redigera Anpassat Nät");
LSTR MSG_UBL_FINE_TUNE_MESH = _UxGT("Finjustera Nät");
LSTR MSG_UBL_DONE_EDITING_MESH = _UxGT("Färdig Redigera Nät");
LSTR MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Bygg Anpassat Nät");
LSTR MSG_UBL_BUILD_MESH_MENU = _UxGT("Bygg Nät");
LSTR MSG_UBL_BUILD_MESH_M = _UxGT("Bygg Nät ($)");
LSTR MSG_UBL_BUILD_COLD_MESH = _UxGT("Bygg Kallt Nät");
LSTR MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Justera Nät Höjd");
LSTR MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Höjd Antal");
LSTR MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Validera Nät");
LSTR MSG_UBL_VALIDATE_MESH_M = _UxGT("Validera Nät ($)");
LSTR MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Validera Anpassat Nät");
LSTR MSG_G26_HEATING_BED = _UxGT("G26 Värma Bädd");
LSTR MSG_G26_HEATING_NOZZLE = _UxGT("G26 Värma Munstycke");
LSTR MSG_G26_MANUAL_PRIME = _UxGT("Manuel grundning...");
LSTR MSG_G26_FIXED_LENGTH = _UxGT("Fastlängd Grundning");
LSTR MSG_G26_PRIME_DONE = _UxGT("Färdig Grundning");
LSTR MSG_UBL_BC_REMOVE = _UxGT("Ta bort & mät bädd");
LSTR MSG_UBL_MOVING_TO_NEXT = _UxGT("Går vidare till nästa");
LSTR MSG_UBL_SET_TEMP_BED = _UxGT("Bäddtemperatur");
LSTR MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Bäddtemperatur");
LSTR MSG_UBL_SET_TEMP_HOTEND = _UxGT("Temperatur munstycke");
LSTR MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Temperatur munstycke");
LSTR MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Redigera anpassat meshnät");
LSTR MSG_UBL_FINE_TUNE_MESH = _UxGT("Finjustera meshnät");
LSTR MSG_UBL_DONE_EDITING_MESH = _UxGT("Redigering meshnät slutförd");
LSTR MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Bygg anpassat meshnät");
LSTR MSG_UBL_BUILD_MESH_MENU = _UxGT("Bygg meshnät");
LSTR MSG_UBL_BUILD_MESH_M = _UxGT("Bygg meshnät ($)");
LSTR MSG_UBL_BUILD_COLD_MESH = _UxGT("Bygg meshnät kallt");
LSTR MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Justera höjd på meshnät");
LSTR MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Höjdantal");
LSTR MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Validera meshnät");
LSTR MSG_UBL_VALIDATE_MESH_M = _UxGT("Validera meshnät ($)");
LSTR MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Validera anpassat meshnät");
LSTR MSG_G26_HEATING_BED = _UxGT("G26 Värm bädd");
LSTR MSG_G26_HEATING_NOZZLE = _UxGT("G26 Värm munstycke");
LSTR MSG_G26_MANUAL_PRIME = _UxGT("Manuell grundinställning...");
LSTR MSG_G26_FIXED_LENGTH = _UxGT("Fast längd grundinställning");
LSTR MSG_G26_PRIME_DONE = _UxGT("Grundinställning klar");
LSTR MSG_G26_CANCELED = _UxGT("G26 Avbruten");
LSTR MSG_G26_LEAVING = _UxGT("Nivellera G26");
LSTR MSG_UBL_CONTINUE_MESH = _UxGT("Fortsätt Bädd Nät");
LSTR MSG_UBL_MESH_LEVELING = _UxGT("Nät Nivellering");
LSTR MSG_UBL_3POINT_MESH_LEVELING = _UxGT("3-Punkts Nivellering");
LSTR MSG_UBL_GRID_MESH_LEVELING = _UxGT("Rutnät Nivellering");
LSTR MSG_UBL_MESH_LEVEL = _UxGT("Nivellera Nät");
LSTR MSG_G26_LEAVING = _UxGT("Höjdjustera G26");
LSTR MSG_UBL_CONTINUE_MESH = _UxGT("Fortsätt bädd meshnät");
LSTR MSG_UBL_MESH_LEVELING = _UxGT("Meshnät höjdjustering");
LSTR MSG_UBL_3POINT_MESH_LEVELING = _UxGT("3-punkts höjdjustering");
LSTR MSG_UBL_GRID_MESH_LEVELING = _UxGT("Höjdjustering av rutnät");
LSTR MSG_UBL_MESH_LEVEL = _UxGT("Höjdjustera meshnät");
LSTR MSG_UBL_SIDE_POINTS = _UxGT("Sidopunkter");
LSTR MSG_UBL_MAP_TYPE = _UxGT("Kart Typ");
LSTR MSG_UBL_OUTPUT_MAP = _UxGT("Utmatning Nät Map");
LSTR MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Utmatning för Värd");
LSTR MSG_UBL_MAP_TYPE = _UxGT("Karttyp");
LSTR MSG_UBL_OUTPUT_MAP = _UxGT("Utmatning meshnätkarta");
LSTR MSG_UBL_OUTPUT_MAP_HOST = _UxGT("Utmatning för värd");
LSTR MSG_UBL_OUTPUT_MAP_CSV = _UxGT("Utmatning för CSV");
LSTR MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Utanför skrivare Backup");
LSTR MSG_UBL_INFO_UBL = _UxGT("Utmatning UBL Info");
LSTR MSG_UBL_FILLIN_AMOUNT = _UxGT("Ifyllnad Mängd");
LSTR MSG_UBL_MANUAL_FILLIN = _UxGT("Manuell Ifyllnad");
LSTR MSG_UBL_SMART_FILLIN = _UxGT("Smart Ifyllnad");
LSTR MSG_UBL_FILLIN_MESH = _UxGT("Ifyllnad Nät");
LSTR MSG_UBL_INVALIDATE_ALL = _UxGT("Ogiltigförklara Alla");
LSTR MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Ogiltigförklara Närmast");
LSTR MSG_UBL_FINE_TUNE_ALL = _UxGT("Finjustera Alla");
LSTR MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Finjustera Närmast");
LSTR MSG_UBL_STORAGE_MESH_MENU = _UxGT("Nät Lagra");
LSTR MSG_UBL_STORAGE_SLOT = _UxGT("Minnesöppning");
LSTR MSG_UBL_LOAD_MESH = _UxGT("Ladda Bädd Nät");
LSTR MSG_UBL_SAVE_MESH = _UxGT("Spara Bädd Nät");
LSTR MSG_MESH_LOADED = _UxGT("Nät %i Ladda");
LSTR MSG_MESH_SAVED = _UxGT("Nät %i Sparad");
LSTR MSG_UBL_NO_STORAGE = _UxGT("Ingen Lagring");
LSTR MSG_UBL_SAVE_ERROR = _UxGT("Fel: UBL Sparad");
LSTR MSG_UBL_RESTORE_ERROR = _UxGT("Fel: UBL Återställd");
LSTR MSG_UBL_Z_OFFSET = _UxGT("Z-Offset: ");
LSTR MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Z-Offset Stoppad");
LSTR MSG_UBL_STEP_BY_STEP_MENU = _UxGT("Steg-för-Steg UBL");
LSTR MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1. Bygg Kallt Nät");
LSTR MSG_UBL_2_SMART_FILLIN = _UxGT("2. Smart Ifyllnad");
LSTR MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3. Validera Nät");
LSTR MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4. Finjustera Alla");
LSTR MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5. Validera Nät");
LSTR MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6. Finjustera Alla");
LSTR MSG_UBL_7_SAVE_MESH = _UxGT("7. Spara Bädd Nät");
LSTR MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Utanför skrivare backup");
LSTR MSG_UBL_INFO_UBL = _UxGT("Utmatning UBL info");
LSTR MSG_UBL_FILLIN_AMOUNT = _UxGT("Ifyllnadsmängd");
LSTR MSG_UBL_MANUAL_FILLIN = _UxGT("Manuell ifyllnad");
LSTR MSG_UBL_SMART_FILLIN = _UxGT("Smart ifyllnad");
LSTR MSG_UBL_FILLIN_MESH = _UxGT("Ifyllnad meshnät");
LSTR MSG_UBL_INVALIDATE_ALL = _UxGT("Ogiltigförklara alla");
LSTR MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Ogiltigförklara närmast");
LSTR MSG_UBL_FINE_TUNE_ALL = _UxGT("Finjustera alla");
LSTR MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Finjustera närmast");
LSTR MSG_UBL_STORAGE_MESH_MENU = _UxGT("Meshnätlagring");
LSTR MSG_UBL_STORAGE_SLOT = _UxGT("Minnesfack");
LSTR MSG_UBL_LOAD_MESH = _UxGT("Ladda bädd meshnät");
LSTR MSG_UBL_SAVE_MESH = _UxGT("Spara bädd meshnät");
LSTR MSG_MESH_LOADED = _UxGT("Meshnät %i laddad");
LSTR MSG_MESH_SAVED = _UxGT("Meshnät %i sparad");
LSTR MSG_UBL_NO_STORAGE = _UxGT("Inget lagringsutrymme");
LSTR MSG_UBL_SAVE_ERROR = _UxGT("Fel när UBL skulle sparas");
LSTR MSG_UBL_RESTORE_ERROR = _UxGT("Fel när UBL skulle återställas");
LSTR MSG_UBL_Z_OFFSET = _UxGT("Z-offset: ");
LSTR MSG_UBL_Z_OFFSET_STOPPED = _UxGT("Z-offset stoppad");
LSTR MSG_UBL_STEP_BY_STEP_MENU = _UxGT("Steg för steg UBL");
LSTR MSG_UBL_1_BUILD_COLD_MESH = _UxGT("1. Bygg meshnät kallt");
LSTR MSG_UBL_2_SMART_FILLIN = _UxGT("2. Smart ifyllnad");
LSTR MSG_UBL_3_VALIDATE_MESH_MENU = _UxGT("3. Validera meshnät");
LSTR MSG_UBL_4_FINE_TUNE_ALL = _UxGT("4. Finjustera alla");
LSTR MSG_UBL_5_VALIDATE_MESH_MENU = _UxGT("5. Validera meshnät");
LSTR MSG_UBL_6_FINE_TUNE_ALL = _UxGT("6. Finjustera alla");
LSTR MSG_UBL_7_SAVE_MESH = _UxGT("7. Spara bädd meshnät");
LSTR MSG_LED_CONTROL = _UxGT("LED Kontroll");
LSTR MSG_LED_CONTROL = _UxGT("LED-kontroll");
LSTR MSG_LIGHTS = _UxGT("Ljus");
LSTR MSG_LIGHT_N = _UxGT("Ljus #{");
LSTR MSG_LED_PRESETS = _UxGT("Ljus Förinställd");
LSTR MSG_SET_LEDS_RED = _UxGT("d");
LSTR MSG_LED_PRESETS = _UxGT("Förinställt ljus");
LSTR MSG_SET_LEDS_RED = _UxGT("tt");
LSTR MSG_SET_LEDS_ORANGE = _UxGT("Orange");
LSTR MSG_SET_LEDS_YELLOW = _UxGT("Gul");
LSTR MSG_SET_LEDS_GREEN = _UxGT("Grön");
LSTR MSG_SET_LEDS_BLUE = _UxGT("Blå");
LSTR MSG_SET_LEDS_YELLOW = _UxGT("Gult");
LSTR MSG_SET_LEDS_GREEN = _UxGT("Grönt");
LSTR MSG_SET_LEDS_BLUE = _UxGT("Blått");
LSTR MSG_SET_LEDS_INDIGO = _UxGT("Indigo");
LSTR MSG_SET_LEDS_VIOLET = _UxGT("Violet");
LSTR MSG_SET_LEDS_VIOLET = _UxGT("Lila");
LSTR MSG_SET_LEDS_WHITE = _UxGT("Vitt");
LSTR MSG_SET_LEDS_DEFAULT = _UxGT("Standard");
LSTR MSG_LED_CHANNEL_N = _UxGT("Kanal {");
LSTR MSG_NEO2_PRESETS = _UxGT("Ljus #2 Förinställd");
LSTR MSG_NEO2_PRESETS = _UxGT("Ljus #2 förinställd");
LSTR MSG_NEO2_BRIGHTNESS = _UxGT("Ljusstyrka");
LSTR MSG_CUSTOM_LEDS = _UxGT("Anpassat Ljus");
LSTR MSG_INTENSITY_R = _UxGT("Rör Intensitet");
LSTR MSG_INTENSITY_G = _UxGT("Grön Intensitet");
LSTR MSG_INTENSITY_B = _UxGT("Blå Intensitet");
LSTR MSG_INTENSITY_W = _UxGT("Vit Intensitet");
LSTR MSG_LED_BRIGHTNESS = _UxGT("Brightness");
LSTR MSG_CUSTOM_LEDS = _UxGT("Anpassat ljus");
LSTR MSG_INTENSITY_R = _UxGT("Ljusstyrka rött");
LSTR MSG_INTENSITY_G = _UxGT("Ljusstyrka grönt");
LSTR MSG_INTENSITY_B = _UxGT("Ljusstyrka blått");
LSTR MSG_INTENSITY_W = _UxGT("Ljusstyrka vitt");
LSTR MSG_LED_BRIGHTNESS = _UxGT("Ljusstyrka");
LSTR MSG_MOVING = _UxGT("Flyttar...");
LSTR MSG_MOVING = _UxGT("Förflyttar...");
LSTR MSG_FREE_XY = _UxGT("Fri XY");
LSTR MSG_MOVE_X = _UxGT("Flytta X");
LSTR MSG_MOVE_Y = _UxGT("Flytta Y");
LSTR MSG_MOVE_Z = _UxGT("Flytta Z");
LSTR MSG_MOVE_N = _UxGT("Flytta @");
LSTR MSG_MOVE_E = _UxGT("Extruder");
LSTR MSG_MOVE_X = _UxGT("Förflytta X");
LSTR MSG_MOVE_Y = _UxGT("Förflytta Y");
LSTR MSG_MOVE_Z = _UxGT("Förflytta Z");
LSTR MSG_MOVE_N = _UxGT("Förflytta @");
LSTR MSG_MOVE_E = _UxGT("Kör extruder");
LSTR MSG_MOVE_EN = _UxGT("Extruder *");
LSTR MSG_HOTEND_TOO_COLD = _UxGT("Hetände för kall");
LSTR MSG_MOVE_N_MM = _UxGT("Flytta $mm");
LSTR MSG_HOTEND_TOO_COLD = _UxGT("Ej uppnådd temperatur munstycke");
LSTR MSG_MOVE_N_MM = _UxGT("Förflytta $mm");
LSTR MSG_MOVE_N_IN = _UxGT("Flytta $in");
LSTR MSG_MOVE_N_DEG = _UxGT("Flytta $") LCD_STR_DEGREE;
LSTR MSG_SPEED = _UxGT("Hastighet");
LSTR MSG_MESH_Z_OFFSET = _UxGT("Bädd Z");
LSTR MSG_NOZZLE = _UxGT("Munstycke");
LSTR MSG_NOZZLE_N = _UxGT("Munstycke ~");
LSTR MSG_NOZZLE_PARKED = _UxGT("Munstycke Parkerad");
LSTR MSG_NOZZLE_STANDBY = _UxGT("Munstycke Standby");
LSTR MSG_NOZZLE_PARKED = _UxGT("Munstycke parkerat");
LSTR MSG_NOZZLE_STANDBY = _UxGT("Munstycke standby");
LSTR MSG_BED = _UxGT("Bädd");
LSTR MSG_CHAMBER = _UxGT("Inkapsling");
LSTR MSG_FAN_SPEED = _UxGT("Fläkt Hastighet");
LSTR MSG_FAN_SPEED_N = _UxGT("Fläkt Hastighet ~");
LSTR MSG_STORED_FAN_N = _UxGT("Lagrad Fläkt ~");
LSTR MSG_EXTRA_FAN_SPEED = _UxGT("Extra Fläkt Hastighet");
LSTR MSG_EXTRA_FAN_SPEED_N = _UxGT("Extra Fläkt Hastighet ~");
LSTR MSG_CONTROLLER_FAN = _UxGT("Kontroller Fläkt");
LSTR MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Overksam Hastighet");
LSTR MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Auto läga");
LSTR MSG_CONTROLLER_FAN_SPEED = _UxGT("Aktive Hastighet");
LSTR MSG_CONTROLLER_FAN_DURATION = _UxGT("Overksam Period");
LSTR MSG_FAN_SPEED = _UxGT("Fläktvarvtal");
LSTR MSG_FAN_SPEED_N = _UxGT("Fläktvarvtal ~");
LSTR MSG_STORED_FAN_N = _UxGT("Sparad fläkt ~");
LSTR MSG_EXTRA_FAN_SPEED = _UxGT("Varvtal extrafläkt");
LSTR MSG_EXTRA_FAN_SPEED_N = _UxGT("Varvtal extrafläkt ~");
LSTR MSG_CONTROLLER_FAN = _UxGT("Fläktstyrning");
LSTR MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Tomgångsvarvtal fläkt");
LSTR MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Autoläge");
LSTR MSG_CONTROLLER_FAN_SPEED = _UxGT("Aktivt varvtal");
LSTR MSG_CONTROLLER_FAN_DURATION = _UxGT("Tomgångsperiod");
LSTR MSG_FLOW = _UxGT("Flöde");
LSTR MSG_FLOW_N = _UxGT("Flöde ~");
LSTR MSG_CONTROL = _UxGT("Kontroll");
LSTR MSG_CONTROL = _UxGT("Styrning");
LSTR MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min");
LSTR MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max");
LSTR MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Fakt");
LSTR MSG_AUTOTEMP = _UxGT("Autotemp");
LSTR MSG_LCD_ON = _UxGT("");
LSTR MSG_LCD_OFF = _UxGT("Av");
LSTR MSG_PID_AUTOTUNE = _UxGT("PID Autojustera");
LSTR MSG_PID_AUTOTUNE_E = _UxGT("PID Autojustera *");
LSTR MSG_PID_AUTOTUNE_DONE = _UxGT("PID tuning done");
LSTR MSG_PID_BAD_HEATER_ID = _UxGT("Autojustera misslyckad! Dålig extruder.");
LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Autojustera misslyckad! Temperatur för hög.");
LSTR MSG_PID_TIMEOUT = _UxGT("Autojustera misslyckad! Tidsgräns.");
LSTR MSG_AUTOTEMP = _UxGT("Autotemperatur");
LSTR MSG_LCD_ON = _UxGT("Till");
LSTR MSG_LCD_OFF = _UxGT("Från");
LSTR MSG_PID_AUTOTUNE = _UxGT("PID automappning");
LSTR MSG_PID_AUTOTUNE_E = _UxGT("PID automappning *");
LSTR MSG_PID_AUTOTUNE_DONE = _UxGT("PID-mappninging klar");
LSTR MSG_PID_BAD_HEATER_ID = _UxGT("Automappning misslyckad! Kass extruder.");
LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Automappning misslyckad! Temperatur för hög.");
LSTR MSG_PID_TIMEOUT = _UxGT("Automappning misslyckad! Tidsgräns överskriden.");
LSTR MSG_SELECT_E = _UxGT("Välj *");
LSTR MSG_ACC = _UxGT("Accel");
LSTR MSG_JERK = _UxGT("Ryck");
@ -292,71 +316,71 @@ namespace LanguageNarrow_sv {
LSTR MSG_VC_JERK = _UxGT("V") STR_C _UxGT("-Ryck");
LSTR MSG_VN_JERK = _UxGT("V@-Ryck");
LSTR MSG_VE_JERK = _UxGT("Ve-Ryck");
LSTR MSG_JUNCTION_DEVIATION = _UxGT("Knutpunkt Avv");
LSTR MSG_MAX_SPEED = _UxGT("Hastighet");
LSTR MSG_JUNCTION_DEVIATION = _UxGT("Knutpunkt avv");
LSTR MSG_MAX_SPEED = _UxGT("Toppfart (mm/s)");
LSTR MSG_VMAX_A = _UxGT("Vmax ") STR_A;
LSTR MSG_VMAX_B = _UxGT("Vmax ") STR_B;
LSTR MSG_VMAX_C = _UxGT("Vmax ") STR_C;
LSTR MSG_VMAX_N = _UxGT("Vmax @");
LSTR MSG_VMAX_E = _UxGT("Vmax E");
LSTR MSG_VMAX_EN = _UxGT("Vmax *");
LSTR MSG_VMIN = _UxGT("Vmin");
LSTR MSG_VTRAV_MIN = _UxGT("VTrav Min");
LSTR MSG_VMAX_N = _UxGT("Toppfart @");
LSTR MSG_VMAX_E = _UxGT("Toppfart E");
LSTR MSG_VMAX_EN = _UxGT("Toppfart *");
LSTR MSG_VMIN = _UxGT("Lägsta hastighet");
LSTR MSG_VTRAV_MIN = _UxGT("Lägsta förflyttningshastighet");
LSTR MSG_ACCELERATION = _UxGT("Acceleration");
LSTR MSG_AMAX_A = _UxGT("Amax ") STR_A;
LSTR MSG_AMAX_B = _UxGT("Amax ") STR_B;
LSTR MSG_AMAX_C = _UxGT("Amax ") STR_C;
LSTR MSG_AMAX_N = _UxGT("Amax @");
LSTR MSG_AMAX_E = _UxGT("Amax E");
LSTR MSG_AMAX_EN = _UxGT("Amax *");
LSTR MSG_A_RETRACT = _UxGT("A-Dra tillbaka");
LSTR MSG_A_TRAVEL = _UxGT("A-Färdas");
LSTR MSG_XY_FREQUENCY_LIMIT = _UxGT("Frekvens max");
LSTR MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Flöde min");
LSTR MSG_AMAX_N = _UxGT("Högsta acceleration @");
LSTR MSG_AMAX_E = _UxGT("Högsta acceleration E");
LSTR MSG_AMAX_EN = _UxGT("Högsta acceleration *");
LSTR MSG_A_RETRACT = _UxGT("Sugacceleration");
LSTR MSG_A_TRAVEL = _UxGT("Förflyttningsacceleration");
LSTR MSG_XY_FREQUENCY_LIMIT = _UxGT("Frekvensbegränsning XY");
LSTR MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Min frekvensfaktor");
LSTR MSG_STEPS_PER_MM = _UxGT("Steg/mm");
LSTR MSG_A_STEPS = STR_A _UxGT(" Steg/mm");
LSTR MSG_B_STEPS = STR_B _UxGT(" Steg/mm");
LSTR MSG_C_STEPS = STR_C _UxGT(" Steg/mm");
LSTR MSG_N_STEPS = _UxGT("@ Steg/mm");
LSTR MSG_E_STEPS = _UxGT("E Steg/mm");
LSTR MSG_EN_STEPS = _UxGT("* Steg/mm");
LSTR MSG_N_STEPS = _UxGT("@ steg/mm");
LSTR MSG_E_STEPS = _UxGT("E steg/mm");
LSTR MSG_EN_STEPS = _UxGT("* steg/mm");
LSTR MSG_TEMPERATURE = _UxGT("Temperatur");
LSTR MSG_MOTION = _UxGT("Rörelse");
LSTR MSG_FILAMENT = _UxGT("Tråd");
LSTR MSG_VOLUMETRIC_ENABLED = _UxGT("E i mm³");
LSTR MSG_VOLUMETRIC_LIMIT = _UxGT("E Gräns i mm³");
LSTR MSG_VOLUMETRIC_LIMIT_E = _UxGT("E Gräns *");
LSTR MSG_FILAMENT_DIAM = _UxGT("Tråd Dia.");
LSTR MSG_FILAMENT_DIAM_E = _UxGT("Tråd Dia. *");
LSTR MSG_FILAMENT_UNLOAD = _UxGT("Lossa mm");
LSTR MSG_VOLUMETRIC_LIMIT = _UxGT("E-gräns i mm³");
LSTR MSG_VOLUMETRIC_LIMIT_E = _UxGT("E-gräns *");
LSTR MSG_FILAMENT_DIAM = _UxGT("Tråddiameter.");
LSTR MSG_FILAMENT_DIAM_E = _UxGT("Tråddiameter. *");
LSTR MSG_FILAMENT_UNLOAD = _UxGT("Frigör mm");
LSTR MSG_FILAMENT_LOAD = _UxGT("Ladda mm");
LSTR MSG_ADVANCE_K = _UxGT("Advancera K");
LSTR MSG_ADVANCE_K_E = _UxGT("Advancera K *");
LSTR MSG_CONTRAST = _UxGT("LCD Kontrast");
LSTR MSG_STORE_EEPROM = _UxGT("Spara Inställningar");
LSTR MSG_LOAD_EEPROM = _UxGT("Ladda Inställningar");
LSTR MSG_RESTORE_DEFAULTS = _UxGT("Återställ Standard");
LSTR MSG_ADVANCE_K = _UxGT("Avancera K");
LSTR MSG_ADVANCE_K_E = _UxGT("Avancera K *");
LSTR MSG_CONTRAST = _UxGT("Kontrast LCD");
LSTR MSG_STORE_EEPROM = _UxGT("Spara inställningar");
LSTR MSG_LOAD_EEPROM = _UxGT("Ladda inställningar");
LSTR MSG_RESTORE_DEFAULTS = _UxGT("Återställ till grundinställning");
LSTR MSG_INIT_EEPROM = _UxGT("Initiera EEPROM");
LSTR MSG_ERR_EEPROM_CRC = _UxGT("EEPROM CRC Fel");
LSTR MSG_ERR_EEPROM_SIZE = _UxGT("EEPROM Storlek Fel");
LSTR MSG_ERR_EEPROM_VERSION = _UxGT("EEPROM Version Fel");
LSTR MSG_SETTINGS_STORED = _UxGT("Inställningar Lagrad");
LSTR MSG_MEDIA_UPDATE = _UxGT("Media Uppdatera");
LSTR MSG_RESET_PRINTER = _UxGT("Återställ Skrivare");
LSTR MSG_ERR_EEPROM_CRC = _UxGT("EEPROM CRC fel");
LSTR MSG_ERR_EEPROM_SIZE = _UxGT("EEPROM-storlek fel");
LSTR MSG_ERR_EEPROM_VERSION = _UxGT("EEPROM-version fel");
LSTR MSG_SETTINGS_STORED = _UxGT("Inställningar sparade");
LSTR MSG_MEDIA_UPDATE = _UxGT("Uppdatera minneskort");
LSTR MSG_RESET_PRINTER = _UxGT("Starta om 3D-skrivare");
LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("Uppdatera");
LSTR MSG_INFO_SCREEN = _UxGT("Info Skärm");
LSTR MSG_INFO_SCREEN = _UxGT("Infoskärm");
LSTR MSG_PREPARE = _UxGT("Förbered");
LSTR MSG_TUNE = _UxGT("Justera");
LSTR MSG_POWER_MONITOR = _UxGT("Ström övervakning");
LSTR MSG_POWER_MONITOR = _UxGT("Strömövervakning");
LSTR MSG_CURRENT = _UxGT("Ström");
LSTR MSG_VOLTAGE = _UxGT("Spänning");
LSTR MSG_POWER = _UxGT("Ström");
LSTR MSG_START_PRINT = _UxGT("Start Utskrift");
LSTR MSG_POWER = _UxGT("Effekt");
LSTR MSG_START_PRINT = _UxGT("Starta utskrift");
LSTR MSG_BUTTON_NEXT = _UxGT("Nästa");
LSTR MSG_BUTTON_INIT = _UxGT("Initiera");
LSTR MSG_BUTTON_STOP = _UxGT("Stoppa");
LSTR MSG_BUTTON_PRINT = _UxGT("Skriv");
LSTR MSG_BUTTON_RESET = _UxGT("Återställa");
LSTR MSG_BUTTON_RESET = _UxGT("Återställ");
LSTR MSG_BUTTON_IGNORE = _UxGT("Ignorera");
LSTR MSG_BUTTON_CANCEL = _UxGT("Avbryt");
LSTR MSG_BUTTON_DONE = _UxGT("Färdig");
@ -364,213 +388,220 @@ namespace LanguageNarrow_sv {
LSTR MSG_BUTTON_PROCEED = _UxGT("Fortsätt");
LSTR MSG_BUTTON_SKIP = _UxGT("Hoppa över");
LSTR MSG_PAUSING = _UxGT("Paus..");
LSTR MSG_PAUSE_PRINT = _UxGT("Pausera Utskrift");
LSTR MSG_RESUME_PRINT = _UxGT("Återuppta Utskrift");
LSTR MSG_HOST_START_PRINT = _UxGT("Värd Start");
LSTR MSG_STOP_PRINT = _UxGT("Stoppa Utskrift");
LSTR MSG_END_LOOPS = _UxGT("Slut Upprepningsloop");
LSTR MSG_PRINTING_OBJECT = _UxGT("Skriver Objekt");
LSTR MSG_CANCEL_OBJECT = _UxGT("Avbryt Objekt");
LSTR MSG_CANCEL_OBJECT_N = _UxGT("Avbryt Objekt {");
LSTR MSG_OUTAGE_RECOVERY = _UxGT("Ström Avbrott");
LSTR MSG_MEDIA_MENU = _UxGT("Skriv fråm Media");
LSTR MSG_NO_MEDIA = _UxGT("Inget Media");
LSTR MSG_PAUSE_PRINT = _UxGT("Pausa utskrift");
LSTR MSG_RESUME_PRINT = _UxGT("Återuppta utskrift");
LSTR MSG_HOST_START_PRINT = _UxGT("Värd start");
LSTR MSG_STOP_PRINT = _UxGT("Stoppa utskrift");
LSTR MSG_END_LOOPS = _UxGT("Slut upprepningsloop");
LSTR MSG_PRINTING_OBJECT = _UxGT("Skriver objekt");
LSTR MSG_CANCEL_OBJECT = _UxGT("Avbryt objekt");
LSTR MSG_CANCEL_OBJECT_N = _UxGT("Avbryt objekt {");
LSTR MSG_OUTAGE_RECOVERY = _UxGT("Strömavbrott");
LSTR MSG_MEDIA_MENU = _UxGT("Skriv från minneskort");
LSTR MSG_NO_MEDIA = _UxGT("Inget minneskort");
LSTR MSG_DWELL = _UxGT("Sov...");
LSTR MSG_USERWAIT = _UxGT("Klick för att återuppta...");
LSTR MSG_PRINT_PAUSED = _UxGT("Utskrift Pausad");
LSTR MSG_USERWAIT = _UxGT("Klicka för att återuppta...");
LSTR MSG_PRINT_PAUSED = _UxGT("Utskrift pausad");
LSTR MSG_PRINTING = _UxGT("Skriver...");
LSTR MSG_PRINT_ABORTED = _UxGT("Utskrift Avbruten");
LSTR MSG_PRINT_DONE = _UxGT("Utskrift Färdig");
LSTR MSG_NO_MOVE = _UxGT("Ingen Flytt.");
LSTR MSG_PRINT_ABORTED = _UxGT("Utskrift avbruten");
LSTR MSG_PRINT_DONE = _UxGT("Utskrift slutförd");
LSTR MSG_NO_MOVE = _UxGT("Ingen förflyttning.");
LSTR MSG_KILLED = _UxGT("DÖDAD. ");
LSTR MSG_STOPPED = _UxGT("STOPPAD. ");
LSTR MSG_CONTROL_RETRACT = _UxGT("Dra tillbaka mm");
LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Byt Dra.mm");
LSTR MSG_CONTROL_RETRACTF = _UxGT("Dra tillbaka V");
LSTR MSG_CONTROL_RETRACT = _UxGT("Sug tillbaka mm");
LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Byt sug.mm");
LSTR MSG_CONTROL_RETRACTF = _UxGT("Sug tillbaka V");
LSTR MSG_CONTROL_RETRACT_ZHOP = _UxGT("Hoppa mm");
LSTR MSG_CONTROL_RETRACT_RECOVER = _UxGT("Åter dra tillbaka. mm");
LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Byt åter dra t. mm");
LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Återdrat. V");
LSTR MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("Byt åter dra. V");
LSTR MSG_AUTORETRACT = _UxGT("Auto-Dra-tillbka");
LSTR MSG_FILAMENT_SWAP_LENGTH = _UxGT("Byt Längd");
LSTR MSG_FILAMENT_SWAP_EXTRA = _UxGT("Byt Extra");
LSTR MSG_FILAMENT_PURGE_LENGTH = _UxGT("Rensa Längd");
LSTR MSG_TOOL_CHANGE = _UxGT("Byt verktyg");
LSTR MSG_TOOL_CHANGE_ZLIFT = _UxGT("Z Höj");
LSTR MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Grund Hastighet");
LSTR MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Återgå Hastighet");
LSTR MSG_FILAMENT_PARK_ENABLED = _UxGT("Parkera Huvud");
LSTR MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Återgår Hastighet");
LSTR MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Fläkt Hastighet");
LSTR MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Fläkt Tid");
LSTR MSG_TOOL_MIGRATION_ON = _UxGT("Auto ");
LSTR MSG_TOOL_MIGRATION_OFF = _UxGT("Auto AV");
LSTR MSG_TOOL_MIGRATION = _UxGT("Verktyg Migration");
LSTR MSG_TOOL_MIGRATION_AUTO = _UxGT("Auto-migration");
LSTR MSG_TOOL_MIGRATION_END = _UxGT("Senast Extruder");
LSTR MSG_CONTROL_RETRACT_RECOVER = _UxGT("Åter sug tillbaka. mm");
LSTR MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Byt åter sug t. mm");
LSTR MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Återsugt. V");
LSTR MSG_CONTROL_RETRACT_RECOVER_SWAPF = _UxGT("Byt åter sug. V");
LSTR MSG_AUTORETRACT = _UxGT("Auto sug tillbka");
LSTR MSG_FILAMENT_SWAP_LENGTH = _UxGT("Byt längd");
LSTR MSG_FILAMENT_SWAP_EXTRA = _UxGT("Byt extra");
LSTR MSG_FILAMENT_PURGE_LENGTH = _UxGT("Rensa längd");
LSTR MSG_TOOL_CHANGE = _UxGT("Verktygsbyte");
LSTR MSG_TOOL_CHANGE_ZLIFT = _UxGT("Z höj");
LSTR MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Grundhastighet");
LSTR MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Återgångshastighet");
LSTR MSG_FILAMENT_PARK_ENABLED = _UxGT("Parkera huvud");
LSTR MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Återgångshastighet");
LSTR MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Fläktvarvtal");
LSTR MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Fläkttid");
LSTR MSG_TOOL_MIGRATION_ON = _UxGT("Auto till");
LSTR MSG_TOOL_MIGRATION_OFF = _UxGT("Auto från");
LSTR MSG_TOOL_MIGRATION = _UxGT("Verktyg migration");
LSTR MSG_TOOL_MIGRATION_AUTO = _UxGT("Auto migration");
LSTR MSG_TOOL_MIGRATION_END = _UxGT("Senaste extruder");
LSTR MSG_TOOL_MIGRATION_SWAP = _UxGT("Migrera till *");
LSTR MSG_FILAMENTCHANGE = _UxGT("Byt Tråd");
LSTR MSG_FILAMENTCHANGE_E = _UxGT("Byt Tråd *");
LSTR MSG_FILAMENTLOAD = _UxGT("Ladda Tråd");
LSTR MSG_FILAMENTLOAD_E = _UxGT("Ladda *");
LSTR MSG_FILAMENTUNLOAD = _UxGT("Lossa Tråd");
LSTR MSG_FILAMENTUNLOAD_E = _UxGT("Lossa *");
LSTR MSG_FILAMENTUNLOAD_ALL = _UxGT("Lossa All");
LSTR MSG_FILAMENTCHANGE = _UxGT("Byt tråd");
LSTR MSG_FILAMENTCHANGE_E = _UxGT("Byt tråd *");
LSTR MSG_FILAMENTLOAD = _UxGT("Ladda tråd");
LSTR MSG_FILAMENTLOAD_E = _UxGT("Ladda * tråd");
LSTR MSG_FILAMENTUNLOAD = _UxGT("Lossa tråd");
LSTR MSG_FILAMENTUNLOAD_E = _UxGT("Lossa * tråd");
LSTR MSG_FILAMENTUNLOAD_ALL = _UxGT("Lossa allt");
LSTR MSG_ATTACH_MEDIA = _UxGT("Bifoga SD-kort");
LSTR MSG_ATTACH_MEDIA = _UxGT("Applicera minneskort");
LSTR MSG_ATTACH_SD = _UxGT("Bifoga SD-kort");
LSTR MSG_ATTACH_USB = _UxGT("Bifoga USB-minne");
LSTR MSG_CHANGE_MEDIA = _UxGT("Byt Media");
LSTR MSG_RELEASE_MEDIA = _UxGT("Släpp Media");
LSTR MSG_RUN_AUTOFILES = _UxGT("Autostarta Filer");
LSTR MSG_CHANGE_MEDIA = _UxGT("Byt minneskort");
LSTR MSG_RELEASE_MEDIA = _UxGT("Mata ut minneskort");
LSTR MSG_RUN_AUTOFILES = _UxGT("Autostarta filer");
LSTR MSG_ZPROBE_OUT = _UxGT("Z Sond Utanför Bädd");
LSTR MSG_SKEW_FACTOR = _UxGT("Skev Faktor");
LSTR MSG_ZPROBE_OUT = _UxGT("Z-prob utanför bädd");
LSTR MSG_SKEW_FACTOR = _UxGT("Skevhetsfaktor");
LSTR MSG_BLTOUCH = _UxGT("BLTouch");
LSTR MSG_BLTOUCH_SELFTEST = _UxGT("Själv-Test");
LSTR MSG_BLTOUCH_SELFTEST = _UxGT("Självtest");
LSTR MSG_BLTOUCH_RESET = _UxGT("Återställ");
LSTR MSG_BLTOUCH_STOW = _UxGT("Stuva undan");
LSTR MSG_BLTOUCH_DEPLOY = _UxGT("Fällut");
LSTR MSG_BLTOUCH_SW_MODE = _UxGT("SW-Läge");
LSTR MSG_BLTOUCH_5V_MODE = _UxGT("5V-Läge");
LSTR MSG_BLTOUCH_OD_MODE = _UxGT("OD-Läge");
LSTR MSG_BLTOUCH_MODE_STORE = _UxGT("Läge-gring");
LSTR MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Sätt BLTouch to 5V");
LSTR MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Sätt BLTouch to OD");
LSTR MSG_BLTOUCH_MODE_ECHO = _UxGT("Reportera Dränering");
LSTR MSG_BLTOUCH_MODE_CHANGE = _UxGT("FARA: Dålig inställningar kan orsaka skada! Fortsätt ändå?");
LSTR MSG_BLTOUCH_STOW = _UxGT("Fäll in");
LSTR MSG_BLTOUCH_DEPLOY = _UxGT("Fäll ut");
LSTR MSG_BLTOUCH_SW_MODE = _UxGT("SW-läge");
LSTR MSG_BLTOUCH_5V_MODE = _UxGT("5V-läge");
LSTR MSG_BLTOUCH_OD_MODE = _UxGT("OD-läge");
LSTR MSG_BLTOUCH_MODE_STORE = _UxGT("Läge-lagring");
LSTR MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Sätt BLTouch till 5V");
LSTR MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Sätt BLTouch till OD");
LSTR MSG_BLTOUCH_MODE_ECHO = _UxGT("Reportera tömning");
LSTR MSG_BLTOUCH_MODE_CHANGE = _UxGT("VARNING: Felaktiga inställningar kan orsaka skada! Fortsätt ändå?");
LSTR MSG_TOUCHMI_PROBE = _UxGT("TouchMI");
LSTR MSG_TOUCHMI_INIT = _UxGT("Initiera TouchMI");
LSTR MSG_TOUCHMI_ZTEST = _UxGT("Z Offset Test");
LSTR MSG_TOUCHMI_ZTEST = _UxGT("Test Z-offset");
LSTR MSG_TOUCHMI_SAVE = _UxGT("Spara");
LSTR MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("Fällut TouchMI");
LSTR MSG_MANUAL_DEPLOY = _UxGT("Fällut Z-Sond");
LSTR MSG_MANUAL_STOW = _UxGT("Stuva undan Z-Sond");
LSTR MSG_HOME_FIRST = _UxGT("Hem %s Först");
LSTR MSG_ZPROBE_OFFSETS = _UxGT("Sond Offsets");
LSTR MSG_ZPROBE_XOFFSET = _UxGT("Sond X Offset");
LSTR MSG_ZPROBE_YOFFSET = _UxGT("Sond Y Offset");
LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Sond Z Offset");
LSTR MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("Fäll ut TouchMI");
LSTR MSG_MANUAL_DEPLOY = _UxGT("Fäll ut Z-prob");
LSTR MSG_MANUAL_STOW = _UxGT("Fäll in Z-prob");
LSTR MSG_HOME_FIRST = _UxGT("Hem %s först");
LSTR MSG_ZPROBE_OFFSETS = _UxGT("Offsets mätprob");
LSTR MSG_ZPROBE_XOFFSET = _UxGT("X-offset mätprob");
LSTR MSG_ZPROBE_YOFFSET = _UxGT("Y-offset mätprob");
LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Z-offset mätprob");
LSTR MSG_ZPROBE_OFFSET_N = _UxGT("Sond @ Offset");
LSTR MSG_BABYSTEP_PROBE_Z = _UxGT("Steg Z justering");
LSTR MSG_MOVE_NOZZLE_TO_BED = _UxGT("Flytta Munstycke till Bädd");
LSTR MSG_BABYSTEP_X = _UxGT("Småsteg X");
LSTR MSG_BABYSTEP_Y = _UxGT("Småsteg Y");
LSTR MSG_BABYSTEP_Z = _UxGT("Småsteg Z");
LSTR MSG_BABYSTEP_N = _UxGT("Småsteg @");
LSTR MSG_MOVE_NOZZLE_TO_BED = _UxGT("Förflytta munstycke till bädd");
LSTR MSG_BABYSTEP_X = _UxGT("Microsteg X");
LSTR MSG_BABYSTEP_Y = _UxGT("Microsteg Y");
LSTR MSG_BABYSTEP_Z = _UxGT("Microsteg Z");
LSTR MSG_BABYSTEP_N = _UxGT("Microsteg @");
LSTR MSG_BABYSTEP_TOTAL = _UxGT("Total");
LSTR MSG_ENDSTOP_ABORT = _UxGT("Slutstopp Avbrott");
LSTR MSG_ERR_HEATING_FAILED = _UxGT("Värma Misslyckad");
LSTR MSG_ENDSTOP_ABORT = _UxGT("Ändlägesstopp avbrott");
LSTR MSG_ERR_HEATING_FAILED = _UxGT("Värmning misslyckad");
LSTR MSG_ERR_REDUNDANT_TEMP = _UxGT("Fel: REDUNDANT TEMP");
LSTR MSG_ERR_THERMAL_RUNAWAY = _UxGT("TERMISK ÖVERDRIFT");
LSTR MSG_ERR_MAXTEMP = _UxGT("Fel: MAXTEMP");
LSTR MSG_ERR_MINTEMP = _UxGT("Fel: MINTEMP");
LSTR MSG_HALTED = _UxGT("Utskrift stoppad");
LSTR MSG_PLEASE_RESET = _UxGT("Snälla Återställ");
LSTR MSG_PLEASE_RESET = _UxGT("Vänligen återställ");
LSTR MSG_SHORT_HOUR = _UxGT("t"); // One character only
LSTR MSG_HEATING = _UxGT("Värmer...");
LSTR MSG_COOLING = _UxGT("Kyler...");
LSTR MSG_BED_HEATING = _UxGT("Bädd Värmer...");
LSTR MSG_BED_COOLING = _UxGT("Bädd Kyler...");
LSTR MSG_PROBE_HEATING = _UxGT("Sond Värmer...");
LSTR MSG_PROBE_COOLING = _UxGT("Sond Kyler...");
LSTR MSG_CHAMBER_HEATING = _UxGT("Kammare Värmer...");
LSTR MSG_CHAMBER_COOLING = _UxGT("Kammare Kyler...");
LSTR MSG_DELTA_CALIBRATE = _UxGT("Delta Kalibrering");
LSTR MSG_COOLING = _UxGT("Avkylning...");
LSTR MSG_BED_HEATING = _UxGT("Värmer bädden...");
LSTR MSG_BED_COOLING = _UxGT("Kyler bädden...");
LSTR MSG_PROBE_HEATING = _UxGT("Värmer munstycke...");
LSTR MSG_PROBE_COOLING = _UxGT("Kyler munstycke...");
LSTR MSG_CHAMBER_HEATING = _UxGT("Värmer kammare...");
LSTR MSG_CHAMBER_COOLING = _UxGT("Kyler kammare...");
LSTR MSG_DELTA_CALIBRATE = _UxGT("Deltakalibrering");
LSTR MSG_DELTA_CALIBRATE_X = _UxGT("Kalibrera X");
LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("Kalibrera Y");
LSTR MSG_DELTA_CALIBRATE_Z = _UxGT("Kalibrera Z");
LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Kalibrera Center");
LSTR MSG_DELTA_SETTINGS = _UxGT("Delta Inställningar");
LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto Kalibrering");
LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Kalibrera mittläge");
LSTR MSG_DELTA_SETTINGS = _UxGT("Deltainställningar");
LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Autokalibrering");
LSTR MSG_DELTA_DIAG_ROD = _UxGT("Diag Rod");
LSTR MSG_DELTA_HEIGHT = _UxGT("Höjd");
LSTR MSG_DELTA_RADIUS = _UxGT("Radius");
LSTR MSG_INFO_MENU = _UxGT("Om Skrivaren");
LSTR MSG_INFO_PRINTER_MENU = _UxGT("Skrivare Info");
LSTR MSG_3POINT_LEVELING = _UxGT("3-Punkt Nivellering");
LSTR MSG_LINEAR_LEVELING = _UxGT("Linjär Nivellering");
LSTR MSG_BILINEAR_LEVELING = _UxGT("Bilinjär Nivellering");
LSTR MSG_UBL_LEVELING = _UxGT("Enhetlig Bädd Nivellering (UBL)");
LSTR MSG_MESH_LEVELING = _UxGT("Nät Nivellering");
LSTR MSG_INFO_STATS_MENU = _UxGT("Skrivar Stats");
LSTR MSG_INFO_BOARD_MENU = _UxGT("Kort Info");
LSTR MSG_INFO_THERMISTOR_MENU = _UxGT("Termistor");
LSTR MSG_DELTA_RADIUS = _UxGT("Radie");
LSTR MSG_INFO_MENU = _UxGT("Om skrivaren");
LSTR MSG_INFO_PRINTER_MENU = _UxGT("Skrivarinformation");
LSTR MSG_3POINT_LEVELING = _UxGT("3-Punkts nivåjustering");
LSTR MSG_LINEAR_LEVELING = _UxGT("Linjär nivåjustering");
LSTR MSG_BILINEAR_LEVELING = _UxGT("Bilinjär nivåjustering");
LSTR MSG_UBL_LEVELING = _UxGT("Enhetlig bädd nivåjustering (UBL)");
LSTR MSG_MESH_LEVELING = _UxGT("Meshnät nivåjustering");
LSTR MSG_INFO_STATS_MENU = _UxGT("Skrivarstatistik");
LSTR MSG_INFO_BOARD_MENU = _UxGT("Styrkortsinfo");
LSTR MSG_INFO_THERMISTOR_MENU = _UxGT("Termistorer");
LSTR MSG_INFO_EXTRUDERS = _UxGT("Extruderare");
LSTR MSG_INFO_BAUDRATE = _UxGT("Baud");
LSTR MSG_INFO_BAUDRATE = _UxGT("Datahastighet");
LSTR MSG_INFO_PROTOCOL = _UxGT("Protokoll");
LSTR MSG_INFO_RUNAWAY_OFF = _UxGT("Överdrift Övervakning: AV");
LSTR MSG_INFO_RUNAWAY_ON = _UxGT("Överdrift Övervakning: PÅ");
LSTR MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Hetände Overksam Tidsgräns");
LSTR MSG_INFO_RUNAWAY_OFF = _UxGT("Övertempsövervakning: från");
LSTR MSG_INFO_RUNAWAY_ON = _UxGT("Övertempsövervakning: till");
LSTR MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Tidsgräns värmare munstycke");
LSTR MSG_CASE_LIGHT = _UxGT("Lådljus");
LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Ljus ljusstyrka");
LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("INKORREKT SKRIVARE");
LSTR MSG_CASE_LIGHT = _UxGT("Kapslingsljus");
LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Ljusstyrka belysning");
LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("DEFEKT SKRIVARE");
LSTR MSG_INFO_PRINT_COUNT = _UxGT("Utskrift");
LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Färdig");
LSTR MSG_INFO_PRINT_TIME = _UxGT("Total");
LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Längsta");
LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Extruderad");
LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Slutförda");
LSTR MSG_INFO_PRINT_TIME = _UxGT("Total utskriftstid");
LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Längsta utskriftstid");
LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Total extrudering");
LSTR MSG_INFO_MIN_TEMP = _UxGT("Min Temp");
LSTR MSG_INFO_MAX_TEMP = _UxGT("Max Temp");
LSTR MSG_INFO_MIN_TEMP = _UxGT("Min temperatur");
LSTR MSG_INFO_MAX_TEMP = _UxGT("Max temperatur");
LSTR MSG_INFO_PSU = _UxGT("PSU");
LSTR MSG_DRIVE_STRENGTH = _UxGT("Driv Styrka");
LSTR MSG_DRIVE_STRENGTH = _UxGT("Drivstyrka");
LSTR MSG_DAC_PERCENT_N = _UxGT("@ Driver %");
LSTR MSG_ERROR_TMC = _UxGT("TMC KOPPLNINGSFEL");
LSTR MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM Skriv");
LSTR MSG_ERROR_TMC = _UxGT("TMC KOPPLINGSFEL");
LSTR MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM skriv");
LSTR MSG_FILAMENT_CHANGE_HEADER = _UxGT("TRÅDBYTE");
LSTR MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("UTSKRIFTSPAUSERAD");
LSTR MSG_FILAMENT_CHANGE_HEADER_PAUSE = _UxGT("UTSKRIFT PAUSAD");
LSTR MSG_FILAMENT_CHANGE_HEADER_LOAD = _UxGT("LADDA TRÅD");
LSTR MSG_FILAMENT_CHANGE_HEADER_UNLOAD = _UxGT("LOSSA TRÅD");
LSTR MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("ÅTERGÅ VAÖ:");
LSTR MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("FORTSÄTT ALTERNATIV:");
LSTR MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Rensa mer");
LSTR MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Fortsätt");
LSTR MSG_FILAMENT_CHANGE_PURGE_CONTINUE = _UxGT("Rengör eller fortsätt?");
LSTR MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Munstycke: ");
LSTR MSG_RUNOUT_SENSOR = _UxGT("Utskjut Sensor");
LSTR MSG_RUNOUT_DISTANCE_MM = _UxGT("Utskjut Dist mm");
LSTR MSG_KILL_HOMING_FAILED = _UxGT("Hemning Misslyckad");
LSTR MSG_LCD_PROBING_FAILED = _UxGT("Sondering Misslyckad");
LSTR MSG_RUNOUT_SENSOR = _UxGT("Trådkontrollgivare");
LSTR MSG_RUNOUT_DISTANCE_MM = _UxGT("Förbrukad trådlängd mm");
LSTR MSG_RUNOUT_ENABLE = _UxGT("Aktivera trådövervakning");
LSTR MSG_RUNOUT_ACTIVE = _UxGT("Trådövervakning i drift");
LSTR MSG_INVERT_EXTRUDER = _UxGT("Invertera extruder");
LSTR MSG_EXTRUDER_MIN_TEMP = _UxGT("Extruder Minimumtemp.");
LSTR MSG_FANCHECK = _UxGT("Fläktvarvövervakning");
LSTR MSG_KILL_HOMING_FAILED = _UxGT("Hemkörning misslyckad");
LSTR MSG_LCD_PROBING_FAILED = _UxGT("Probning misslyckad");
LSTR MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("VÄLJ TRÅD");
LSTR MSG_MMU2_MENU = _UxGT("MMU");
LSTR MSG_KILL_MMU2_FIRMWARE = _UxGT("Uppdatera MMU Firmware!");
LSTR MSG_MMU2_NOT_RESPONDING = _UxGT("MMU Behöver uppmärksamhet.");
LSTR MSG_MMU2_RESUME = _UxGT("MMU Återuppta");
LSTR MSG_KILL_MMU2_FIRMWARE = _UxGT("Uppdatera MMU firmware!");
LSTR MSG_MMU2_NOT_RESPONDING = _UxGT("MMU behöver kontrolleras.");
LSTR MSG_MMU2_RESUME = _UxGT("Återuppta MMU");
LSTR MSG_MMU2_RESUMING = _UxGT("MMU Återupptas...");
LSTR MSG_MMU2_LOAD_FILAMENT = _UxGT("MMU Ladda");
LSTR MSG_MMU2_LOAD_ALL = _UxGT("MMU Ladda Alla");
LSTR MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("MMU Ladda till Munstycke");
LSTR MSG_MMU2_EJECT_FILAMENT = _UxGT("MMU Mata ut");
LSTR MSG_MMU2_LOAD_FILAMENT = _UxGT("Ladda MMU");
LSTR MSG_MMU2_LOAD_ALL = _UxGT("MMU ladda alla");
LSTR MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("MMU ladda till munstycke");
LSTR MSG_MMU2_EJECT_FILAMENT = _UxGT("Mata ut MMU");
LSTR MSG_MMU2_EJECT_FILAMENT_N = _UxGT("MMU Mata ut ~");
LSTR MSG_MMU2_UNLOAD_FILAMENT = _UxGT("MMU Lossa");
LSTR MSG_MMU2_LOADING_FILAMENT = _UxGT("Ladda Tråd %i...");
LSTR MSG_MMU2_EJECTING_FILAMENT = _UxGT("Mata ut Tråd ...");
LSTR MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Lossa Tråd...");
LSTR MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Lossa MMU");
LSTR MSG_MMU2_LOADING_FILAMENT = _UxGT("Ladda tråd %i...");
LSTR MSG_MMU2_EJECTING_FILAMENT = _UxGT("Mata ut tråd ...");
LSTR MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Lossa tråd...");
LSTR MSG_MMU2_ALL = _UxGT("Alla");
LSTR MSG_MMU2_FILAMENT_N = _UxGT("Tråd ~");
LSTR MSG_MMU2_RESET = _UxGT("Återställ MMU");
LSTR MSG_MMU2_RESETTING = _UxGT("MMU Återställer...");
LSTR MSG_MMU2_EJECT_RECOVER = _UxGT("Ta bort, Klicka");
LSTR MSG_MMU2_RESETTING = _UxGT("MMU återställs...");
LSTR MSG_MMU2_EJECT_RECOVER = _UxGT("Ta bort, klicka");
LSTR MSG_MMU2_REMOVE_AND_CLICK = _UxGT("Avlägsna och klicka...");
LSTR MSG_MIX = _UxGT("Mixa");
LSTR MSG_MIX_COMPONENT_N = _UxGT("Komponent {");
LSTR MSG_MIXER = _UxGT("Mixer");
LSTR MSG_GRADIENT = _UxGT("Gradient");
LSTR MSG_FULL_GRADIENT = _UxGT("Full Gradient");
LSTR MSG_TOGGLE_MIX = _UxGT("Växla Mix");
LSTR MSG_CYCLE_MIX = _UxGT("Totera Mix");
LSTR MSG_GRADIENT_MIX = _UxGT("Gradient Mix");
LSTR MSG_REVERSE_GRADIENT = _UxGT("Omvänd Gradient");
LSTR MSG_ACTIVE_VTOOL = _UxGT("Aktive V-verktyg");
LSTR MSG_START_VTOOL = _UxGT("Start V-verktyg");
LSTR MSG_END_VTOOL = _UxGT(" Slut V-verktyg");
LSTR MSG_FULL_GRADIENT = _UxGT("Full gradient");
LSTR MSG_TOGGLE_MIX = _UxGT("Växla mix");
LSTR MSG_CYCLE_MIX = _UxGT("Rotera mix");
LSTR MSG_GRADIENT_MIX = _UxGT("Gradient mix");
LSTR MSG_REVERSE_GRADIENT = _UxGT("Omvänd gradient");
LSTR MSG_ACTIVE_VTOOL = _UxGT("Aktiva V-verktyg");
LSTR MSG_START_VTOOL = _UxGT("Starta V-verktyg");
LSTR MSG_END_VTOOL = _UxGT(" Avsluta V-verktyg");
LSTR MSG_GRADIENT_ALIAS = _UxGT("Alias V-verktyg");
LSTR MSG_RESET_VTOOLS = _UxGT("Återställ V-verktyg");
LSTR MSG_COMMIT_VTOOL = _UxGT("Kommitta V-verktyg Mix");
LSTR MSG_VTOOLS_RESET = _UxGT("V-verktyg blev Återställda");
LSTR MSG_COMMIT_VTOOL = _UxGT("Anslut V-verktyg mix");
LSTR MSG_VTOOLS_RESET = _UxGT("V-verktyg blev återställda");
LSTR MSG_START_Z = _UxGT("Start Z:");
LSTR MSG_END_Z = _UxGT(" Slut Z:");
@ -584,15 +615,15 @@ namespace LanguageNarrow_sv {
LSTR MSG_BAD_PAGE_SPEED = _UxGT("Dålig sida hastighet");
LSTR MSG_EDIT_PASSWORD = _UxGT("Redigera Lösenord");
LSTR MSG_LOGIN_REQUIRED = _UxGT("Login Krävs");
LSTR MSG_LOGIN_REQUIRED = _UxGT("Inloggning krävs");
LSTR MSG_PASSWORD_SETTINGS = _UxGT("Lösenordsinställningar");
LSTR MSG_ENTER_DIGIT = _UxGT("Ange Siffra");
LSTR MSG_CHANGE_PASSWORD = _UxGT("Sätt/Redigera Lösenord");
LSTR MSG_REMOVE_PASSWORD = _UxGT("Ta bort Lösenord");
LSTR MSG_PASSWORD_SET = _UxGT("Lösenord är ");
LSTR MSG_ENTER_DIGIT = _UxGT("Ange siffra");
LSTR MSG_CHANGE_PASSWORD = _UxGT("Ange/ändra lösenord");
LSTR MSG_REMOVE_PASSWORD = _UxGT("Ta bort lösenord");
LSTR MSG_PASSWORD_SET = _UxGT("Lösenordet är ");
LSTR MSG_START_OVER = _UxGT("Börja om");
LSTR MSG_REMINDER_SAVE_SETTINGS = _UxGT("Kom ihåg att Spara!");
LSTR MSG_PASSWORD_REMOVED = _UxGT("Lösenord Bort taget");
LSTR MSG_REMINDER_SAVE_SETTINGS = _UxGT("Glöm inte att spara!");
LSTR MSG_PASSWORD_REMOVED = _UxGT("Lösenord borttaget");
//
// Filament Change screens show up to 2 lines on a 3-line display
@ -609,21 +640,21 @@ namespace LanguageNarrow_sv {
LSTR MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Klicka för att slutföra"));
LSTR MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Återgår..."));
LSTR MSG_TMC_DRIVERS = _UxGT("TMC Drivers");
LSTR MSG_TMC_CURRENT = _UxGT("Driver Ström");
LSTR MSG_TMC_HYBRID_THRS = _UxGT("Hybrid Tröskelvärde");
LSTR MSG_TMC_HOMING_THRS = _UxGT("Sensorlös Hemning");
LSTR MSG_TMC_DRIVERS = _UxGT("TMC-Drivare");
LSTR MSG_TMC_CURRENT = _UxGT("Strömdrivare");
LSTR MSG_TMC_HYBRID_THRS = _UxGT("Tröskelvärde hybrid");
LSTR MSG_TMC_HOMING_THRS = _UxGT("Givarfri hemkörning");
LSTR MSG_TMC_STEPPING_MODE = _UxGT("Stegningsläge");
LSTR MSG_TMC_STEALTHCHOP = _UxGT("Smyghack");
LSTR MSG_SERVICE_RESET = _UxGT("Återställ");
LSTR MSG_SERVICE_IN = _UxGT(" in:");
LSTR MSG_BACKLASH = _UxGT("Backlash");
LSTR MSG_BACKLASH = _UxGT("Backslag");
LSTR MSG_BACKLASH_CORRECTION = _UxGT("Korrigering");
LSTR MSG_BACKLASH_SMOOTHING = _UxGT("Glättning");
LSTR MSG_BACKLASH_SMOOTHING = _UxGT("Släta ut");
LSTR MSG_LEVEL_X_AXIS = _UxGT("Nivå X Axel");
LSTR MSG_AUTO_CALIBRATE = _UxGT("Auto Kalibrera");
LSTR MSG_LEVEL_X_AXIS = _UxGT("Nivå X-axel");
LSTR MSG_AUTO_CALIBRATE = _UxGT("Autokalibrera");
LSTR MSG_FTDI_HEATER_TIMEOUT = _UxGT("Overksam tidsgräns, temperatur minskning. Tryck ok för att återvärma och igen för att fortsätta.");
LSTR MSG_HEATER_TIMEOUT = _UxGT("Värmare Tidsgräns");
LSTR MSG_REHEAT = _UxGT("Återvärm");
@ -640,7 +671,7 @@ namespace LanguageNarrow_sv {
LSTR MSG_TOP_RIGHT = _UxGT("Uppe Höger");
LSTR MSG_BOTTOM_RIGHT = _UxGT("Nere Höger");
LSTR MSG_CALIBRATION_COMPLETED = _UxGT("Kalibrering Färdig");
LSTR MSG_CALIBRATION_FAILED = _UxGT("Kalibrering Misslyckad");
LSTR MSG_CALIBRATION_FAILED = _UxGT("Kalibrering misslyckad");
}
namespace LanguageWide_sv {

View file

@ -1049,17 +1049,23 @@ void MarlinUI::init() {
TERN_(LCD_HAS_STATUS_INDICATORS, update_indicators());
#if HAS_ENCODER_ACTION
TERN_(HAS_SLOW_BUTTONS, slow_buttons = read_slow_buttons()); // Buttons that take too long to read in interrupt context
// Read buttons that take too long to read in interrupt context,
// as with an external LCD button API.
TERN_(HAS_SLOW_BUTTONS, slow_buttons = read_slow_buttons());
// RRW Keypad interaction resets the timeout to status screen
if (TERN0(IS_RRW_KEYPAD, handle_keypad()))
reset_status_timeout(ms);
// Wake the display for any encoder movement
static int8_t lastEncoderDiff;
if (lastEncoderDiff != encoderDiff) wake_display();
lastEncoderDiff = encoderDiff;
// Did the encoder turn by more than "Encoder Pulses Per Step" ticks?
const uint8_t abs_diff = ABS(encoderDiff);
const bool encoderPastThreshold = (abs_diff >= epps);
if (encoderPastThreshold && TERN1(IS_TFTGLCD_PANEL, !external_control)) {
int32_t encoder_multiplier = 1;
@ -1103,16 +1109,22 @@ void MarlinUI::init() {
}
}
// Has the wheel advanced by a step or the encoder done a click?
if (encoderPastThreshold || lcd_clicked) {
// Retain the current screen
reset_status_timeout(ms);
// Keep the lights on
#if HAS_BACKLIGHT_TIMEOUT
refresh_backlight_timeout();
#elif HAS_DISPLAY_SLEEP
refresh_screen_timeout();
#endif
// Make sure the display is updated in response
refresh(LCDVIEW_REDRAW_NOW);
// This will cause paged displays to go to "first page"
TERN_(HAS_MARLINUI_U8GLIB, drawing_screen = false);
#if MARLINUI_SCROLL_NAME
filename_scroll_max = 0;
@ -1170,6 +1182,7 @@ void MarlinUI::init() {
TERN_(HAS_ADC_BUTTONS, keypad_buttons = 0);
#if HAS_MARLINUI_U8GLIB
#if ENABLED(LIGHTWEIGHT_UI)
const bool in_status = on_status_screen(),
do_u8g_loop = !in_status;
@ -1198,11 +1211,14 @@ void MarlinUI::init() {
return;
}
}
#else
#else // !HAS_MARLINUI_U8GLIB
run_current_screen();
// Apply all DWIN drawing after processing
TERN_(IS_DWIN_MARLINUI, dwinUpdateLCD());
#endif
TERN_(HAS_MARLINUI_MENU, lcd_clicked = false);

View file

@ -667,6 +667,11 @@ public:
static void preheat_all(const uint8_t m, const uint8_t e=active_extruder) { apply_preheat(m, PT_ALL, e); }
#endif
/**
* The current screen will time out unless 'defer_return_to_status' is true,
* and the display will go back to the Status Screen.
* Call this method whenever the user interacts to reset the timeout.
*/
static void reset_status_timeout(const millis_t ms) {
TERN(HAS_SCREEN_TIMEOUT, return_to_status_ms = ms + LCD_TIMEOUT_TO_STATUS, UNUSED(ms));
}

View file

@ -274,7 +274,7 @@ static void _lcd_goto_next_corner() {
}
TERN_(BLTOUCH, if (!bltouch.high_speed_mode) bltouch.stow());
ui.goto_screen(_lcd_draw_probing);
return (probe_triggered);
return probe_triggered;
}
void _lcd_test_corners() {

View file

@ -349,6 +349,7 @@ void menu_main() {
SUBMENU(MSG_MEDIA_MENU_SD, MEDIA_MENU_GATEWAY);
else if (TERN0(SHOW_UNMOUNTED_DRIVES, card.isSDCardInserted()))
SUBMENU(MSG_MEDIA_MENU_SD, MEDIA_MENU_GATEWAY_SD);
if (card.isFlashDriveMounted())
SUBMENU(MSG_MEDIA_MENU_USB, MEDIA_MENU_GATEWAY);
else if (TERN0(SHOW_UNMOUNTED_DRIVES, card.isFlashDriveInserted()))

View file

@ -101,7 +101,10 @@ class MenuItem_sdfolder : public MenuItem_sdbase {
}
};
//
// Shortcut menu items to go directly to inserted — not necessarily mounted — drives
//
void menu_file_selector_sd() {
if (!card.isSDCardSelected()) {
card.release();
@ -111,7 +114,6 @@ void menu_file_selector_sd() {
ui.goto_screen(menu_file_selector);
}
// Shortcut menu items to go directly to inserted — not necessarily mounted — drives
void menu_file_selector_usb() {
if (!card.isFlashDriveSelected()) {
card.release();
@ -121,7 +123,6 @@ void menu_file_selector_usb() {
ui.goto_screen(menu_file_selector);
}
// Shortcut menu items to go directly to inserted — not necessarily mounted — drives
void menu_file_selector() {
ui.encoder_direction_menus();

View file

@ -315,15 +315,31 @@ void menu_move() {
FSTR_P get_shaper_name(const AxisEnum axis) {
switch (ftMotion.cfg.shaper[axis]) {
default: return nullptr;
case ftMotionShaper_NONE: return GET_TEXT_F(MSG_LCD_OFF);
case ftMotionShaper_ZV: return GET_TEXT_F(MSG_FTM_ZV);
case ftMotionShaper_ZVD: return GET_TEXT_F(MSG_FTM_ZVD);
case ftMotionShaper_ZVDD: return GET_TEXT_F(MSG_FTM_ZVDD);
case ftMotionShaper_ZVDDD: return GET_TEXT_F(MSG_FTM_ZVDDD);
case ftMotionShaper_EI: return GET_TEXT_F(MSG_FTM_EI);
case ftMotionShaper_2HEI: return GET_TEXT_F(MSG_FTM_2HEI);
case ftMotionShaper_3HEI: return GET_TEXT_F(MSG_FTM_3HEI);
case ftMotionShaper_MZV: return GET_TEXT_F(MSG_FTM_MZV);
case ftMotionShaper_NONE: return GET_TEXT_F(MSG_LCD_OFF);
#if ENABLED(FTM_SHAPER_ZV)
case ftMotionShaper_ZV: return GET_TEXT_F(MSG_FTM_ZV);
#endif
#if ENABLED(FTM_SHAPER_ZVD)
case ftMotionShaper_ZVD: return GET_TEXT_F(MSG_FTM_ZVD);
#endif
#if ENABLED(FTM_SHAPER_ZVDD)
case ftMotionShaper_ZVDD: return GET_TEXT_F(MSG_FTM_ZVDD);
#endif
#if ENABLED(FTM_SHAPER_ZVDDD)
case ftMotionShaper_ZVDDD: return GET_TEXT_F(MSG_FTM_ZVDDD);
#endif
#if ENABLED(FTM_SHAPER_EI)
case ftMotionShaper_EI: return GET_TEXT_F(MSG_FTM_EI);
#endif
#if ENABLED(FTM_SHAPER_2HEI)
case ftMotionShaper_2HEI: return GET_TEXT_F(MSG_FTM_2HEI);
#endif
#if ENABLED(FTM_SHAPER_3HEI)
case ftMotionShaper_3HEI: return GET_TEXT_F(MSG_FTM_3HEI);
#endif
#if ENABLED(FTM_SHAPER_MZV)
case ftMotionShaper_MZV: return GET_TEXT_F(MSG_FTM_MZV);
#endif
}
}
@ -343,8 +359,7 @@ void menu_move() {
#endif
void ftm_menu_set_shaper(const ftMotionShaper_t s) {
ftMotion.cfg.shaper[MenuItemBase::itemIndex] = s;
ftMotion.update_shaping_params();
queue.inject(TS(F("M493"), IAXIS_CHAR(MenuItemBase::itemIndex), 'C', int(s)));
ui.go_back();
}
@ -355,15 +370,15 @@ void menu_move() {
START_MENU();
BACK_ITEM_N(axis, MSG_FTM_CONFIGURE_AXIS_N);
if (shaper != ftMotionShaper_NONE) ACTION_ITEM_N(axis, MSG_LCD_OFF, []{ ftm_menu_set_shaper(ftMotionShaper_NONE) ; });
if (shaper != ftMotionShaper_ZV) ACTION_ITEM_N(axis, MSG_FTM_ZV, []{ ftm_menu_set_shaper(ftMotionShaper_ZV) ; });
if (shaper != ftMotionShaper_ZVD) ACTION_ITEM_N(axis, MSG_FTM_ZVD, []{ ftm_menu_set_shaper(ftMotionShaper_ZVD) ; });
if (shaper != ftMotionShaper_ZVDD) ACTION_ITEM_N(axis, MSG_FTM_ZVDD, []{ ftm_menu_set_shaper(ftMotionShaper_ZVDD) ; });
if (shaper != ftMotionShaper_ZVDDD) ACTION_ITEM_N(axis, MSG_FTM_ZVDDD,[]{ ftm_menu_set_shaper(ftMotionShaper_ZVDDD) ; });
if (shaper != ftMotionShaper_EI) ACTION_ITEM_N(axis, MSG_FTM_EI, []{ ftm_menu_set_shaper(ftMotionShaper_EI) ; });
if (shaper != ftMotionShaper_2HEI) ACTION_ITEM_N(axis, MSG_FTM_2HEI, []{ ftm_menu_set_shaper(ftMotionShaper_2HEI) ; });
if (shaper != ftMotionShaper_3HEI) ACTION_ITEM_N(axis, MSG_FTM_3HEI, []{ ftm_menu_set_shaper(ftMotionShaper_3HEI) ; });
if (shaper != ftMotionShaper_MZV) ACTION_ITEM_N(axis, MSG_FTM_MZV, []{ ftm_menu_set_shaper(ftMotionShaper_MZV) ; });
if (shaper != ftMotionShaper_NONE) ACTION_ITEM_N(axis, MSG_LCD_OFF, []{ ftm_menu_set_shaper(ftMotionShaper_NONE) ; });
TERN_(FTM_SHAPER_ZV, if (shaper != ftMotionShaper_ZV) ACTION_ITEM_N(axis, MSG_FTM_ZV, []{ ftm_menu_set_shaper(ftMotionShaper_ZV) ; }));
TERN_(FTM_SHAPER_ZVD, if (shaper != ftMotionShaper_ZVD) ACTION_ITEM_N(axis, MSG_FTM_ZVD, []{ ftm_menu_set_shaper(ftMotionShaper_ZVD) ; }));
TERN_(FTM_SHAPER_ZVDD, if (shaper != ftMotionShaper_ZVDD) ACTION_ITEM_N(axis, MSG_FTM_ZVDD, []{ ftm_menu_set_shaper(ftMotionShaper_ZVDD) ; }));
TERN_(FTM_SHAPER_ZVDDD, if (shaper != ftMotionShaper_ZVDDD) ACTION_ITEM_N(axis, MSG_FTM_ZVDDD,[]{ ftm_menu_set_shaper(ftMotionShaper_ZVDDD) ; }));
TERN_(FTM_SHAPER_EI, if (shaper != ftMotionShaper_EI) ACTION_ITEM_N(axis, MSG_FTM_EI, []{ ftm_menu_set_shaper(ftMotionShaper_EI) ; }));
TERN_(FTM_SHAPER_2HEI, if (shaper != ftMotionShaper_2HEI) ACTION_ITEM_N(axis, MSG_FTM_2HEI, []{ ftm_menu_set_shaper(ftMotionShaper_2HEI) ; }));
TERN_(FTM_SHAPER_3HEI, if (shaper != ftMotionShaper_3HEI) ACTION_ITEM_N(axis, MSG_FTM_3HEI, []{ ftm_menu_set_shaper(ftMotionShaper_3HEI) ; }));
TERN_(FTM_SHAPER_MZV, if (shaper != ftMotionShaper_MZV) ACTION_ITEM_N(axis, MSG_FTM_MZV, []{ ftm_menu_set_shaper(ftMotionShaper_MZV) ; }));
END_MENU();
}
@ -375,9 +390,15 @@ void menu_move() {
START_MENU();
BACK_ITEM(MSG_FIXED_TIME_MOTION);
if (traj_type != TrajectoryType::TRAPEZOIDAL) ACTION_ITEM(MSG_FTM_TRAPEZOIDAL, []{ ftMotion.updateTrajectoryType(TrajectoryType::TRAPEZOIDAL); ui.go_back(); });
if (traj_type != TrajectoryType::POLY5) ACTION_ITEM(MSG_FTM_POLY5, []{ ftMotion.updateTrajectoryType(TrajectoryType::POLY5); ui.go_back(); });
if (traj_type != TrajectoryType::POLY6) ACTION_ITEM(MSG_FTM_POLY6, []{ ftMotion.updateTrajectoryType(TrajectoryType::POLY6); ui.go_back(); });
if (traj_type != TrajectoryType::TRAPEZOIDAL) ACTION_ITEM(MSG_FTM_TRAPEZOIDAL, []{
queue.inject(TS(F("M494"), 'T', int(TrajectoryType::TRAPEZOIDAL))); ui.go_back();
});
if (traj_type != TrajectoryType::POLY5) ACTION_ITEM(MSG_FTM_POLY5, []{
queue.inject(TS(F("M494"), 'T', int(TrajectoryType::POLY5))); ui.go_back();
});
if (traj_type != TrajectoryType::POLY6) ACTION_ITEM(MSG_FTM_POLY6, []{
queue.inject(TS(F("M494"), 'T', int(TrajectoryType::POLY6))); ui.go_back();
});
END_MENU();
}
@ -425,12 +446,18 @@ void menu_move() {
START_MENU();
BACK_ITEM_N(MenuItemBase::itemIndex, MSG_FTM_CONFIGURE_AXIS_N);
if (dmode != dynFreqMode_DISABLED) ACTION_ITEM(MSG_LCD_OFF, []{ (void)ftMotion.cfg.setDynFreqMode(dynFreqMode_DISABLED); ui.go_back(); });
if (dmode != dynFreqMode_DISABLED) ACTION_ITEM(MSG_LCD_OFF, []{
queue.inject(TS(F("M493D"), int(dynFreqMode_DISABLED))); ui.go_back();
});
#if HAS_DYNAMIC_FREQ_MM
if (dmode != dynFreqMode_Z_BASED) ACTION_ITEM(MSG_FTM_Z_BASED, []{ (void)ftMotion.cfg.setDynFreqMode(dynFreqMode_Z_BASED); ui.go_back(); });
if (dmode != dynFreqMode_Z_BASED) ACTION_ITEM(MSG_FTM_Z_BASED, []{
queue.inject(TS(F("M493D"), int(dynFreqMode_Z_BASED))); ui.go_back();
});
#endif
#if HAS_DYNAMIC_FREQ_G
if (dmode != dynFreqMode_MASS_BASED) ACTION_ITEM(MSG_FTM_MASS_BASED, []{ (void)ftMotion.cfg.setDynFreqMode(dynFreqMode_MASS_BASED); ui.go_back(); });
if (dmode != dynFreqMode_MASS_BASED) ACTION_ITEM(MSG_FTM_MASS_BASED, []{
queue.inject(TS(F("M493D"), int(dynFreqMode_MASS_BASED))); ui.go_back();
});
#endif
END_MENU();
@ -444,33 +471,45 @@ void menu_move() {
START_MENU();
BACK_ITEM(MSG_FIXED_TIME_MOTION);
#if HAS_FTM_EI_SHAPING
#define EISHAPER_MENU_ITEM(A) \
if (AXIS_IS_EISHAPING(A)) \
EDIT_ITEM_FAST_N(float42_52, axis, MSG_FTM_VTOL_N, &c.vtol[axis], 0.0f, 1.0f, ftMotion.update_shaping_params);
#else
#define EISHAPER_MENU_ITEM(A) NOOP
#endif
if (false SHAPED_GANG(|| axis == X_AXIS, || axis == Y_AXIS, || axis == Z_AXIS, || axis == E_AXIS)) {
SUBMENU_N_S(axis, get_shaper_name(axis), MSG_FTM_CMPN_MODE, menu_ftm_shaper);
if (AXIS_IS_SHAPING(axis)) {
EDIT_ITEM_FAST_N(float42_52, axis, MSG_FTM_BASE_FREQ_N, &c.baseFreq[axis], FTM_MIN_SHAPE_FREQ, (FTM_FS) / 2, ftMotion.update_shaping_params);
EDIT_ITEM_FAST_N(float42_52, axis, MSG_FTM_ZETA_N, &c.zeta[axis], 0.0f, 1.0f, ftMotion.update_shaping_params);
EISHAPER_MENU_ITEM(axis);
if (IS_SHAPING(c.shaper[axis])) {
editable.decimal = c.baseFreq[axis];
EDIT_ITEM_FAST_N(float42_52, axis, MSG_FTM_BASE_FREQ_N, &editable.decimal, FTM_MIN_SHAPE_FREQ, (FTM_FS) / 2, []{
queue.inject(TS(F("M493"), IAXIS_CHAR(MenuItemBase::itemIndex), 'A', p_float_t(editable.decimal, 3)));
});
editable.decimal = c.zeta[axis];
EDIT_ITEM_FAST_N(float42_52, axis, MSG_FTM_ZETA_N, &editable.decimal, 0.0f, FTM_MAX_DAMPENING, []{
queue.inject(TS(F("M493"), IAXIS_CHAR(MenuItemBase::itemIndex), 'I', p_float_t(editable.decimal, 3)));
});
#if HAS_FTM_EI_SHAPING
if (IS_EISHAPING(c.shaper[axis])) {
editable.decimal = c.vtol[axis];
EDIT_ITEM_FAST_N(float42_52, axis, MSG_FTM_VTOL_N, &editable.decimal, 0.0f, 1.0f, []{
queue.inject(TS(F("M493"), IAXIS_CHAR(MenuItemBase::itemIndex), 'Q', p_float_t(editable.decimal, 3)));
});
}
#endif
}
}
#if ENABLED(FTM_SMOOTHING)
editable.decimal = c.smoothingTime[axis];
EDIT_ITEM_FAST_N(float43, axis, MSG_FTM_SMOOTH_TIME_N, &editable.decimal, 0.0f, FTM_MAX_SMOOTHING_TIME, []{ (void)ftMotion.set_smoothing_time(AxisEnum(MenuItemBase::itemIndex), editable.decimal); });
EDIT_ITEM_FAST_N(float43, axis, MSG_FTM_SMOOTH_TIME_N, &editable.decimal, 0.0f, FTM_MAX_SMOOTHING_TIME, []{
queue.inject(TS(F("M494"), IAXIS_CHAR(MenuItemBase::itemIndex), p_float_t(editable.decimal, 4)));
});
#endif
#if HAS_DYNAMIC_FREQ
if (axis == X_AXIS || axis == Y_AXIS) {
SUBMENU_N_S(axis, get_dyn_freq_mode_name(), MSG_FTM_DYN_MODE, menu_ftm_dyn_mode);
if (c.dynFreqMode != dynFreqMode_DISABLED)
EDIT_ITEM_FAST_N(float42_52, axis, MSG_FTM_DFREQ_K_N, &c.dynFreqK[axis], 0.0f, 20.0f);
if (c.dynFreqMode != dynFreqMode_DISABLED) {
editable.decimal = c.dynFreqK[axis];
EDIT_ITEM_FAST_N(float42_52, axis, MSG_FTM_DFREQ_K_N, &editable.decimal, 0.0f, 20.0f, []{
queue.inject(TS(F("M493"), IAXIS_CHAR(MenuItemBase::itemIndex), 'F', p_float_t(editable.decimal, 3)));
});
}
}
#endif
@ -486,8 +525,12 @@ void menu_move() {
BACK_ITEM(MSG_MOTION);
#if HAS_STANDARD_MOTION
bool show_state = c.active;
EDIT_ITEM(bool, MSG_FIXED_TIME_MOTION, &show_state, []{ (void)ftMotion.toggle(); });
// Because this uses G-code the display of the actual state will be delayed by an unknown period of time.
// To fix this G-codes M493/M494 could refresh the UI when they are done.
editable.state = c.active;
EDIT_ITEM(bool, MSG_FIXED_TIME_MOTION, &editable.state, []{
queue.inject(TS(F("M493"), 'S', int(editable.state)));
});
#endif
// Show only when FT Motion is active (or optionally always show)
@ -495,13 +538,20 @@ void menu_move() {
#if ENABLED(FTM_POLYS)
SUBMENU_S(ftMotion.getTrajectoryName(), MSG_FTM_TRAJECTORY, menu_ftm_trajectory_generator);
if (ftMotion.getTrajectoryType() == TrajectoryType::POLY6)
EDIT_ITEM(float42_52, MSG_FTM_POLY6_OVERSHOOT, &c.poly6_acceleration_overshoot, 1.25f, 1.875f);
if (ftMotion.getTrajectoryType() == TrajectoryType::POLY6) {
editable.decimal = c.poly6_acceleration_overshoot;
EDIT_ITEM(float42_52, MSG_FTM_POLY6_OVERSHOOT, &editable.decimal, 1.25f, 1.875f, []{
queue.inject(TS(F("M494"), 'O', editable.decimal));
});
}
#endif
CARTES_MAP(_FTM_AXIS_SUBMENU);
EDIT_ITEM(bool, MSG_FTM_AXIS_SYNC, &c.axis_sync_enabled);
editable.state = c.axis_sync_enabled;
EDIT_ITEM(bool, MSG_FTM_AXIS_SYNC, &editable.state, []{
queue.inject(TS(F("M493"), IAXIS_CHAR(MenuItemBase::itemIndex), 'T', int(editable.state)));
});
#if ENABLED(FTM_RESONANCE_TEST)
SUBMENU(MSG_FTM_RESONANCE_TEST, menu_ftm_resonance_test);
@ -513,9 +563,6 @@ void menu_move() {
void menu_tune_ft_motion() {
// Define stuff ahead of the menu loop
ft_config_t &c = ftMotion.cfg;
#ifdef __AVR__
// Copy Flash strings to RAM for C-string substitution
@ -548,8 +595,12 @@ void menu_move() {
#if ENABLED(FTM_POLYS)
SUBMENU_S(_traj_name(), MSG_FTM_TRAJECTORY, menu_ftm_trajectory_generator);
if (ftMotion.getTrajectoryType() == TrajectoryType::POLY6)
EDIT_ITEM(float42_52, MSG_FTM_POLY6_OVERSHOOT, &c.poly6_acceleration_overshoot, 1.25f, 1.875f);
if (ftMotion.getTrajectoryType() == TrajectoryType::POLY6) {
editable.decimal = ftMotion.cfg.poly6_acceleration_overshoot;
EDIT_ITEM(float42_52, MSG_FTM_POLY6_OVERSHOOT, &editable.decimal, 1.25f, 1.875f, []{
queue.inject(TS(F("M494"), 'O', editable.decimal));
});
}
#endif
SHAPED_MAP(_FTM_AXIS_SUBMENU);

View file

@ -1,5 +1,5 @@
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
<!-- Created with Inkscape (http://www.inkscape.org/) -->
<!-- Created with Inkscape (http://inkscape.org/) -->
<svg
width="32"
@ -12,8 +12,8 @@
inkscape:export-filename="time_elapsed_plain.svg"
inkscape:export-xdpi="96"
inkscape:export-ydpi="96"
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
xmlns:inkscape="http://inkscape.org/namespaces/inkscape"
xmlns:sodipodi="https://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
xmlns="http://www.w3.org/2000/svg"
xmlns:svg="http://www.w3.org/2000/svg">
<sodipodi:namedview

Before

Width:  |  Height:  |  Size: 5.6 KiB

After

Width:  |  Height:  |  Size: 5.5 KiB

Before After
Before After

View file

@ -1,5 +1,5 @@
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
<!-- Created with Inkscape (http://www.inkscape.org/) -->
<!-- Created with Inkscape (http://inkscape.org/) -->
<svg
width="32"
@ -12,8 +12,8 @@
inkscape:export-filename="time_remaining_plain.svg"
inkscape:export-xdpi="96"
inkscape:export-ydpi="96"
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
xmlns:inkscape="http://inkscape.org/namespaces/inkscape"
xmlns:sodipodi="https://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
xmlns="http://www.w3.org/2000/svg"
xmlns:svg="http://www.w3.org/2000/svg">
<sodipodi:namedview

Before

Width:  |  Height:  |  Size: 5.6 KiB

After

Width:  |  Height:  |  Size: 5.5 KiB

Before After
Before After

View file

@ -4,7 +4,7 @@ This Font Software is licensed under the SIL Open Font License,
Version 1.1.
This license is copied below, and is also available with a FAQ at:
http://scripts.sil.org/OFL
https://scripts.sil.org/OFL
-----------------------------------------------------------
SIL OPEN FONT LICENSE Version 1.1 - 26 February 2007

View file

@ -1,5 +1,5 @@
The SIL Open Font License version 1.1 is copied below, and is also
available with a FAQ at http://scripts.sil.org/OFL.
available with a FAQ at https://scripts.sil.org/OFL.
-----------------------------------------------------------
SIL OPEN FONT LICENSE Version 1.1 - 26 February 2007

View file

@ -306,6 +306,7 @@ void Touch::touch(touch_control_t * const control) {
}
}
//
// Set the control as "held" until the touch is released
//
void Touch::hold(touch_control_t * const control, const millis_t delay/*=0*/) {

View file

@ -95,7 +95,7 @@
#elif THERMISTOR_ID == 12
#define THERMISTOR_NAME "E3104FXT (alt)"
#elif THERMISTOR_ID == 13
#define THERMISTOR_NAME "Hisens 3950"
#define THERMISTOR_NAME "Hisense 3950"
#elif THERMISTOR_ID == 14
#define THERMISTOR_NAME "100k Ender-5 S1"
#elif THERMISTOR_ID == 15

View file

@ -499,7 +499,7 @@ float MAX31865::temperature(float rtd_res) {
/**
* MAX31865 SPI Timing constants
* See MAX31865 datasheet (https://datasheets.maximintegrated.com/en/ds/MAX31865.pdf)
* See MAX31865 datasheet (https://datasheets.maximintegrated.com/en/ds/max31865.pdf)
* All timings in nsec, minimum values.
*/

View file

@ -51,6 +51,9 @@
FTMotion ftMotion;
void ft_config_t::prep_for_shaper_change() { ftMotion.prep_for_shaper_change(); }
void ft_config_t::update_shaping_params() { TERN_(HAS_FTM_SHAPING, ftMotion.update_shaping_params()); }
//-----------------------------------------------------------------
// Variables.
//-----------------------------------------------------------------
@ -70,6 +73,7 @@ xyze_pos_t FTMotion::startPos, // (mm) Start position of bl
FTMotion::endPos_prevBlock = { 0.0f }; // (mm) End position of previous block
xyze_float_t FTMotion::ratio; // (ratio) Axis move ratio of block
float FTMotion::tau = 0.0f; // (s) Time since start of block
bool FTMotion::fastForwardUntilMotion = false; // Fast forward time if there is no motion
// Trajectory generators
TrapezoidalTrajectoryGenerator FTMotion::trapezoidalGenerator;
@ -191,12 +195,16 @@ void FTMotion::loop() {
#if HAS_FTM_SHAPING
void FTMotion::update_shaping_params() {
#define UPDATE_SHAPER(A) \
shaping.A.ena = IS_SHAPING(ftMotion.cfg.shaper.A); \
shaping.A.set_axis_shaping_A(cfg.shaper.A, cfg.zeta.A OPTARG(HAS_FTM_EI_SHAPING, cfg.vtol.A)); \
shaping.A.set_axis_shaping_N(cfg.shaper.A, cfg.baseFreq.A, cfg.zeta.A);
prep_for_shaper_change();
auto update_shaper = [&](AxisEnum axis, axis_shaping_t &shap) {
shap.ena = IS_SHAPING(cfg.shaper[axis]);
shap.set_axis_shaping_A(cfg.shaper[axis], cfg.zeta[axis] OPTARG(HAS_FTM_EI_SHAPING, cfg.vtol[axis]));
shap.set_axis_shaping_N(cfg.shaper[axis], cfg.baseFreq[axis], cfg.zeta[axis]);
};
#define UPDATE_SHAPER(A) update_shaper(_AXIS(A), shaping.A);
SHAPED_MAP(UPDATE_SHAPER);
shaping.refresh_largest_delay_samples();
}
@ -212,8 +220,9 @@ void FTMotion::loop() {
smoothing.refresh_largest_delay_samples();
}
bool FTMotion::set_smoothing_time(const AxisEnum axis, const float s_time) {
if (!WITHIN(s_time, 0.0f, FTM_MAX_SMOOTHING_TIME)) return false;
bool FTMotion::set_smoothing_time(const AxisEnum axis, float s_time) {
LIMIT(s_time, 0.0f, FTM_MAX_SMOOTHING_TIME);
prep_for_shaper_change();
cfg.smoothingTime[axis] = s_time;
update_smoothing_params();
return true;
@ -228,6 +237,7 @@ void FTMotion::reset() {
tau = 0;
stepping.reset();
shaping.reset();
fastForwardUntilMotion = true;
TERN_(FTM_SMOOTHING, smoothing.reset(););
TERN_(HAS_EXTRUDERS, prev_traj_e = 0.0f); // Reset linear advance variables.
@ -314,7 +324,7 @@ void FTMotion::init() {
case TrajectoryType::POLY6:
break;
}
planner.synchronize();
prep_for_shaper_change();
setTrajectoryType(type);
return true;
}
@ -379,8 +389,13 @@ bool FTMotion::plan_next_block() {
stepper.last_direction_bits.hz = current_block->direction_bits.hz;
#endif
// Cache the extruder index for this block
TERN_(DISTINCT_E_FACTORS, block_extruder_axis = E_AXIS_N(current_block->extruder));
// Cache the extruder index / axis for this block
#if ANY(HAS_MULTI_EXTRUDER, MIXING_EXTRUDER)
stepper.stepper_extruder = current_block->extruder;
#endif
#if ENABLED(DISTINCT_E_FACTORS)
block_extruder_axis = E_AXIS_N(current_block->extruder);
#endif
const float totalLength = current_block->millimeters;
@ -409,38 +424,41 @@ bool FTMotion::plan_next_block() {
}
}
/**
* Ensure extruder position stays within floating point precision bounds.
* Float32 numbers have 23 bits of precision, so the minimum increment ("resolution") around a value x is:
* resolution = 2^(floor(log2(|x|)) - 23)
* By resetting at ±1'000mm (1 meter), we get a minimum resolution of ~ 0.00006mm, enough for smoothing to work well.
*/
void FTMotion::ensure_float_precision() {
constexpr float FTM_POSITION_WRAP_THRESHOLD = 1'000.0f; // (mm) Reset when position exceeds this to prevent floating point precision loss
#if HAS_EXTRUDERS
if (fabs(endPos_prevBlock.E) >= FTM_POSITION_WRAP_THRESHOLD) {
const float offset = -endPos_prevBlock.E;
endPos_prevBlock.E += offset;
#if HAS_EXTRUDERS
// Offset extruder shaping buffer
#if ALL(HAS_FTM_SHAPING, FTM_SHAPER_E)
for (uint32_t i = 0; i < FTM_ZMAX; ++i) shaping.E.d_zi[i] += offset;
#endif
/**
* Ensure extruder position stays within floating point precision bounds.
* Float32 numbers have 23 bits of precision, so the minimum increment ("resolution") around a value x is:
* resolution = 2^(floor(log2(|x|)) - 23)
* By resetting at ±1'000mm (1 meter), we get a minimum resolution of ~ 0.00006mm, enough for smoothing to work well.
*/
void FTMotion::ensure_float_precision() {
constexpr float FTM_POSITION_WRAP_THRESHOLD = 1000; // (mm) Reset when position exceeds this to prevent floating point precision loss
if (ABS(endPos_prevBlock.E) < FTM_POSITION_WRAP_THRESHOLD) return;
// Offset extruder smoothing buffer
#if ENABLED(FTM_SMOOTHING)
for (uint8_t i = 0; i < FTM_SMOOTHING_ORDER; ++i) smoothing.E.smoothing_pass[i] += offset;
#endif
const float offset = -endPos_prevBlock.E;
// Offset linear advance previous position
prev_traj_e += offset;
endPos_prevBlock.E = 0;
// Offset stepper current position
const int64_t delta_steps_q48_16 = offset * planner.settings.axis_steps_per_mm[block_extruder_axis] * (1ULL << 16);
stepping.curr_steps_q48_16.E += delta_steps_q48_16;
};
#endif
}
// Offset extruder shaping buffer
#if ALL(HAS_FTM_SHAPING, FTM_SHAPER_E)
for (uint32_t i = 0; i < ftm_zmax; ++i) shaping.E.d_zi[i] += offset;
#endif
// Offset extruder smoothing buffer
#if ENABLED(FTM_SMOOTHING)
for (uint8_t i = 0; i < FTM_SMOOTHING_ORDER; ++i) smoothing.E.smoothing_pass[i] += offset;
#endif
// Offset linear advance previous position
prev_traj_e += offset;
// Offset stepper current position
const int64_t delta_steps_q48_16 = offset * planner.settings.axis_steps_per_mm[block_extruder_axis] * (1ULL << 16);
stepping.curr_steps_q48_16.E += delta_steps_q48_16;
}
#endif // HAS_EXTRUDERS
xyze_float_t FTMotion::calc_traj_point(const float dist) {
xyze_float_t traj_coords;
@ -504,17 +522,20 @@ xyze_float_t FTMotion::calc_traj_point(const float dist) {
#if ENABLED(FTM_SMOOTHING)
#define _SMOOTHEN(A) /* Approximate gaussian smoothing via chained EMAs */ \
if (smoothing.A.alpha > 0.0f) { \
float smooth_val = traj_coords.A; \
for (uint8_t _i = 0; _i < FTM_SMOOTHING_ORDER; ++_i) { \
smoothing.A.smoothing_pass[_i] += (smooth_val - smoothing.A.smoothing_pass[_i]) * smoothing.A.alpha; \
smooth_val = smoothing.A.smoothing_pass[_i]; \
} \
traj_coords.A = smooth_val; \
// Approximate Gaussian smoothing via chained EMAs
auto _smoothen = [&](const AxisEnum axis, axis_smoothing_t &smoo) {
if (smoo.alpha <= 0.0f) return;
float smooth_val = traj_coords[axis];
for (uint8_t _i = 0; _i < FTM_SMOOTHING_ORDER; ++_i) {
smoo.smoothing_pass[_i] += (smooth_val - smoo.smoothing_pass[_i]) * smoo.alpha;
smooth_val = smoo.smoothing_pass[_i];
}
traj_coords[axis] = smooth_val;
};
#define _SMOOTHEN(A) _smoothen(_AXIS(A), smoothing.A);
CARTES_MAP(_SMOOTHEN);
max_total_delay += smoothing.largest_delay_samples;
#endif // FTM_SMOOTHING
@ -525,27 +546,29 @@ xyze_float_t FTMotion::calc_traj_point(const float dist) {
max_total_delay += shaping.largest_delay_samples;
// Apply shaping if active on each axis
#define _SHAPE(A) \
do { \
const uint32_t group_delay = ftMotion.cfg.axis_sync_enabled \
? max_total_delay - TERN0(FTM_SMOOTHING, smoothing.A.delay_samples) \
: -shaping.A.Ni[0]; \
/* α=1exp((dt / (τ / order))) */ \
shaping.A.d_zi[shaping.zi_idx] = traj_coords.A; \
traj_coords.A = 0; \
for (uint32_t i = 0; i <= shaping.A.max_i; i++) { \
/* echo_delay is always positive since Ni[i] = echo_relative_delay - group_delay + max_total_delay */ \
/* where echo_relative_delay > 0 and group_delay ≤ max_total_delay */ \
const uint32_t echo_delay = group_delay + shaping.A.Ni[i]; \
int32_t udiff = shaping.zi_idx - echo_delay; \
if (udiff < 0) udiff += FTM_ZMAX; \
traj_coords.A += shaping.A.Ai[i] * shaping.A.d_zi[udiff]; \
} \
} while (0);
auto _shape = [&](const AxisEnum axis, axis_shaping_t &shap OPTARG(FTM_SMOOTHING, const axis_smoothing_t &smoo)) {
const uint32_t group_delay = ftMotion.cfg.axis_sync_enabled
? max_total_delay - TERN0(FTM_SMOOTHING, smoo.delay_samples)
: -shap.Ni[0];
//
// α = 1 exp((dt / (τ / order)))
//
shap.d_zi[shaping.zi_idx] = traj_coords[axis];
traj_coords[axis] = 0;
for (uint32_t i = 0; i <= shap.max_i; i++) {
// echo_delay is always positive since Ni[i] = echo_relative_delay - group_delay + max_total_delay
// where echo_relative_delay > 0 and group_delay ≤ max_total_delay
const uint32_t echo_delay = group_delay + shap.Ni[i];
int32_t udiff = shaping.zi_idx - echo_delay;
if (udiff < 0) udiff += ftm_zmax;
traj_coords[axis] += shap.Ai[i] * shap.d_zi[udiff];
}
};
#define _SHAPE(A) _shape(_AXIS(A), shaping.A OPTARG(FTM_SMOOTHING, smoothing.A));
SHAPED_MAP(_SHAPE);
if (++shaping.zi_idx == (FTM_ZMAX)) shaping.zi_idx = 0;
if (++shaping.zi_idx == ftm_zmax) shaping.zi_idx = 0;
#endif // HAS_FTM_SHAPING
@ -581,10 +604,16 @@ void FTMotion::fill_stepper_plan_buffer() {
// Get distance from trajectory generator
xyze_float_t traj_coords = calc_traj_point(currentGenerator->getDistanceAtTime(tau));
// Calculate and store stepper plan in buffer
stepping_enqueue(traj_coords);
if (fastForwardUntilMotion && traj_coords == startPos) {
// Axis synchronization delays all axes. When coming from a reset, there is a ramp up time filling all buffers.
// If the slowest axis doesn't move and it isn't smoothened, this time can be skipped.
// It eliminates idle time when changing smoothing time or shapers and speeds up homing and bed leveling.
}
else {
fastForwardUntilMotion = false;
// Calculate and store stepper plan in buffer
stepping_enqueue(traj_coords);
}
}
}

View file

@ -98,19 +98,63 @@ typedef struct FTConfig {
static constexpr TrajectoryType trajectory_type = TrajectoryType::TRAPEZOIDAL;
#endif
static void prep_for_shaper_change();
static void update_shaping_params();
#if HAS_STANDARD_MOTION
bool setActive(const bool a) {
if (a == active) return false;
stepper.ftMotion_syncPosition();
prep_for_shaper_change();
active = a;
update_shaping_params();
return true;
}
#endif
bool setAxisSync(const bool ena) {
if (ena == axis_sync_enabled) return false;
prep_for_shaper_change();
axis_sync_enabled = ena;
update_shaping_params();
return true;
}
#if HAS_FTM_SHAPING
constexpr bool goodZeta(const float z) { return WITHIN(z, 0.01f, 1.0f); }
constexpr bool goodVtol(const float v) { return WITHIN(v, 0.00f, 1.0f); }
bool setShaper(const AxisEnum a, const ftMotionShaper_t s) {
if (s == shaper[a]) return false;
prep_for_shaper_change();
shaper[a] = s;
update_shaping_params();
return true;
}
constexpr bool goodZeta(const float z) { return WITHIN(z, 0.00f, ftm_max_dampening); }
bool setZeta(const AxisEnum a, float z) {
if (z == zeta[a]) return false;
LIMIT(z, 0.00f, ftm_max_dampening);
prep_for_shaper_change();
zeta[a] = z;
update_shaping_params();
return true;
}
#if HAS_FTM_EI_SHAPING
constexpr bool goodVtol(const float v) { return WITHIN(v, 0.00f, 1.0f); }
bool setVtol(const AxisEnum a, float v) {
if (v == vtol[a]) return false;
LIMIT(v, 0.00f, 1.0f);
prep_for_shaper_change();
vtol[a] = v;
update_shaping_params();
return true;
}
#endif
#if HAS_DYNAMIC_FREQ
@ -121,10 +165,11 @@ typedef struct FTConfig {
TERN_(HAS_DYNAMIC_FREQ_MM, case dynFreqMode_Z_BASED:)
TERN_(HAS_DYNAMIC_FREQ_G, case dynFreqMode_MASS_BASED:)
case dynFreqMode_DISABLED:
planner.synchronize();
prep_for_shaper_change();
dynFreqMode = dynFreqMode_t(m);
break;
}
update_shaping_params();
return 1;
}
@ -133,12 +178,30 @@ typedef struct FTConfig {
|| TERN0(HAS_DYNAMIC_FREQ_G, dynFreqMode == dynFreqMode_MASS_BASED));
}
bool setDynFreqK(const AxisEnum a, const float k) {
if (!modeUsesDynFreq()) return false;
if (k == dynFreqK[a]) return false;
prep_for_shaper_change();
dynFreqK[a] = k;
update_shaping_params();
return true;
}
#endif // HAS_DYNAMIC_FREQ
#endif // HAS_FTM_SHAPING
constexpr bool goodBaseFreq(const float f) { return WITHIN(f, FTM_MIN_SHAPE_FREQ, (FTM_FS) / 2); }
bool setBaseFreq(const AxisEnum a, float f) {
if (f == baseFreq[a]) return false;
LIMIT(f, FTM_MIN_SHAPE_FREQ, (FTM_FS) / 2);
prep_for_shaper_change();
baseFreq[a] = f;
update_shaping_params();
return true;
}
void set_defaults() {
#if HAS_STANDARD_MOTION
active = ENABLED(FTM_IS_DEFAULT_MOTION);
@ -164,6 +227,8 @@ typedef struct FTConfig {
#endif // HAS_FTM_SHAPING
TERN_(FTM_POLYS, poly6_acceleration_overshoot = FTM_POLY6_ACCELERATION_OVERSHOOT);
update_shaping_params();
}
} ft_config_t;
@ -186,8 +251,6 @@ class FTMotion {
static void set_defaults() {
cfg.set_defaults();
TERN_(HAS_FTM_SHAPING, update_shaping_params());
#if ENABLED(FTM_SMOOTHING)
#define _RESET_SMOOTH(A) (void)set_smoothing_time(_AXIS(A), FTM_SMOOTHING_TIME_##A);
CARTES_MAP(_RESET_SMOOTH);
@ -210,11 +273,6 @@ class FTMotion {
static ResonanceGenerator rtg; // Resonance trajectory generator instance
#endif
#if HAS_FTM_SHAPING
// Refresh gains and indices used by shaping functions.
static void update_shaping_params();
#endif
#if ENABLED(FTM_SMOOTHING)
// Refresh alpha and delay samples used by smoothing functions.
static void update_smoothing_params();
@ -271,6 +329,7 @@ class FTMotion {
endPos_prevBlock; // (mm) End position of previous block
static xyze_float_t ratio; // (ratio) Axis move ratio of block
static float tau; // (s) Time since start of block
static bool fastForwardUntilMotion; // Fast forward time if there is no motion
// Trajectory generators
static TrapezoidalTrajectoryGenerator trapezoidalGenerator;
@ -307,6 +366,19 @@ class FTMotion {
static float prev_traj_e;
#endif
#if HAS_FTM_SHAPING
// Refresh gains and indices used by shaping functions.
friend void ft_config_t::update_shaping_params();
static void update_shaping_params();
#endif
// Synchronize and reset motion prior to parameter changes
friend void ft_config_t::prep_for_shaper_change();
static void prep_for_shaper_change() {
planner.synchronize();
reset();
}
// Buffers
static void discard_planner_block_protected();
static uint32_t calc_runout_samples();
@ -314,7 +386,7 @@ class FTMotion {
static void fill_stepper_plan_buffer();
static xyze_float_t calc_traj_point(const float dist);
static bool plan_next_block();
static void ensure_float_precision();
static void ensure_float_precision() IF_DISABLED(HAS_EXTRUDERS, {});
}; // class FTMotion

View file

@ -90,7 +90,7 @@ void AxisShaping::set_axis_shaping_A(
} break;
#endif
#if ENABLED(FTM_SHAPER_H2EI)
#if ENABLED(FTM_SHAPER_2HEI)
case ftMotionShaper_2HEI: {
max_i = 3U;
const float vtolx2 = sq(vtol);
@ -130,61 +130,65 @@ void AxisShaping::set_axis_shaping_A(
break;
#endif
default:
case ftMotionShaper_NONE:
max_i = 0;
Ai[0] = 1.0f; // No echoes so the whole impulse is applied in the first tap
break;
}
}
} // set_axis_shaping_A
// Refresh the indices used by shaping functions.
// Ai[] must be precomputed (if zeta or vtol change, call set_axis_shaping_A first)
void AxisShaping::set_axis_shaping_N(const ftMotionShaper_t shaper, const float f, const float zeta) {
// Note that protections are omitted for DBZ and for index exceeding array length.
const float df = sqrt ( 1.f - sq(zeta) );
const float df = SQRT(1.f - sq(zeta));
float base = 0.0f;
switch (shaper) {
case ftMotionShaper_ZV:
Ni[1] = LROUND((0.5f / f / df) * (FTM_FS));
break;
case ftMotionShaper_ZVD:
case ftMotionShaper_EI:
Ni[1] = LROUND((0.5f / f / df) * (FTM_FS));
Ni[2] = Ni[1] + Ni[1];
break;
case ftMotionShaper_ZVDD:
case ftMotionShaper_2HEI:
Ni[1] = LROUND((0.5f / f / df) * (FTM_FS));
Ni[2] = Ni[1] + Ni[1];
Ni[3] = Ni[2] + Ni[1];
break;
case ftMotionShaper_ZVDDD:
case ftMotionShaper_3HEI:
Ni[1] = LROUND((0.5f / f / df) * (FTM_FS));
Ni[2] = Ni[1] + Ni[1];
Ni[3] = Ni[2] + Ni[1];
Ni[4] = Ni[3] + Ni[1];
break;
case ftMotionShaper_MZV:
Ni[1] = LROUND((0.375f / f / df) * (FTM_FS));
Ni[2] = Ni[1] + Ni[1];
break;
#if ANY(FTM_SHAPER_ZV, FTM_SHAPER_ZVD, FTM_SHAPER_EI, FTM_SHAPER_ZVDD, FTM_SHAPER_2HEI, FTM_SHAPER_ZVDDD, FTM_SHAPER_3HEI)
TERN_(FTM_SHAPER_ZV, case ftMotionShaper_ZV: )
TERN_(FTM_SHAPER_ZVD, case ftMotionShaper_ZVD: )
TERN_(FTM_SHAPER_EI, case ftMotionShaper_EI: )
TERN_(FTM_SHAPER_ZVDD, case ftMotionShaper_ZVDD: )
TERN_(FTM_SHAPER_2HEI, case ftMotionShaper_2HEI: )
TERN_(FTM_SHAPER_ZVDDD, case ftMotionShaper_ZVDDD: )
TERN_(FTM_SHAPER_3HEI, case ftMotionShaper_3HEI: )
base = 0.5f;
break;
#endif
#if ENABLED(FTM_SHAPER_MZV)
case ftMotionShaper_MZV: base = 0.375f; break;
#endif
case ftMotionShaper_NONE:
// No echoes.
// max_i is set to 0 by set_axis_shaping_A, so delay centroid (Ni[0]) will also correctly be 0
default:
// No echoes. max_i already set to 0 by set_axis_shaping_A
break;
}
// Group delay in samples (i.e., Axis delay caused by shaping): sum(Ai * Ni[i]).
// Skipping i=0 since the uncompensated delay of the first impulse is always zero, so Ai[0] * Ni[0] == 0
float centroid = 0.0f;
for (uint8_t i = 1; i <= max_i; ++i) centroid -= Ai[i] * Ni[i];
#if HAS_FTM_SHAPING
Ni[0] = LROUND(centroid);
// Compute echo indices
Ni[1] = LROUND((base / f / df) * FTM_FS);
for (uint8_t i = 2; i <= max_i; ++i) Ni[i] = Ni[i - 1] + Ni[1];
// The resulting echo index can be negative, this is ok because it will be offset
// by the max delay of all axes before it is used.
for (uint8_t i = 1; i <= max_i; ++i) Ni[i] += Ni[0];
}
// Group delay in samples (i.e., Axis delay caused by shaping): sum(Ai * Ni[i]).
// Skipping i=0 since the uncompensated delay of the first impulse is always zero,
// so Ai[0] * Ni[0] == 0
float centroid = 0.0f;
for (uint8_t i = 1; i <= max_i; ++i) centroid -= Ai[i] * Ni[i];
Ni[0] = LROUND(centroid);
// The resulting echo index can be negative, this is ok because it will be offset
// by the max delay of all axes before it is used.
for (uint8_t i = 1; i <= max_i; ++i) Ni[i] += Ni[0];
#endif
} // set_axis_shaping_N
#endif // FT_MOTION

View file

@ -91,14 +91,39 @@ typedef FTShapedAxes<float> ft_shaped_float_t;
typedef FTShapedAxes<ftMotionShaper_t> ft_shaped_shaper_t;
typedef FTShapedAxes<dynFreqMode_t> ft_shaped_dfm_t;
#define FTM_MAX_DAMPENING 0.25
constexpr float ftm_max_dampening = float(FTM_MAX_DAMPENING),
ftm_min_df = SQRT(1.0f - sq(ftm_max_dampening));
constexpr uint32_t CALC_N1(const float v) { return LROUND((v / FTM_MIN_SHAPE_FREQ / ftm_min_df) * (FTM_FS)); }
// Maximum delays for shaping functions
constexpr float ftm_shaping_max_i = _MAX(0.0f
OPTARG(FTM_SHAPER_ZV, 1 * CALC_N1(0.5f)) OPTARG(FTM_SHAPER_EI, 2 * CALC_N1(0.5f) )
OPTARG(FTM_SHAPER_ZVD, 2 * CALC_N1(0.5f)) OPTARG(FTM_SHAPER_2HEI, 3 * CALC_N1(0.5f) )
OPTARG(FTM_SHAPER_ZVDD, 3 * CALC_N1(0.5f)) OPTARG(FTM_SHAPER_3HEI, 4 * CALC_N1(0.5f) )
OPTARG(FTM_SHAPER_ZVDDD, 4 * CALC_N1(0.5f)) OPTARG(FTM_SHAPER_MZV, 2 * CALC_N1(0.375f))
);
// Max delays for smoothing
constexpr uint32_t ftm_smooth_max_i = uint32_t(TERN0(FTM_SMOOTHING, CEIL(FTM_FS * FTM_MAX_SMOOTHING_TIME)));
constexpr size_t ftm_zmax = ftm_shaping_max_i + ftm_smooth_max_i;
constexpr uint8_t ftm_shaping_ni_size = _MAX(1
OPTARG(FTM_SHAPER_ZV, 2) OPTARG(FTM_SHAPER_EI, 3)
OPTARG(FTM_SHAPER_ZVD, 3) OPTARG(FTM_SHAPER_2HEI, 4)
OPTARG(FTM_SHAPER_ZVDD, 4) OPTARG(FTM_SHAPER_3HEI, 5)
OPTARG(FTM_SHAPER_ZVDDD, 5) OPTARG(FTM_SHAPER_MZV, 3)
);
// Shaping data
typedef struct AxisShaping {
bool ena = false; // Enabled indication
float d_zi[FTM_ZMAX] = { 0.0f }; // Data point delay vector
float Ai[5]; // Shaping gain vector
int32_t Ni[5]; // Shaping time index vector
uint32_t max_i; // Vector length for the selected shaper
bool ena = false; // Enabled indication
float d_zi[ftm_zmax] = { 0.0f }; // Data point delay vector
float Ai[ftm_shaping_ni_size]; // Shaping gain vector
int32_t Ni[ftm_shaping_ni_size] = { 0 }; // Shaping time index vector
uint32_t max_i; // Vector length for the selected shaper
// Set the gains used by shaping functions
void set_axis_shaping_N(const ftMotionShaper_t shaper, const float f, const float zeta);
@ -117,7 +142,7 @@ typedef struct Shaping {
axis_shaping_t SHAPED_AXIS_NAMES;
uint32_t largest_delay_samples;
// Shaping an axis makes it lag with respect to the others by certain amount, the "centroid delay"
// Ni[0] stores how far in the past the first step would need to happen to avoid desynchronisation (it is therefore negative).
// Ni[0] stores how far in the past the first step would need to happen to avoid desynchronization (it is therefore negative).
// Of course things can't be done in the past, so when shaping is applied, the all axes are delayed by largest_delay_samples
// minus their own centroid delay. This makes them all be equally delayed and therefore in synch.
void refresh_largest_delay_samples() { largest_delay_samples = -_MIN(SHAPED_LIST(X.Ni[0], Y.Ni[0], Z.Ni[0], E.Ni[0])); }

View file

@ -34,22 +34,22 @@ typedef struct FTSmoothedAxes {
} ft_smoothed_float_t;
// Smoothing data for each axis
// The smoothing algorithm used is an approximation of moving window averaging with gaussian weights, based
// on chained exponential smoothers.
// For the smoothing algorithm use an approximation of moving window averaging
// with Gaussian weights, based on chained exponential smoothers.
typedef struct AxisSmoothing {
float smoothing_pass[FTM_SMOOTHING_ORDER] = { 0.0f }; // Last value of each of the exponential smoothing passes
float alpha = 0.0f; // Pre-calculated alpha for smoothing.
uint32_t delay_samples = 0; // Pre-calculated delay in samples for smoothing.
void set_time(const float s_time); // Set smoothing time, recalculate alpha and delay.
float alpha = 0.0f; // Pre-calculated alpha for smoothing
uint32_t delay_samples = 0; // Pre-calculated delay in samples for smoothing
void set_time(const float s_time); // Set smoothing time, recalculate alpha and delay
} axis_smoothing_t;
typedef struct Smoothing {
axis_smoothing_t CARTES_AXIS_NAMES;
int32_t largest_delay_samples;
// Smoothing causes a phase delay equal to smoothing_time. This delay is componensated for during axis synchronisation, which
// is done by delaying all axes to match the laggiest one (i.e largest_delay_samples).
// Smoothing causes a phase delay equal to smoothing_time. This delay is compensated-for during axis synchronization,
// which is done by delaying all axes to match the laggiest one (i.e., largest_delay_samples).
void refresh_largest_delay_samples() { largest_delay_samples = _MAX(CARTES_LIST(X.delay_samples, Y.delay_samples, Z.delay_samples, E.delay_samples)); }
// Note: the delay equals smoothing_time iff the input signal frequency is lower than 1/smoothing_time, luckily for us, this holds in this case
// Note: The delay equals smoothing_time only if the input signal frequency is under 1/smoothing_time; which, luckily, holds in this case.
void reset() {
#define _CLEAR(A) ZERO(A.smoothing_pass);
LOGICAL_AXIS_MAP(_CLEAR);

View file

@ -30,19 +30,22 @@ FORCE_INLINE constexpr uint32_t a_times_b_shift_16(const uint32_t a, const uint3
const uint32_t hi = a >> 16, lo = a & 0x0000FFFF;
return (hi * b) + ((lo * b) >> 16);
}
#define FTM_NEVER uint32_t(UINT16_MAX) // Reserved number to indicate "no ticks in this frame" (FRAME_TICKS_FP+1 would work too)
constexpr uint32_t FRAME_TICKS = STEPPER_TIMER_RATE / FTM_FS; // Timer ticks per frame (by default, 1kHz)
constexpr uint32_t TICKS_BITS = __builtin_clzl(FRAME_TICKS + 1UL); // Bits to represent the max value (duration of a frame, +1 one for FTM_NEVER).
constexpr uint32_t FTM_Q_INT = 32u - TICKS_BITS; // Bits remaining
// "clz" counts leading zeroes.
constexpr uint32_t FTM_Q = 16u - FTM_Q_INT; // uint16 interval fractional bits.
// Intervals buffer has fixed point numbers with the point on this position
static_assert(FRAME_TICKS < FTM_NEVER, "(STEPPER_TIMER_RATE / FTM_FS) must be < " STRINGIFY(FTM_NEVER) " to fit 16-bit fixed-point numbers.");
static_assert(FRAME_TICKS != 2000 || FTM_Q_INT == 11, "FTM_Q_INT should be 11");
static_assert(FRAME_TICKS != 2000 || FTM_Q == 5, "FTM_Q should be 5");
static_assert(FRAME_TICKS != 25000 || FTM_Q_INT == 15, "FTM_Q_INT should be 15");
static_assert(FRAME_TICKS != 25000 || FTM_Q == 1, "FTM_Q should be 1");
// Count leading zeroes of v when stored in a 32 bit uint, equivalent to `32 - ceil(log2(v))`
constexpr int CLZ32(const uint32_t v, const int c=0) {
return v ? (TEST32(v, 31)) ? c : CLZ32(v << 1, c + 1) : 32;
}
#define FTM_NEVER uint32_t(UINT16_MAX) // Reserved number to indicate "no ticks in this frame" (FRAME_TICKS_FP+1 would work too)
constexpr uint32_t FRAME_TICKS = STEPPER_TIMER_RATE / FTM_FS; // Timer ticks per frame
constexpr uint32_t FTM_Q_INT = 32u - CLZ32(FRAME_TICKS + 1U); // Bits to represent the integer part of the max value (duration of a frame, +1 one for FTM_NEVER).
constexpr uint32_t FTM_Q = 16u - FTM_Q_INT; // uint16 interval fractional bits.
// Intervals buffer has fixed point numbers with the point on this position
static_assert(FRAME_TICKS < FTM_NEVER, "(STEPPER_TIMER_RATE / FTM_FS) (" STRINGIFY(STEPPER_TIMER_RATE) " / " STRINGIFY(FTM_FS) ") must be < " STRINGIFY(FTM_NEVER) " to fit 16-bit fixed-point numbers.");
// Sanity check
static_assert(POW(2, 16 - FTM_Q) > FRAME_TICKS, "FRAME_TICKS in Q format should fit in a uint16");
static_assert(POW(2, 16 - FTM_Q - 1) <= FRAME_TICKS, "A smaller FTM_Q would still alow a FRAME_TICKS in Q format to fit in a uint16");
// The _FP and _fp suffixes mean the number is in fixed point format with the point at the FTM_Q position.
// See: https://en.wikipedia.org/wiki/Fixed-point_arithmetic
@ -151,6 +154,8 @@ typedef struct Stepping {
// Buffering part
//
#define FTM_BUFFER_MASK (FTM_BUFFER_SIZE - 1u)
stepper_plan_t stepper_plan_buff[FTM_BUFFER_SIZE];
uint32_t stepper_plan_tail = 0, stepper_plan_head = 0;
XYZEval<int64_t> curr_steps_q48_16{0};

View file

@ -783,22 +783,29 @@ block_t* Planner::get_future_block(const uint8_t offset) {
}
/**
* Calculate trapezoid parameters, multiplying the entry- and exit-speeds
* by the provided factors. If entry_factor is 0 don't change the initial_rate.
* Assumes that the implied initial_rate and final_rate are no less than
* sqrt(block->acceleration_steps_per_s2 / 2). This is ensured through
* minimum_planner_speed_sqr / min_entry_speed_sqr - but there's one
* exception in recalculate_trapezoids().
* Calculate trapezoid (or or update FTM) motion parameters for a block.
*
* `entry_speed` is an optional override in mm/s.
* A value of `0` is a sentinel meaning do not override the blocks
* existing entry speed / initial_rate.
*
* This is relied upon by recalculate_trapezoids(), which intentionally
* passes `0` to preserve previously propagated speeds.
*
* Assumes implied entry and exit speeds are >= sqrt(acceleration / 2),
* enforced via minimum_planner_speed_sqr / min_entry_speed_sqr, with one
* controlled exception in recalculate_trapezoids().
*
* ############ VERY IMPORTANT ############
* NOTE: The PRECONDITION to call this function is that the block is
* NOT BUSY and it is marked as RECALCULATE. That WARRANTIES the Stepper ISR
* is not and will not use the block while we modify it.
* PRECONDITIONs to run this function:
* - The block is NOT BUSY.
* - The block is marked RECALCULATE.
* That WARRANTIES the Stepper ISR is not and will not use the block while we modify it.
*/
void Planner::calculate_trapezoid_for_block(block_t * const block, const float entry_speed, const float exit_speed) {
#if ENABLED(FT_MOTION)
block->entry_speed = entry_speed;
if (entry_speed) block->entry_speed = entry_speed;
block->exit_speed = exit_speed;
#endif
@ -2628,7 +2635,7 @@ bool Planner::_populate_block(
// Fast acos(-t) approximation (max. error +-0.033rad = 1.89°)
// Based on MinMax polynomial published by W. Randolph Franklin, see
// https://wrf.ecse.rpi.edu/Research/Short_Notes/arcsin/onlyelem.html
// https://wrfranklin.org/Research/Short_Notes/arcsin/onlyelem.html
// acos( t) = pi / 2 - asin(x)
// acos(-t) = pi - acos(t) ... pi / 2 + asin(x)

View file

@ -67,7 +67,7 @@ static inline float dist1(const float x1, const float y1, const float x2, const
/**
* The algorithm for computing the step is loosely based on the one in Kig
* (See https://sources.debian.net/src/kig/4:15.08.3-1/misc/kigpainter.cpp/#L759)
* (See https://sources.debian.org/src/kig/4:15.08.3-1/misc/kigpainter.cpp/#L759)
* However, we do not use the stack.
*
* The algorithm goes as it follows: the parameters t runs from 0.0 to

View file

@ -1593,8 +1593,10 @@ void Stepper::isr() {
// FT Motion can be toggled if Standard Motion is also active
const bool using_ftMotion = ENABLED(NO_STANDARD_MOTION) || TERN0(FT_MOTION, ftMotion.cfg.active);
// We need this variable here to be able to use it in the following loop
// Storage for the soonest timer value of the next possible ISR, used in this do loop
hal_timer_t min_ticks;
// Loop until all events for this ISR have been issued
do {
hal_timer_t interval = 0;
@ -1744,7 +1746,7 @@ void Stepper::isr() {
* Get the current tick value + margin
* Assuming at least 6µs between calls to this ISR...
* On AVR the ISR epilogue+prologue is estimated at 100 instructions - Give 8µs as margin
* On ARM the ISR epilogue+prologue is estimated at 20 instructions - Give 1µs as margin
* On ARM the ISR epilogue+prologue is estimated at 20 instructions - Give 1µs as margin
*/
min_ticks = HAL_timer_get_count(MF_TIMER_STEP) + hal_timer_t(TERN(__AVR__, 8, 1) * (STEPPER_TIMER_TICKS_PER_US));
@ -3623,7 +3625,24 @@ void Stepper::report_positions() {
DIR_WAIT_AFTER();
}
// Start step pulses. Edge stepping will toggle the STEP pin.
/**
* - For every axis drive STEP pins
* - If any axes lack DEDGE stepping:
* - Wait for the longest required Pulse Delay
* - Reset state of all non-DEDGE STEP pins
*
* The stepper_extruder must be pre-filled at this point.
*
* Emits macros of the form: [XYZEIJKUVW]_APPLY_STEP(state, ?always?)
* For the standard E axis this expands to: E_STEP_WRITE(stepper_extruder, state)
*
* TODO: For MIXING_EXTRUDER stepping distribute the steps proportionally to the
* E stepper drivers' STEP pins according to pre-calculated Bresenham factors.
* So the events are timed just like normal E stepping; only the STEP pin varies.
*/
// Start step pulses on all axes including the active Extruder.
// Edge stepping will simply toggle the STEP pin.
#define _FTM_STEP_START(A) A##_APPLY_STEP(step_bits.A, false);
LOGICAL_AXIS_MAP(_FTM_STEP_START);

View file

@ -21,7 +21,7 @@
*/
#pragma once
// R25 = 100 kOhm, beta25 = 4100 K, 4.7 kOhm pull-up, Hisens thermistor
// R25 = 100 kOhm, beta25 = 4100 K, 4.7 kOhm pull-up, Hisense thermistor
constexpr temp_entry_t temptable_13[] PROGMEM = {
{ OV( 20.04), 300 },
{ OV( 23.19), 290 },

View file

@ -122,7 +122,7 @@ typedef struct { raw_adc_t value; celsius_t celsius; } temp_entry_t;
#if ANY_THERMISTOR_IS(12) // beta25 = 4700 K, R25 = 100kΩ, Pullup = 4.7kΩ, "Personal calibration for Makibox hot bed"
#include "thermistor_12.h"
#endif
#if ANY_THERMISTOR_IS(13) // beta25 = 4100 K, R25 = 100kΩ, Pullup = 4.7kΩ, "Hisens"
#if ANY_THERMISTOR_IS(13) // beta25 = 4100 K, R25 = 100kΩ, Pullup = 4.7kΩ, "Hisense"
#include "thermistor_13.h"
#endif
#if ANY_THERMISTOR_IS(14) // beta25 = 4092 K, R25 = 100kΩ, Pullup = 4.7kΩ, "EPCOS" for hot bed

View file

@ -23,7 +23,7 @@
/**
* Geeetech GT2560 Revision A+ board pin assignments
* Schematic: https://www.geeetech.com/wiki/images/d/d3/Hardware_GT2560_RevA%2B.pdf
* Schematic: https://wiki.geeetech.com/images/d/d3/Hardware_GT2560_RevA+.pdf
* ATmega2560
*/

View file

@ -23,7 +23,7 @@
/**
* Geeetech GT2560 Rev B Pins
* Schematic: https://www.geeetech.com/wiki/images/7/72/GT2560_REVB.pdf
* Schematic: https://wiki.geeetech.com/images/7/72/GT2560_REVB.pdf
* ATmega2560
*/

View file

@ -23,7 +23,7 @@
/**
* Protoneer v3.00 pin assignments
* Schematic: https://i0.wp.com/blog.protoneer.co.nz/wp-content/uploads/2013/07/Arduino-CNC-Shield-Scematics-V3.XX_.jpg
* Schematic: https://hexmix.ru/wp-content/uploads/2019/03/Arduino-CNC-Shield-V3.XX_.pdf
* ATmega2560
*
* This CNC shield has an UNO pinout and fits all Arduino-compatibles.

View file

@ -1072,7 +1072,7 @@
#elif MB(ERROR)
#warning "Most likely missing / misplaced Configuration files."
#elif defined(MOTHERBOARD)
#error "Unknown MOTHERBOARD value set in Configuration.h."
static_assert(false, "Unknown MOTHERBOARD value (" STRINGIFY(MOTHERBOARD) ") set in Configuration.h.");
#else
#error "MOTHERBOARD not defined! Use '#define MOTHERBOARD BOARD_...' in Configuration.h."
#endif

View file

@ -181,5 +181,5 @@
* ##################################
*
* Pictogram by Ludy https://github.com/Ludy87
* See: https://sebastien.andrivet.com/en/posts/wanhao-duplicator-i3-plus-3d-printer/
* See: https://sebastien.andrivet.com/en/posts/wanhao-duplicator-i3-plus-3d-printers/
*/

View file

@ -24,7 +24,7 @@
/**
* K8200 Arduino Mega with RAMPS v1.3 pin assignments
* Identical to 3DRAG
* Schematic: https://www.velleman.eu/images/tmp/K8200diagram.jpg
* Schematic: https://cdn.velleman.eu/images/tmp/K8200diagram.jpg
* ATmega2560
*/

View file

@ -24,7 +24,7 @@
/**
* Velleman K8400 (Vertex)
* 3DRAG clone
* Schematic: https://filimprimante3d.fr/documents/k8400-schema-electronique.jpg
* Schematic: https://www.filimprimante3d.fr/documents/k8400-schema-electronique.jpg
* ATmega2560, ATmega1280
*
* K8400 has some minor differences over a normal 3Drag:

View file

@ -23,7 +23,7 @@
/**
* VORON Design v2 pin assignments
* See https://github.com/mzbotreprap/VORON/blob/master/Firmware/Marlin/pins_RAMPS_VORON.h
* See https://github.com/thaytan/VORON/blob/master/Firmware/Marlin/pins_RAMPS_VORON.h
* ATmega2560
*/

View file

@ -107,51 +107,35 @@
//
#define NEOPIXEL_PIN 24
// Custom serial pins for RP2040 UART remapping
#define SERIAL1_TX_PIN 8
#define SERIAL1_RX_PIN 9
/**
* TMC2208/TMC2209 stepper drivers
*/
#if HAS_TMC_UART
/**
* Hardware serial communication ports.
* If undefined software serial is used according to the pins below
*/
//#define X_HARDWARE_SERIAL Serial1
//#define X2_HARDWARE_SERIAL Serial1
//#define Y_HARDWARE_SERIAL Serial1
//#define Y2_HARDWARE_SERIAL Serial1
//#define Z_HARDWARE_SERIAL MSerial1
//#define Z2_HARDWARE_SERIAL Serial1
//#define E0_HARDWARE_SERIAL Serial1
//#define E1_HARDWARE_SERIAL Serial1
//#define E2_HARDWARE_SERIAL Serial1
//#define E3_HARDWARE_SERIAL Serial1
//#define E4_HARDWARE_SERIAL Serial1
#define X_HARDWARE_SERIAL MarlinSerial1
#define Y_HARDWARE_SERIAL MarlinSerial1
#define Z_HARDWARE_SERIAL MarlinSerial1
#define E0_HARDWARE_SERIAL MarlinSerial1
/**
* Software serial
*/
#ifndef X_SERIAL_TX_PIN
#define X_SERIAL_TX_PIN 8
// Default TMC slave addresses
#ifndef X_SLAVE_ADDRESS
#define X_SLAVE_ADDRESS 0
#endif
#ifndef X_SERIAL_RX_PIN
#define X_SERIAL_RX_PIN 9
#ifndef Y_SLAVE_ADDRESS
#define Y_SLAVE_ADDRESS 2
#endif
#ifndef Y_SERIAL_TX_PIN
#define Y_SERIAL_TX_PIN 8
#ifndef Z_SLAVE_ADDRESS
#define Z_SLAVE_ADDRESS 1
#endif
#ifndef Y_SERIAL_RX_PIN
#define Y_SERIAL_RX_PIN 9
#endif
#ifndef Z_SERIAL_TX_PIN
#define Z_SERIAL_TX_PIN 8
#endif
#ifndef Z_SERIAL_RX_PIN
#define Z_SERIAL_RX_PIN 9
#endif
#ifndef E0_SERIAL_TX_PIN
#define E0_SERIAL_TX_PIN 8
#endif
#ifndef E0_SERIAL_RX_PIN
#define E0_SERIAL_RX_PIN 9
#ifndef E0_SLAVE_ADDRESS
#define E0_SLAVE_ADDRESS 3
#endif
#define TMC_BAUD_RATE 115200
#endif

View file

@ -23,7 +23,7 @@
/**
* Bricolemon Lite Board. Based on atsamd51 (AGCM4), bootloader and credits by ADAFRUIT.
* https://lemoncrest.com https://bricogeek.com
* https://lemoncrest.com https://tienda.bricogeek.com
*
* This board its a 3.3V LOGIC Board, following the ADAFRUIT example, all of the board is open source.
* Schematic: Refer to the Bricolemon

View file

@ -23,7 +23,7 @@
/**
* Bricolemon Board. Based on ATSAMD51 (AGCM4), bootloader and credits by ADAFRUIT.
* https://lemoncrest.com https://bricogeek.com
* https://lemoncrest.com https://tienda.bricogeek.com
*/
#if NOT_TARGET(ARDUINO_GRAND_CENTRAL_M4)

View file

@ -24,6 +24,7 @@
/**
* ReprapWorld Minitronics v2.0
* https://reprap.org/wiki/Minitronics_20
* https://www.123-3d.nl/pdf/datasheet_minitronics_20_20181003.pdf
* 48MHz Atmel SAMD21J18 ARM Cortex-M0+
*/

Some files were not shown because too many files have changed in this diff Show more