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

This commit is contained in:
Andrew 2025-10-29 08:00:24 -04:00 committed by GitHub
commit 91665ea321
No known key found for this signature in database
GPG key ID: B5690EEEBB952194
361 changed files with 5185 additions and 2854 deletions

0
.gitignore vendored Executable file → Normal file
View file

View file

@ -4,6 +4,31 @@ CONTAINER_RT_OPTS := --rm -v $(PWD):/code -v platformio-cache:/root/.platformio
CONTAINER_IMAGE := marlin-dev
UNIT_TEST_CONFIG ?= default
# Find a Python 3 interpreter
ifeq ($(OS),Windows_NT)
# Windows: use `where` fall back through the three common names
PYTHON := $(shell 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))
else
# POSIX: use `command -v` prefer python3 over python
PYTHON := $(shell command -v python3 2>/dev/null || command -v python 2>/dev/null)
# Unix/Linux: Use find command
PINS := $(shell find Marlin/src/pins -mindepth 2 -name 'pins_*.h')
endif
# Check that the found interpreter is Python 3
# Error if there's no Python 3 available
ifneq ($(strip $(PYTHON)),)
PYTHON_VERSION := $(shell $(PYTHON) -c "import sys; print(sys.version_info[0])" 2>/dev/null)
ifneq ($(PYTHON_VERSION),3)
$(error $(PYTHON) is not Python 3 install a Python3.x interpreter or adjust your PATH)
endif
else
$(error No Python executable found install Python 3.x and make sure it is in your PATH)
endif
help:
@echo "Tasks for local development:"
@echo "make marlin : Build Marlin for the configured board"
@ -20,7 +45,7 @@ help:
@echo "make unit-test-single-local-docker : Run unit tests for a single config locally, using docker"
@echo "make unit-test-all-local : Run all code tests locally"
@echo "make unit-test-all-local-docker : Run all code tests locally, using docker"
@echo "make setup-local-docker : Setup local docker using buildx"
@echo "make setup-local-docker : Setup local docker"
@echo ""
@echo "Options for testing:"
@echo " TEST_TARGET Set when running tests-single-*, to select the"
@ -41,6 +66,9 @@ marlin:
./buildroot/bin/mftest -a
.PHONY: marlin
clean:
rm -rf .pio/build*
tests-single-ci:
export GIT_RESET_HARD=true
$(MAKE) tests-single-local TEST_TARGET=$(TEST_TARGET) PLATFORMIO_BUILD_FLAGS=-DGITHUB_ACTION
@ -57,10 +85,10 @@ tests-single-local-docker:
$(CONTAINER_RT_BIN) run $(CONTAINER_RT_OPTS) $(CONTAINER_IMAGE) make tests-single-local TEST_TARGET=$(TEST_TARGET) VERBOSE_PLATFORMIO=$(VERBOSE_PLATFORMIO) GIT_RESET_HARD=$(GIT_RESET_HARD) ONLY_TEST="$(ONLY_TEST)"
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)
@$(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) $(SCRIPTS_DIR)/get_test_targets.py) ; do \
if [ "$$TEST_TARGET" = "linux_native" ] && [ "$$(uname)" = "Darwin" ]; then \
echo "Skipping tests for $$TEST_TARGET on macOS" ; \
continue ; \
@ -88,18 +116,36 @@ unit-test-all-local-docker:
@if ! $(CONTAINER_RT_BIN) images -q $(CONTAINER_IMAGE) > /dev/null ; then $(MAKE) setup-local-docker ; fi
$(CONTAINER_RT_BIN) run $(CONTAINER_RT_OPTS) $(CONTAINER_IMAGE) make unit-test-all-local
setup-local-docker:
$(CONTAINER_RT_BIN) buildx build -t $(CONTAINER_IMAGE) -f docker/Dockerfile .
USERNAME := $(shell whoami)
USER_ID := $(shell id -u)
GROUP_ID := $(shell id -g)
PINS := $(shell find Marlin/src/pins -mindepth 2 -name '*.h')
.PHONY: setup-local-docker setup-local-docker-old
setup-local-docker:
@echo "Building marlin-dev Docker image..."
$(CONTAINER_RT_BIN) build -t $(CONTAINER_IMAGE) \
--build-arg USERNAME=$(USERNAME) \
--build-arg USER_ID=$(USER_ID) \
--build-arg GROUP_ID=$(GROUP_ID) \
-f docker/Dockerfile .
@echo
@echo "To run all tests in Docker:"
@echo " make tests-all-local-docker"
@echo "To run a single test in Docker:"
@echo " make tests-single-local-docker TEST_TARGET=mega2560"
setup-local-docker-old:
$(CONTAINER_RT_BIN) buildx build -t $(CONTAINER_IMAGE) -f docker/Dockerfile .
.PHONY: $(PINS) format-pins validate-pins
$(PINS): %:
@echo "Formatting pins $@"
@python $(SCRIPTS_DIR)/pinsformat.py $< $@
@$(PYTHON) $(SCRIPTS_DIR)/pinsformat.py $< $@
format-pins: $(PINS)
@echo "Processed $(words $(PINS)) pins files"
validate-pins: format-pins
@echo "Validating pins files"
@ -109,8 +155,8 @@ validate-pins: format-pins
format-lines:
@echo "Formatting all sources"
@python $(SCRIPTS_DIR)/linesformat.py buildroot
@python $(SCRIPTS_DIR)/linesformat.py Marlin
@$(PYTHON) $(SCRIPTS_DIR)/linesformat.py buildroot
@$(PYTHON) $(SCRIPTS_DIR)/linesformat.py Marlin
validate-lines:
@echo "Validating text formatting"
@ -122,4 +168,4 @@ BOARDS_FILE := Marlin/src/core/boards.h
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) $(SCRIPTS_DIR)/validate_boards.py $(BOARDS_FILE) || (echo "\nError: boards.h file is not valid. Please check and correct it.\n" && exit 1)

View file

@ -942,7 +942,7 @@
* protect against a broken or disconnected thermistor wire.
*
* The issue: If a thermistor falls out, it will report the much lower
* temperature of the air in the room, and the the firmware will keep
* temperature of the air in the room, and the firmware will keep
* the heater on.
*
* If you get "Thermal Runaway" or "Heating failed" errors the
@ -3469,6 +3469,7 @@
* NOTOSANS - Default font with anti-aliasing. Supports Latin Extended and non-Latin characters.
* UNIFONT - Lightweight font, no anti-aliasing. Supports Latin Extended and non-Latin characters.
* HELVETICA - Lightweight font, no anti-aliasing. Supports Basic Latin (0x0020-0x007F) and Latin-1 Supplement (0x0080-0x00FF) characters only.
* :['NOTOSANS', 'UNIFONT', 'HELVETICA']
*/
#define TFT_FONT NOTOSANS
@ -3478,6 +3479,7 @@
* BLUE_MARLIN - Default theme with 'midnight blue' background
* BLACK_MARLIN - Theme with 'black' background
* ANET_BLACK - Theme used for Anet ET4/5
* :['BLUE_MARLIN', 'BLACK_MARLIN', 'ANET_BLACK']
*/
#define TFT_THEME BLACK_MARLIN

View file

@ -297,7 +297,7 @@
* protect against a broken or disconnected thermistor wire.
*
* The issue: If a thermistor falls out, it will report the much lower
* temperature of the air in the room, and the the firmware will keep
* temperature of the air in the room, and the firmware will keep
* the heater on.
*
* The solution: Once the temperature reaches the target, start observing.
@ -778,7 +778,7 @@
// @section endstops
// If you want endstops to stay on (by default) even when not homing
// If you want endstops to stay on (by default) even when not homing,
// enable this option. Override at any time with M120, M121.
//#define ENDSTOPS_ALWAYS_ON_DEFAULT
@ -1143,47 +1143,83 @@
/**
* Fixed-time-based Motion Control -- BETA FEATURE
* Enable/disable and set parameters with G-code M493.
* Enable/disable and set parameters with G-code M493 and M494.
* See ft_types.h for named values used by FTM options.
*/
//#define FT_MOTION
#if ENABLED(FT_MOTION)
//#define FTM_IS_DEFAULT_MOTION // Use FT Motion as the factory default?
//#define FTM_IS_DEFAULT_MOTION // Use FT Motion as the factory default?
//#define FT_MOTION_MENU // Provide a MarlinUI menu to set M493 and M494 parameters
//#define FTM_HOME_AND_PROBE // Use FT Motion for homing / probing. Disable if FT Motion breaks these functions.
#define FTM_DEFAULT_DYNFREQ_MODE dynFreqMode_DISABLED // Default mode of dynamic frequency calculation. (DISABLED, Z_BASED, MASS_BASED)
#define FTM_LINEAR_ADV_DEFAULT_ENA false // Default linear advance enable (true) or disable (false)
#define FTM_LINEAR_ADV_DEFAULT_K 0.0f // Default linear advance gain. (Acceleration-based scaling factor.)
#define FTM_DEFAULT_SHAPER_X ftMotionShaper_NONE // Default shaper mode on X axis (NONE, ZV, ZVD, ZVDD, ZVDDD, EI, 2HEI, 3HEI, MZV)
#define FTM_SHAPING_DEFAULT_FREQ_X 37.0f // (Hz) Default peak frequency used by input shapers
#define FTM_SHAPING_ZETA_X 0.1f // Zeta used by input shapers for X axis
#define FTM_SHAPING_V_TOL_X 0.05f // Vibration tolerance used by EI input shapers for X axis
#define FTM_DEFAULT_SHAPER_Y ftMotionShaper_NONE // Default shaper mode on Y axis
#define FTM_SHAPING_DEFAULT_FREQ_X 37.0f // (Hz) Default peak frequency used by input shapers
#define FTM_SHAPING_DEFAULT_FREQ_Y 37.0f // (Hz) Default peak frequency used by input shapers
#define FTM_LINEAR_ADV_DEFAULT_ENA false // Default linear advance enable (true) or disable (false)
#define FTM_LINEAR_ADV_DEFAULT_K 0.0f // Default linear advance gain. (Acceleration-based scaling factor.)
#define FTM_SHAPING_ZETA_X 0.1f // Zeta used by input shapers for X axis
#define FTM_SHAPING_ZETA_Y 0.1f // Zeta used by input shapers for Y axis
#define FTM_SHAPING_DEFAULT_FREQ_Y 37.0f // (Hz) Default peak frequency used by input shapers
#define FTM_SHAPING_ZETA_Y 0.1f // Zeta used by input shapers for Y axis
#define FTM_SHAPING_V_TOL_Y 0.05f // Vibration tolerance used by EI input shapers for Y axis
#define FTM_SHAPING_V_TOL_X 0.05f // Vibration tolerance used by EI input shapers for X axis
#define FTM_SHAPING_V_TOL_Y 0.05f // Vibration tolerance used by EI input shapers for Y axis
//#define FTM_SHAPER_Z // Include Z shaping support
#define FTM_DEFAULT_SHAPER_Z ftMotionShaper_NONE // Default shaper mode on Z axis
#define FTM_SHAPING_DEFAULT_FREQ_Z 21.0f // (Hz) Default peak frequency used by input shapers
#define FTM_SHAPING_ZETA_Z 0.03f // Zeta used by input shapers for Z axis
#define FTM_SHAPING_V_TOL_Z 0.05f // Vibration tolerance used by EI input shapers for Z axis
//#define FT_MOTION_MENU // Provide a MarlinUI menu to set M493 parameters
//#define FTM_SHAPER_E // Include E shaping support
// Required to synchronize extruder with XYZ (better quality)
#define FTM_DEFAULT_SHAPER_E ftMotionShaper_NONE // Default shaper mode on Extruder axis
#define FTM_SHAPING_DEFAULT_FREQ_E 21.0f // (Hz) Default peak frequency used by input shapers
#define FTM_SHAPING_ZETA_E 0.03f // Zeta used by input shapers for E axis
#define FTM_SHAPING_V_TOL_E 0.05f // Vibration tolerance used by EI input shapers for E axis
//#define FTM_SMOOTHING // Smoothing can reduce artifacts and make steppers quieter
// on sharp corners, but too much will round corners.
#if ENABLED(FTM_SMOOTHING)
#define FTM_MAX_SMOOTHING_TIME 0.10f // (s) Maximum smoothing time. Higher values consume more RAM.
// Increase smoothing time to reduce jerky motion, ghosting and noises.
#define FTM_SMOOTHING_TIME_X 0.00f // (s) Smoothing time for X axis. Zero means disabled.
#define FTM_SMOOTHING_TIME_Y 0.00f // (s) Smoothing time for Y axis
#define FTM_SMOOTHING_TIME_Z 0.00f // (s) Smoothing time for Z axis
#define FTM_SMOOTHING_TIME_E 0.02f // (s) Smoothing time for E axis. Prevents noise/skipping from LA by
// smoothing acceleration peaks, which may also smooth curved surfaces.
#endif
#define FTM_TRAJECTORY_TYPE TRAPEZOIDAL // Block acceleration profile (TRAPEZOIDAL, POLY5, POLY6)
// TRAPEZOIDAL: Continuous Velocity. Max acceleration is respected.
// POLY5: Like POLY6 with 1.5x but cpu cheaper.
// POLY6: Continuous Acceleration (aka S_CURVE).
// POLY trajectories not only reduce resonances without rounding corners, but also
// reduce extruder strain due to linear advance.
#define FTM_POLY6_ACCELERATION_OVERSHOOT 1.875f // Max acceleration overshoot factor for POLY6 (1.25 to 1.875)
/**
* Advanced configuration
*/
#define FTM_UNIFIED_BWS // DON'T DISABLE unless you use Ulendo FBS (not implemented)
#define FTM_UNIFIED_BWS // DON'T DISABLE unless you use Ulendo FBS (not implemented)
#if ENABLED(FTM_UNIFIED_BWS)
#define FTM_BW_SIZE 100 // Unified Window and Batch size with a ratio of 2
#define FTM_BW_SIZE 100 // Unified Window and Batch size with a ratio of 2
#else
#define FTM_WINDOW_SIZE 200 // Custom Window size for trajectory generation needed by Ulendo FBS
#define FTM_BATCH_SIZE 100 // Custom Batch size for trajectory generation needed by Ulendo FBS
#define FTM_WINDOW_SIZE 200 // Custom Window size for trajectory generation needed by Ulendo FBS
#define FTM_BATCH_SIZE 100 // Custom Batch size for trajectory generation needed by Ulendo FBS
#endif
#define FTM_FS 1000 // (Hz) Frequency for trajectory generation. (Reciprocal of FTM_TS)
#define FTM_TS 0.001f // (s) Time step for trajectory generation. (Reciprocal of FTM_FS)
#define FTM_FS 1000 // (Hz) Frequency for trajectory generation
#if DISABLED(COREXY)
#define FTM_STEPPER_FS 20000 // (Hz) Frequency for stepper I/O update
#define FTM_STEPPER_FS 20000 // (Hz) Frequency for stepper I/O update
// Use this to adjust the time required to consume the command buffer.
// Try increasing this value if stepper motion is choppy.
#define FTM_STEPPERCMD_BUFF_SIZE 3000 // Size of the stepper command buffers
#define FTM_STEPPERCMD_BUFF_SIZE 3000 // Size of the stepper command buffers
#else
// CoreXY motion needs a larger buffer size. These values are based on our testing.
@ -1191,18 +1227,7 @@
#define FTM_STEPPERCMD_BUFF_SIZE 6000
#endif
#define FTM_STEPS_PER_UNIT_TIME (FTM_STEPPER_FS / FTM_FS) // Interpolated stepper commands per unit time
#define FTM_CTS_COMPARE_VAL (FTM_STEPS_PER_UNIT_TIME / 2) // Comparison value used in interpolation algorithm
#define FTM_MIN_TICKS ((STEPPER_TIMER_RATE) / (FTM_STEPPER_FS)) // Minimum stepper ticks between steps
#define FTM_MIN_SHAPE_FREQ 10 // Minimum shaping frequency
#define FTM_RATIO (FTM_FS / FTM_MIN_SHAPE_FREQ) // Factor for use in FTM_ZMAX. DON'T CHANGE.
#define FTM_ZMAX (FTM_RATIO * 2) // Maximum delays for shaping functions (even numbers only!)
// Calculate as:
// ZV : FTM_RATIO / 2
// ZVD, MZV : FTM_RATIO
// 2HEI : FTM_RATIO * 3 / 2
// 3HEI : FTM_RATIO * 2
#define FTM_MIN_SHAPE_FREQ 10 // (Hz) Minimum shaping frequency, lower consumes more RAM
#endif // FT_MOTION
/**
@ -1852,6 +1877,7 @@
#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.
#endif
// Allow international symbols in long filenames. To display correctly, the
@ -4260,7 +4286,7 @@
//#define I2CPE_ENC_1_TICKS_REV (16 * 200) // Only needed for rotary encoders; number of stepper
// steps per full revolution (motor steps/rev * microstepping)
//#define I2CPE_ENC_1_INVERT // Invert the direction of axis travel.
#define I2CPE_ENC_1_EC_METHOD I2CPE_ECM_MICROSTEP // Type of error error correction.
#define I2CPE_ENC_1_EC_METHOD I2CPE_ECM_MICROSTEP // Type of error correction.
#define I2CPE_ENC_1_EC_THRESH 0.10 // Threshold size for error (in mm) above which the
// printer will attempt to correct the error; errors
// smaller than this are ignored to minimize effects of
@ -4692,6 +4718,11 @@
//
//#define PINS_DEBUGGING
//
// M265 - I2C Scanner
//
//#define I2C_SCANNER
// Enable Tests that will run at startup and produce a report
//#define MARLIN_TEST_BUILD

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-09-09"
//#define STRING_DISTRIBUTION_DATE "2025-10-29"
/**
* The protocol for communication to the host. Protocol indicates communication

View file

@ -86,13 +86,14 @@ heater_0_maxtemp = 275
pidtemp = on
pid_k1 = 0.95
pid_max = 255
pid_functional_range = 10
pid_functional_range = 20
default_kp = 22.20
default_ki = 1.08
default_kd = 114.00
temp_sensor_bed = 1
bed_check_interval = 5000
bed_mintemp = 5
bed_maxtemp = 150
@ -163,18 +164,28 @@ min_steps_per_segment = 6
default_minsegmenttime = 20000
[config:basic]
hotend_overshoot = 15
bed_overshoot = 10
max_bed_power = 255
busy_while_heating = on
host_keepalive_feature = on
default_keepalive_interval = 2
printjob_timer_autostart = on
jd_handle_small_segments = on
validate_homing_endstops = on
editable_steps_per_unit = on
eeprom_boot_silent = on
eeprom_chitchat = on
endstoppullups = on
extrude_maxlength = 200
prevent_cold_extrusion = on
extrude_mintemp = 170
host_keepalive_feature = on
hotend_overshoot = 15
jd_handle_small_segments = on
max_bed_power = 255
prevent_lengthy_extrude = on
extrude_maxlength = 200
min_software_endstops = on
max_software_endstops = on
@ -195,21 +206,19 @@ preheat_2_temp_hotend = 240
preheat_2_temp_bed = 110
preheat_2_fan_speed = 0
prevent_cold_extrusion = on
prevent_lengthy_extrude = on
printjob_timer_autostart = on
temp_bed_hysteresis = 3
temp_bed_residency_time = 10
temp_bed_window = 1
temp_residency_time = 10
temp_window = 1
validate_homing_endstops = on
editable_steps_per_unit = on
[config:advanced]
arc_support = on
min_arc_segment_mm = 0.1
max_arc_segment_mm = 1.0
min_circle_segments = 72
n_arc_correction = 25
auto_report_temperatures = on
autotemp = on
@ -223,22 +232,23 @@ disable_idle_x = on
disable_idle_y = on
disable_idle_z = on
disable_idle_e = on
e0_auto_fan_pin = -1
faster_gcode_parser = on
debug_flags_gcode = on
homing_bump_mm = { 5, 5, 2 }
max_arc_segment_mm = 1.0
min_arc_segment_mm = 0.1
min_circle_segments = 72
n_arc_correction = 25
serial_overrun_protection = on
slowdown = on
slowdown_divisor = 2
tx_buffer_size = 0
multistepping_limit = 16
bed_check_interval = 5000
watch_bed_temp_increase = 2
watch_bed_temp_period = 60
serial_overrun_protection = on
tx_buffer_size = 0
watch_temp_increase = 2
watch_temp_period = 40
watch_bed_temp_increase = 2
watch_bed_temp_period = 60

View file

@ -241,7 +241,7 @@ uint8_t extDigitalRead(const int8_t pin) {
*
* DC values -1.0 to 1.0. Negative duty cycle inverts the pulse.
*/
uint16_t set_pwm_frequency_hz(const_float_t hz, const float dca, const float dcb, const float dcc) {
uint16_t set_pwm_frequency_hz(const float hz, const float dca, const float dcb, const float dcc) {
float count = 0;
if (hz > 0 && (dca || dcb || dcc)) {
count = float(F_CPU) / hz; // 1x prescaler, TOP for 16MHz base freq.
@ -254,7 +254,7 @@ uint16_t set_pwm_frequency_hz(const_float_t hz, const float dca, const float dcb
else { prescaler = 1; SET_CS(5, PRESCALER_1); }
count /= float(prescaler);
const float pwm_top = round(count); // Get the rounded count
const float pwm_top = roundf(count); // Get the rounded count
ICR5 = (uint16_t)pwm_top - 1; // Subtract 1 for TOP
OCR5A = pwm_top * ABS(dca); // Update and scale DCs
@ -280,7 +280,7 @@ uint16_t set_pwm_frequency_hz(const_float_t hz, const float dca, const float dcb
SET_CS(5, PRESCALER_64); // 16MHz / 64 = 250kHz
OCR5A = OCR5B = OCR5C = 0;
}
return round(count);
return roundf(count);
}
#endif

View file

@ -95,7 +95,7 @@
/**
* The Trinamic library includes SoftwareSerial.h, leading to a compile error.
*/
#if ALL(HAS_TRINAMIC_CONFIG, ENDSTOP_INTERRUPTS_FEATURE)
#if ALL(HAS_TMC_SW_SERIAL, ENDSTOP_INTERRUPTS_FEATURE)
#error "TMCStepper includes SoftwareSerial.h which is incompatible with ENDSTOP_INTERRUPTS_FEATURE. Disable ENDSTOP_INTERRUPTS_FEATURE to continue."
#endif

View file

@ -93,15 +93,15 @@ namespace AVRHelpers {
typedef T type;
};
template <typename T>
struct voltype <T, 1u> {
struct voltype <T, 1U> {
typedef uint8_t type;
};
template <typename T>
struct voltype <T, 2u> {
struct voltype <T, 2U> {
typedef uint16_t type;
};
template <typename T>
struct voltype <T, 4u> {
struct voltype <T, 4U> {
typedef uint32_t type;
};
@ -2007,7 +2007,7 @@ inline void _ATmega_resetperipherals() {
#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM05__)
_EEAR._EEAR = 0;
dwrite(_EEDR, (uint8_t)0u);
dwrite(_EEDR, (uint8_t)0U);
#endif
#if defined(__AVR_TRM01__) || defined(__AVR_TRM02__) || defined(__AVR_TRM03__) || defined(__AVR_TRM04__) || defined(__AVR_TRM05__)

View file

@ -28,7 +28,7 @@
// ------------------------
typedef uint16_t hal_timer_t;
#define HAL_TIMER_TYPE_MAX 0xFFFF
#define HAL_TIMER_TYPE_MAX 0xFFFFU
// ------------------------
// Defines

View file

@ -34,7 +34,7 @@
#define FORCE_INLINE __attribute__((always_inline)) inline
typedef uint32_t hal_timer_t;
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFF
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFUL
#define HAL_TIMER_PRESCALER 2
#define HAL_TIMER_RATE ((F_CPU) / (HAL_TIMER_PRESCALER)) // frequency of timers peripherals

View file

@ -64,10 +64,10 @@
#define CRITICAL_SECTION_END() portEXIT_CRITICAL(&hal.spinlock)
#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment
#define PWM_FREQUENCY 1000u // Default PWM frequency when set_pwm_duty() is called without set_pwm_frequency()
#define PWM_RESOLUTION 10u // Default PWM bit resolution
#define CHANNEL_MAX_NUM 15u // max PWM channel # to allocate (7 to only use low speed, 15 to use low & high)
#define MAX_PWM_IOPIN 33u // hardware pwm pins < 34
#define PWM_FREQUENCY 1000U // Default PWM frequency when set_pwm_duty() is called without set_pwm_frequency()
#define PWM_RESOLUTION 10U // Default PWM bit resolution
#define CHANNEL_MAX_NUM 15U // max PWM channel # to allocate (7 to only use low speed, 15 to use low & high)
#define MAX_PWM_IOPIN 33U // hardware pwm pins < 34
#ifndef MAX_EXPANDER_BITS
#define MAX_EXPANDER_BITS 32 // I2S expander bit width (max 32)
#endif

View file

@ -35,7 +35,7 @@ Servo::Servo() {}
int8_t Servo::attach(const int inPin) {
if (inPin > 0) pin = inPin;
channel = get_pwm_channel(pin, 50u, 16u);
channel = get_pwm_channel(pin, 50U, 16U);
return channel; // -1 if no PWM avail.
}

View file

@ -78,8 +78,8 @@ void IRAM_ATTR timer_isr(void *para) {
/**
* Enable and initialize the timer
* @param timer_num timer number to initialize
* @param frequency frequency of the timer
* @param timer_num timer number to initialize
* @param frequency frequency of the timer
*/
void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
const tTimerConfig timer = timer_config[timer_num];

View file

@ -30,7 +30,7 @@
#define FORCE_INLINE __attribute__((always_inline)) inline
typedef uint64_t hal_timer_t;
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFFFFFFFFFULL
#define HAL_TIMER_TYPE_MAX 0xFFFF'FFFF'FFFF'FFFFULL
#ifndef MF_TIMER_STEP
#define MF_TIMER_STEP 0 // Timer Index for Stepper
@ -52,12 +52,12 @@ typedef uint64_t hal_timer_t;
#if ENABLED(I2S_STEPPER_STREAM)
#define STEPPER_TIMER_PRESCALE 1
#define STEPPER_TIMER_RATE 250000 // 250khz, 4µs pulses of i2s word clock
#define STEPPER_TIMER_RATE 250'000 // 250khz, 4µs pulses of i2s word clock
#else
#define STEPPER_TIMER_PRESCALE 40
#define STEPPER_TIMER_RATE ((HAL_TIMER_RATE) / (STEPPER_TIMER_PRESCALE)) // frequency of stepper timer, 2MHz
#endif
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1'000'000) // stepper timer ticks per µs
#define STEP_TIMER_MIN_INTERVAL 8 // minimum time in µs between stepper interrupts

View file

@ -26,4 +26,4 @@
#define TS_TYPICAL_SLOPE 4.5
// TODO: Implement voltage scaling (calibrated Vrefint) and ADC resolution scaling (when applicable)
#define TEMP_SOC_SENSOR(RAW) ((TS_TYPICAL_V - (RAW) / float(OVERSAMPLENR) / float(HAL_ADC_RANGE) * (float(ADC_VREF_MV) / 1000.0f)) / ((TS_TYPICAL_SLOPE) / 1000.0f) + TS_TYPICAL_TEMP)
#define TEMP_SOC_SENSOR(RAW) ((TS_TYPICAL_V - (RAW) / float(OVERSAMPLENR) / float(HAL_ADC_RANGE) * (float(ADC_VREF_MV) * 0.001f)) / ((TS_TYPICAL_SLOPE) * 0.001f) + TS_TYPICAL_TEMP)

View file

@ -37,9 +37,9 @@ public:
MarlinServo();
/**
* @brief attach the pin to the servo, set pin mode, return channel number
* @param pin pin to attach to
* @return channel number, -1 if failed
* @brief attach the pin to the servo, set pin mode, return channel number
* @param pin pin to attach to
* @return channel number, -1 if failed
*/
int8_t attach(const pin_t apin);

View file

@ -27,7 +27,7 @@
//
typedef Timer0 *timer_channel_t;
typedef uint16_t hal_timer_t;
#define HAL_TIMER_TYPE_MAX 0xFFFF
#define HAL_TIMER_TYPE_MAX 0xFFFFU
//
// Timer instances

View file

@ -34,7 +34,7 @@
#define FORCE_INLINE __attribute__((always_inline)) inline
typedef uint32_t hal_timer_t;
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFF
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFUL
#define HAL_TIMER_RATE ((SystemCoreClock) / 4) // frequency of timers peripherals

View file

@ -29,6 +29,6 @@
// LPC1768 boards seem to lose steps when saving to EEPROM during print (issue #20785)
// TODO: Which other boards are incompatible?
#if defined(MCU_LPC1768) && ENABLED(FLASH_EEPROM_EMULATION) && PRINTCOUNTER_SAVE_INTERVAL > 0
#if ALL(MCU_LPC1768, FLASH_EEPROM_EMULATION) && PRINTCOUNTER_SAVE_INTERVAL > 0
#define PRINTCOUNTER_SYNC
#endif

View file

@ -57,7 +57,7 @@
#define _HAL_TIMER_ISR(T) __HAL_TIMER_ISR(T)
typedef uint32_t hal_timer_t;
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFF
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFUL
#define HAL_TIMER_RATE ((F_CPU) / 4) // frequency of timers peripherals

View file

@ -27,7 +27,7 @@
*
* Couldn't just call exact copies because the overhead killed the LCD update speed
* With an intermediate level the softspi was running in the 10-20kHz range which
* resulted in using about about 25% of the CPU's time.
* resulted in using about 25% of the CPU's time.
*/
#ifdef TARGET_LPC1768

View file

@ -28,7 +28,7 @@
*
* Couldn't just call exact copies because the overhead killed the LCD update speed
* With an intermediate level the softspi was running in the 10-20kHz range which
* resulted in using about about 25% of the CPU's time.
* resulted in using about 25% of the CPU's time.
*/
void u8g_SetPinOutput(uint8_t internal_pin_number);

View file

@ -34,7 +34,7 @@
#define FORCE_INLINE __attribute__((always_inline)) inline
typedef uint64_t hal_timer_t;
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFFFFFFFFF
#define HAL_TIMER_TYPE_MAX 0xFFFF'FFFF'FFFF'FFFFULL
#define HAL_TIMER_RATE ((SystemCoreClock) / 4) // frequency of timers peripherals
@ -52,11 +52,11 @@ typedef uint64_t hal_timer_t;
#endif
#define SYSTICK_TIMER_FREQUENCY 1000
#define TEMP_TIMER_RATE 1000000
#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency
#define TEMP_TIMER_RATE 1'000'000
#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency
#define STEPPER_TIMER_RATE HAL_TIMER_RATE // frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE)
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1'000'000) // stepper timer ticks per µs
#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US)
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer

View file

@ -27,7 +27,7 @@
*
* Couldn't just call exact copies because the overhead killed the LCD update speed
* With an intermediate level the softspi was running in the 10-20kHz range which
* resulted in using about about 25% of the CPU's time.
* resulted in using about 25% of the CPU's time.
*/
#ifdef __PLAT_NATIVE_SIM__

View file

@ -28,7 +28,7 @@
*
* Couldn't just call exact copies because the overhead killed the LCD update speed
* With an intermediate level the softspi was running in the 10-20kHz range which
* resulted in using about about 25% of the CPU's time.
* resulted in using about 25% of the CPU's time.
*/
#ifdef __cplusplus

View file

@ -71,13 +71,13 @@ static uint8_t SPI_speed = 0;
static uint8_t swSpiTransfer(uint8_t b, const uint8_t spi_speed, const pin_t sck_pin, const pin_t miso_pin, const pin_t mosi_pin) {
for (uint8_t i = 0; i < 8; i++) {
WRITE_PIN(mosi_pin, !!(b & 0x80));
WRITE_PIN(sck_pin, TERN(U8G_SPI_USE_MODE_3, LOW, HIGH));
DELAY_CYCLES(SPI_SPEED);
WRITE_PIN(sck_pin, HIGH);
WRITE_PIN(mosi_pin, !!(b & 0x80));
DELAY_CYCLES(SPI_SPEED);
b <<= 1;
if (miso_pin >= 0 && READ_PIN(miso_pin)) b |= 1;
WRITE_PIN(sck_pin, LOW);
WRITE_PIN(sck_pin, TERN(U8G_SPI_USE_MODE_3, HIGH, LOW));
DELAY_CYCLES(SPI_SPEED);
}
return b;
@ -85,7 +85,7 @@ static uint8_t swSpiTransfer(uint8_t b, const uint8_t spi_speed, const pin_t sck
static uint8_t swSpiInit(const uint8_t spiRate, const pin_t sck_pin, const pin_t mosi_pin) {
WRITE_PIN(mosi_pin, HIGH);
WRITE_PIN(sck_pin, LOW);
WRITE_PIN(sck_pin, TERN(U8G_SPI_USE_MODE_3, HIGH, LOW));
return spiRate;
}
@ -93,11 +93,11 @@ static void u8g_com_st7920_write_byte_sw_spi(uint8_t rs, uint8_t val) {
static uint8_t rs_last_state = 255;
if (rs != rs_last_state) {
// Transfer Data (FA) or Command (F8)
swSpiTransfer(rs ? 0x0FA : 0x0F8, SPI_speed, SCK_pin_ST7920_HAL, -1, MOSI_pin_ST7920_HAL_HAL);
swSpiTransfer(rs ? 0xFA : 0xF8, SPI_speed, SCK_pin_ST7920_HAL, -1, MOSI_pin_ST7920_HAL_HAL);
rs_last_state = rs;
DELAY_US(40); // Give the controller time to process the data: 20 is bad, 30 is OK, 40 is safe
}
swSpiTransfer(val & 0x0F0, SPI_speed, SCK_pin_ST7920_HAL, -1, MOSI_pin_ST7920_HAL_HAL);
swSpiTransfer(val & 0xF0, SPI_speed, SCK_pin_ST7920_HAL, -1, MOSI_pin_ST7920_HAL_HAL);
swSpiTransfer(val << 4, SPI_speed, SCK_pin_ST7920_HAL, -1, MOSI_pin_ST7920_HAL_HAL);
}
@ -169,5 +169,32 @@ uint8_t u8g_com_ST7920_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void
}
#endif
#if ENABLED(LIGHTWEIGHT_UI)
#define ST7920_CS() { WRITE(LCD_PINS_RS, HIGH); }
#define ST7920_NCS() { WRITE(LCD_PINS_RS, LOW); }
#define ST7920_SET_CMD() { ST7920_SWSPI_SND_8BIT(0xF8); }
#define ST7920_SET_DAT() { ST7920_SWSPI_SND_8BIT(0xFA); }
#define ST7920_WRITE_BYTE(a) { ST7920_SWSPI_SND_8BIT((uint8_t)((a)&0xF0u)); ST7920_SWSPI_SND_8BIT((uint8_t)((a)<<4U)); }
#define ST7920_DAT(V) !!((V) & 0x80)
#define ST7920_SND_BIT(...) do{ \
WRITE(LCD_PINS_D4, LOW); \
WRITE(LCD_PINS_EN, ST7920_DAT(val)); \
WRITE(LCD_PINS_D4, HIGH); \
val <<= 1; }while(0);
void ST7920_SWSPI_SND_8BIT(uint8_t val) {
REPEAT(8, ST7920_SND_BIT);
}
void ST7920_cs() { ST7920_CS(); }
void ST7920_ncs() { ST7920_NCS(); }
void ST7920_set_cmd() { ST7920_SET_CMD(); }
void ST7920_set_dat() { ST7920_SET_DAT(); }
void ST7920_write_byte(const uint8_t val) { ST7920_WRITE_BYTE(val); }
#endif // LIGHTWEIGHT_UI
#endif // IS_U8GLIB_ST7920
#endif // __PLAT_NATIVE_SIM__

View file

@ -127,7 +127,7 @@ uint8_t swSpiTransfer_mode_3(uint8_t b, const uint8_t spi_speed, const pin_t sck
static uint8_t SPI_speed = 0;
static uint8_t swSpiInit(const uint8_t spi_speed, const uint8_t clk_pin, const uint8_t mosi_pin) {
return spi_speed;
return spi_speed;
}
static void u8g_sw_spi_shift_out(uint8_t dataPin, uint8_t clockPin, uint8_t val) {

View file

@ -41,9 +41,9 @@
#define _HAL_TIMER_ISR(T) __HAL_TIMER_ISR(T)
typedef uint64_t hal_timer_t;
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFFFFFFFFF
#define HAL_TIMER_TYPE_MAX 0xFFFF'FFFF'FFFF'FFFFULL
#define HAL_TIMER_RATE (1000000ull) // fixed value as we use a microsecond timesource
#define HAL_TIMER_RATE (1'000'000ULL) // fixed value as we use a microsecond timesource
#ifndef MF_TIMER_STEP
#define MF_TIMER_STEP 0 // Timer Index for Stepper
#endif

View file

@ -83,7 +83,7 @@ bool PersistentStore::access_start() {
NVMCTRL->CTRLA.reg = NVMCTRL_CTRLA_CMDEX_KEY | NVMCTRL_CTRLA_CMD_PBC;
while (NVMCTRL->INTFLAG.bit.READY == 0) { }
PAGE_SIZE = pow(2,3 + NVMCTRL->PARAM.bit.PSZ);
PAGE_SIZE = POW(2, 3 + NVMCTRL->PARAM.bit.PSZ);
ROW_SIZE= PAGE_SIZE * 4;
/*NVMCTRL->SEECFG.reg = NVMCTRL_SEECFG_WMODE_BUFFERED; // Buffered mode and segment reallocation active
if (NVMCTRL->SEESTAT.bit.RLOCK)

View file

@ -33,7 +33,7 @@
// --------------------------------------------------------------------------
typedef uint32_t hal_timer_t;
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFF
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFUL
#define HAL_TIMER_RATE F_CPU // frequency of timers peripherals

View file

@ -32,7 +32,7 @@
*
* Couldn't just call exact copies because the overhead killed the LCD update speed
* With an intermediate level the softspi was running in the 10-20kHz range which
* resulted in using about about 25% of the CPU's time.
* resulted in using about 25% of the CPU's time.
*/
#ifdef __SAMD21__

View file

@ -33,7 +33,7 @@
*
* Couldn't just call exact copies because the overhead killed the LCD update speed
* With an intermediate level the softspi was running in the 10-20kHz range which
* resulted in using about about 25% of the CPU's time.
* resulted in using about 25% of the CPU's time.
*/
void u8g_SetPinOutput(uint8_t internal_pin_number);

View file

@ -32,7 +32,7 @@
// --------------------------------------------------------------------------
typedef uint32_t hal_timer_t;
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFF
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFUL
#define HAL_TIMER_RATE F_CPU // frequency of timers peripherals

View file

@ -39,8 +39,8 @@ static_assert(COUNT(servoDelay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM
static uint32_t servo_interrupt_priority = NVIC_EncodePriority(NVIC_GetPriorityGrouping(), TIM_IRQ_PRIO, TIM_IRQ_SUBPRIO);
// This must be called after the STM32 Servo class has initialized the timer.
// It may only be needed after the first call to attach(), but it is possible
// that is is necessary after every detach() call. To be safe this is currently
// It may only be needed after the first call to attach(), but it's possible
// that this is needed after every detach() call. To be safe this is currently
// called after every call to attach().
static void fixServoTimerInterruptPriority() {
NVIC_SetPriority(getTimerUpIrq(TIMER_SERVO), servo_interrupt_priority);

View file

@ -29,6 +29,6 @@
#endif
// Some STM32F4 boards may lose steps when saving to EEPROM during print (PR #17946)
#if defined(STM32F4xx) && ENABLED(FLASH_EEPROM_EMULATION) && PRINTCOUNTER_SAVE_INTERVAL > 0
#if ALL(STM32F4xx, FLASH_EEPROM_EMULATION) && PRINTCOUNTER_SAVE_INTERVAL > 0
#define PRINTCOUNTER_SYNC
#endif

View file

@ -132,6 +132,9 @@ void TFT_FSMC::init() {
DMAtx.Init.Priority = DMA_PRIORITY_HIGH;
LCD = (LCD_CONTROLLER_TypeDef *)controllerAddress;
DMAtx.Init.PeriphInc = DMA_PINC_DISABLE;
HAL_DMA_Init(&DMAtx);
}
uint32_t TFT_FSMC::getID() {
@ -179,15 +182,19 @@ void TFT_FSMC::abort() {
}
void TFT_FSMC::transmitDMA(uint32_t memoryIncrease, uint16_t *data, uint16_t count) {
DMAtx.Init.PeriphInc = memoryIncrease;
HAL_DMA_Init(&DMAtx);
if (!__IS_DMA_CONFIGURED(&DMAtx) || DMAtx.Init.PeriphInc != memoryIncrease) {
DMAtx.Init.PeriphInc = memoryIncrease;
HAL_DMA_Init(&DMAtx);
}
HAL_DMA_Start(&DMAtx, (uint32_t)data, (uint32_t)&(LCD->RAM), count);
TERN_(TFT_SHARED_IO, while (isBusy()));
}
void TFT_FSMC::transmit(uint32_t memoryIncrease, uint16_t *data, uint16_t count) {
DMAtx.Init.PeriphInc = memoryIncrease;
HAL_DMA_Init(&DMAtx);
if (!__IS_DMA_CONFIGURED(&DMAtx) || DMAtx.Init.PeriphInc != memoryIncrease) {
DMAtx.Init.PeriphInc = memoryIncrease;
HAL_DMA_Init(&DMAtx);
}
dataTransferBegin();
HAL_DMA_Start(&DMAtx, (uint32_t)data, (uint32_t)&(LCD->RAM), count);
HAL_DMA_PollForTransfer(&DMAtx, HAL_DMA_FULL_TRANSFER, HAL_MAX_DELAY);

View file

@ -30,3 +30,6 @@ uint8_t u8g_com_HAL_STM32_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, vo
uint8_t u8g_com_stm32duino_hw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); // See U8glib-HAL
#define U8G_COM_HAL_HW_SPI_FN u8g_com_stm32duino_hw_spi_fn
uint8_t u8g_com_stm32duino_ssd_i2c_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); // u8g_com_stm32duino_ssd_i2c.cpp
#define U8G_COM_SSD_I2C_HAL u8g_com_stm32duino_ssd_i2c_fn

View file

@ -0,0 +1,194 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
/**
* 2-Wire I2C COM Driver
*
* Handles both Hardware and Software I2C so any pins can be used as SDA and SLC.
* Wire library is used for Hardware I2C.
* SlowSoftWire is used for Software I2C.
*
* Wire / SoftWire library selection can be done automatically at runtime.
*
* SDA and SLC pins must be named DOGLCD_SDA_PIN, DOGLCD_SCL_PIN to distinguish
* from other I2C devices (e.g., EEPROM) that use I2C_SDA_PIN, I2C_SLC_PIN.
*/
#ifdef ARDUINO_ARCH_STM32
#include "../../../inc/MarlinConfig.h"
#if HAS_U8GLIB_I2C_OLED
#include <U8glib-HAL.h>
#if ENABLED(U8G_USES_HW_I2C)
#include <Wire.h>
#ifndef MASTER_ADDRESS
#define MASTER_ADDRESS 0x01
#endif
#endif
#if ENABLED(U8G_USES_SW_I2C)
#include <SlowSoftI2CMaster.h>
#include <SlowSoftWire.h>
#endif
/**
* BUFFER_LENGTH is defined in libraries\Wire\utility\WireBase.h
* Default value is 32
* Increase this value to 144 to send U8G_COM_MSG_WRITE_SEQ in single block
*/
#ifndef BUFFER_LENGTH
#define BUFFER_LENGTH 32
#endif
#if BUFFER_LENGTH > 144
#error "BUFFER_LENGTH should not be greater than 144."
#endif
#define I2C_MAX_LENGTH (BUFFER_LENGTH - 1)
uint8_t u8g_com_stm32duino_ssd_i2c_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) {
// Hardware I2C flag
#ifdef COMPILE_TIME_I2C_IS_HARDWARE
constexpr bool isHardI2C = ENABLED(COMPILE_TIME_I2C_IS_HARDWARE);
#else
static bool isHardI2C = false;
static bool i2c_initialized = false; // Flag to only run init/linking code once
if (!i2c_initialized) { // Init runtime linkages
i2c_initialized = true; // Only do this once
I2C_TypeDef *i2cInstance1 = (I2C_TypeDef *)pinmap_peripheral(digitalPinToPinName(DOGLCD_SDA_PIN), PinMap_I2C_SDA);
I2C_TypeDef *i2cInstance2 = (I2C_TypeDef *)pinmap_peripheral(digitalPinToPinName(DOGLCD_SCL_PIN), PinMap_I2C_SCL);
isHardI2C = (i2cInstance1 && (i2cInstance1 == i2cInstance2)); // Found hardware I2C controller
}
#endif
static uint8_t msgInitCount = 0; // Ignore all messages until 2nd U8G_COM_MSG_INIT
if (msgInitCount) {
if (msg == U8G_COM_MSG_INIT) msgInitCount--;
if (msgInitCount) return -1;
}
static uint8_t control;
if (isHardI2C) { // Found hardware I2C controller
#if ENABLED(U8G_USES_HW_I2C)
static TwoWire wire2; // A TwoWire object for use below
switch (msg) {
case U8G_COM_MSG_INIT:
wire2.setClock(400000);
wire2.setSCL(DOGLCD_SCL_PIN);
wire2.setSDA(DOGLCD_SDA_PIN);
wire2.begin(MASTER_ADDRESS, 0); // Start as master
break;
case U8G_COM_MSG_ADDRESS: // Define cmd (arg_val = 0) or data mode (arg_val = 1)
control = arg_val ? 0x40 : 0x00;
break;
case U8G_COM_MSG_WRITE_BYTE:
wire2.beginTransmission(0x3C);
wire2.write(control);
wire2.write(arg_val);
wire2.endTransmission();
break;
case U8G_COM_MSG_WRITE_SEQ: {
uint8_t* dataptr = (uint8_t*)arg_ptr;
#ifdef I2C_MAX_LENGTH
while (arg_val > 0) {
wire2.beginTransmission(0x3C);
wire2.write(control);
if (arg_val <= I2C_MAX_LENGTH) {
wire2.write(dataptr, arg_val);
arg_val = 0;
}
else {
wire2.write(dataptr, I2C_MAX_LENGTH);
arg_val -= I2C_MAX_LENGTH;
dataptr += I2C_MAX_LENGTH;
}
wire2.endTransmission();
}
#else
wire2.beginTransmission(0x3C);
wire2.write(control);
wire2.write(dataptr, arg_val);
wire2.endTransmission();
#endif // I2C_MAX_LENGTH
break;
}
}
#endif // U8G_USES_HW_I2C
}
else { // Software I2C
#if ENABLED(U8G_USES_SW_I2C)
static SlowSoftWire sWire = SlowSoftWire(DOGLCD_SDA_PIN, DOGLCD_SCL_PIN);
switch (msg) {
case U8G_COM_MSG_INIT:
sWire.setClock(400000);
sWire.begin(); // Start as master
break;
case U8G_COM_MSG_ADDRESS: // Define cmd (arg_val = 0) or data mode (arg_val = 1)
control = arg_val ? 0x40 : 0x00;
break;
case U8G_COM_MSG_WRITE_BYTE:
sWire.beginTransmission((uint8_t)0x3C);
sWire.write((uint8_t)control);
sWire.write((uint8_t)arg_val);
sWire.endTransmission();
break;
case U8G_COM_MSG_WRITE_SEQ: {
uint8_t* dataptr = (uint8_t*)arg_ptr;
#ifdef I2C_MAX_LENGTH
while (arg_val > 0) {
sWire.beginTransmission((uint8_t)0x3C);
sWire.write((uint8_t)control);
if (arg_val <= I2C_MAX_LENGTH) {
sWire.write((const uint8_t *)dataptr, (size_t)arg_val);
arg_val = 0;
}
else {
sWire.write((const uint8_t *)dataptr, I2C_MAX_LENGTH);
arg_val -= I2C_MAX_LENGTH;
dataptr += I2C_MAX_LENGTH;
}
sWire.endTransmission();
}
#else
sWire.beginTransmission((uint8_t)0x3C);
sWire.write((uint8_t)control);
sWire.write((const uint8_t *)dataptr, (size_t)arg_val);
sWire.endTransmission();
#endif // I2C_MAX_LENGTH
break;
}
}
#endif // U8G_USES_SW_I2C
}
return 1;
}
#endif // HAS_U8GLIB_I2C_OLED
#endif // ARDUINO_ARCH_STM32

View file

@ -800,7 +800,7 @@ void ADC_StartCalibration(ADC_Module* NS_ADCx);
void ADC_EnableDMA(ADC_Module* NS_ADCx, uint32_t Cmd);
/**================================================================
* Configure ADC interrupt enable enable
* Configure ADC interrupt enable
================================================================*/
void ADC_ConfigInt(ADC_Module* NS_ADCx, uint16_t ADC_IT, uint32_t Cmd);

View file

@ -92,7 +92,7 @@ void install_min_serial() {
HAL_min_serial_out = &TX;
}
#if DISABLED(DYNAMIC_VECTORTABLE) && DISABLED(STM32F0xx) // Cortex M0 can't branch to a symbol that's too far, so we have a specific hack for them
#if NONE(DYNAMIC_VECTORTABLE, STM32F0xx) // Cortex M0 can't branch to a symbol that's too far, so we have a specific hack for them
extern "C" {
__attribute__((naked)) void JumpHandler_ASM() {
__asm__ __volatile__ (

View file

@ -86,7 +86,6 @@ __attribute__((always_inline)) __STATIC_INLINE void __DSB() {
#define FSMC_ADDRESS_SETUP_TIME 15 // AddressSetupTime
#define FSMC_DATA_SETUP_TIME 15 // DataSetupTime
static uint8_t fsmcInit = 0;
void TFT_FSMC::init() {
uint8_t cs = FSMC_CS_PIN, rs = FSMC_RS_PIN;
uint32_t controllerAddress;
@ -99,8 +98,9 @@ void TFT_FSMC::init() {
struct fsmc_nor_psram_reg_map* fsmcPsramRegion;
static bool fsmcInit = false;
if (fsmcInit) return;
fsmcInit = 1;
fsmcInit = true;
switch (cs) {
case FSMC_CS_NE1: controllerAddress = (uint32_t)FSMC_NOR_PSRAM_REGION1; fsmcPsramRegion = FSMC_NOR_PSRAM1_BASE; break;

View file

@ -40,7 +40,7 @@
*/
typedef uint16_t hal_timer_t;
#define HAL_TIMER_TYPE_MAX 0xFFFF
#define HAL_TIMER_TYPE_MAX 0xFFFFU
#define HAL_TIMER_RATE uint32_t(F_CPU) // frequency of timers peripherals

View file

@ -34,7 +34,7 @@
#define FORCE_INLINE __attribute__((always_inline)) inline
typedef uint32_t hal_timer_t;
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFF
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFUL
#define FTM0_TIMER_PRESCALE 8
#define FTM1_TIMER_PRESCALE 4

View file

@ -34,7 +34,7 @@
#define FORCE_INLINE __attribute__((always_inline)) inline
typedef uint32_t hal_timer_t;
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFF
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFUL
#define FTM0_TIMER_PRESCALE 8
#define FTM1_TIMER_PRESCALE 4

View file

@ -98,7 +98,7 @@ void MarlinHAL::clear_reset_source() {
#define WDT_TIMEOUT TERN(WATCHDOG_DURATION_8S, 8, 4) // 4 or 8 second timeout
constexpr uint8_t timeoutval = (WDT_TIMEOUT - 0.5f) / 0.5f;
constexpr uint8_t timeoutval = (WDT_TIMEOUT - 0.5f) * 2.0f;
void MarlinHAL::watchdog_init() {
CCM_CCGR3 |= CCM_CCGR3_WDOG1(3); // enable WDOG1 clocks

View file

@ -34,7 +34,7 @@
#define FORCE_INLINE __attribute__((always_inline)) inline
typedef uint32_t hal_timer_t;
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFE
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFEUL
#define GPT_TIMER_RATE (F_CPU / 4) // 150MHz (Can't use F_BUS_ACTUAL because it's extern volatile)

View file

@ -414,7 +414,7 @@ UnwResult UnwStartArm(UnwState * const state) {
/* S indicates that banked registers (untracked) are used, unless
* this is a load including the PC when the S-bit indicates that
* that CPSR is loaded from SPSR (also untracked, but ignored).
* CPSR is loaded from SPSR (also untracked, but ignored).
*/
if (S && (!L || (regList & (0x01 << 15)) == 0)) {
UnwPrintd1("\nError:S-bit set requiring banked registers\n");
@ -431,7 +431,7 @@ UnwResult UnwStartArm(UnwState * const state) {
/* Check if ascending or descending.
* Registers are loaded/stored in order of address.
* i.e. r0 is at the lowest address, r15 at the highest.
* i.e., r0 is at the lowest address, r15 at the highest.
*/
r = U ? 0 : 15;
do {

View file

@ -28,6 +28,7 @@
#include "macros.h"
#define BOARD_ERROR -2
#define BOARD_UNKNOWN -1
//
@ -175,16 +176,17 @@
#define BOARD_GT2560_V41B 1322 // Geeetech GT2560 V4.1B for A10(M/T/D)
#define BOARD_EINSTART_S 1323 // Einstart retrofit
#define BOARD_WANHAO_ONEPLUS 1324 // Wanhao 0ne+ i3 Mini
#define BOARD_OVERLORD 1325 // Overlord/Overlord Pro
#define BOARD_HJC2560C_REV1 1326 // ADIMLab Gantry v1
#define BOARD_HJC2560C_REV2 1327 // ADIMLab Gantry v2
#define BOARD_LEAPFROG_XEED2015 1328 // Leapfrog Xeed 2015
#define BOARD_PICA_REVB 1329 // PICA Shield (original version)
#define BOARD_PICA 1330 // PICA Shield (rev C or later)
#define BOARD_INTAMSYS40 1331 // Intamsys 4.0 (Funmat HT)
#define BOARD_MALYAN_M180 1332 // Malyan M180 Mainboard Version 2 (no display function, direct G-code only)
#define BOARD_PROTONEER_CNC_SHIELD_V3 1333 // Mega controller & Protoneer CNC Shield V3.00
#define BOARD_WEEDO_62A 1334 // WEEDO 62A board (TINA2, Monoprice Cadet, etc.)
#define BOARD_WANHAO_D9 1325 // Wanhao D9 MK2
#define BOARD_OVERLORD 1326 // Overlord/Overlord Pro
#define BOARD_HJC2560C_REV1 1327 // ADIMLab Gantry v1
#define BOARD_HJC2560C_REV2 1328 // ADIMLab Gantry v2
#define BOARD_LEAPFROG_XEED2015 1329 // Leapfrog Xeed 2015
#define BOARD_PICA_REVB 1330 // PICA Shield (original version)
#define BOARD_PICA 1331 // PICA Shield (rev C or later)
#define BOARD_INTAMSYS40 1332 // Intamsys 4.0 (Funmat HT)
#define BOARD_MALYAN_M180 1333 // Malyan M180 Mainboard Version 2 (no display function, direct G-code only)
#define BOARD_PROTONEER_CNC_SHIELD_V3 1334 // Mega controller & Protoneer CNC Shield V3.00
#define BOARD_WEEDO_62A 1335 // WEEDO 62A board (TINA2, Monoprice Cadet, etc.)
//
// ATmega1281, ATmega2561
@ -511,10 +513,11 @@
#define BOARD_BTT_OCTOPUS_PRO_V1_1 6008 // BigTreeTech Octopus Pro v1.1 (STM32H723ZE)
#define BOARD_BTT_MANTA_M8P_V2_0 6009 // BigTreeTech Manta M8P V2.0 (STM32H723ZE)
#define BOARD_BTT_KRAKEN_V1_0 6010 // BigTreeTech Kraken v1.0 (STM32H723ZG)
#define BOARD_TEENSY41 6011 // Teensy 4.1
#define BOARD_T41U5XBB 6012 // T41U5XBB Teensy 4.1 breakout board
#define BOARD_FLY_D8_PRO 6013 // FLY_D8_PRO (STM32H723VG)
#define BOARD_FLY_SUPER8_PRO 6014 // FLY SUPER8 PRO (STM32H723ZG)
#define BOARD_TEENSY40 6011 // Teensy 4.0
#define BOARD_TEENSY41 6012 // Teensy 4.1
#define BOARD_T41U5XBB 6013 // T41U5XBB Teensy 4.1 breakout board
#define BOARD_FLY_D8_PRO 6014 // FLY_D8_PRO (STM32H723VG)
#define BOARD_FLY_SUPER8_PRO 6015 // FLY SUPER8 PRO (STM32H723ZG)
//
// Espressif ESP32 WiFi

View file

@ -358,6 +358,21 @@
#define STR_Z2 STR_C "2"
#define STR_Z3 STR_C "3"
#define STR_Z4 STR_C "4"
#if CORE_IS_XY || CORE_IS_XZ
#define STEPPER_A_NAME 'A'
#else
#define STEPPER_A_NAME 'X'
#endif
#if CORE_IS_XY || CORE_IS_YZ
#define STEPPER_B_NAME 'B'
#else
#define STEPPER_B_NAME 'Y'
#endif
#if CORE_IS_XZ || CORE_IS_YZ
#define STEPPER_C_NAME 'C'
#else
#define STEPPER_C_NAME 'Z'
#endif
//
// Endstop Names used by Endstops::report_states

View file

@ -58,6 +58,7 @@
// Macros to make a string from a macro
#define STRINGIFY_(M) #M
#define STRINGIFY(M) STRINGIFY_(M)
#define CHARIFY(M) STRINGIFY(M)[0]
#define A(CODE) " " CODE "\n\t"
#define L(CODE) CODE ":\n\t"

View file

@ -99,7 +99,7 @@ void SERIAL_WARN_START() { SERIAL_ECHO(F("Warning:")); }
void SERIAL_ECHO_SP(uint8_t count) { count *= (PROPORTIONAL_FONT_RATIO); while (count--) SERIAL_CHAR(' '); }
void serial_offset(const_float_t v, const uint8_t sp/*=0*/) {
void serial_offset(const float v, const uint8_t sp/*=0*/) {
if (v == 0 && sp == 1)
SERIAL_CHAR(' ');
else if (v > 0 || (v == 0 && sp == 2))
@ -121,7 +121,7 @@ void print_bin(uint16_t val) {
}
}
void _print_xyz(NUM_AXIS_ARGS_(const_float_t) FSTR_P const prefix) {
void _print_xyz(NUM_AXIS_ARGS_(const float) FSTR_P const prefix) {
if (prefix) SERIAL_ECHO(prefix);
#if NUM_AXES
SERIAL_ECHOPGM_P(NUM_AXIS_PAIRED_LIST(
@ -132,12 +132,12 @@ void _print_xyz(NUM_AXIS_ARGS_(const_float_t) FSTR_P const prefix) {
#endif
}
void print_xyz(NUM_AXIS_ARGS_(const_float_t) FSTR_P const prefix/*=nullptr*/, FSTR_P const suffix/*=nullptr*/) {
void print_xyz(NUM_AXIS_ARGS_(const float) FSTR_P const prefix/*=nullptr*/, FSTR_P const suffix/*=nullptr*/) {
_print_xyz(NUM_AXIS_LIST_(x, y, z, i, j, k, u, v, w) prefix);
if (suffix) SERIAL_ECHO(suffix); else SERIAL_EOL();
}
void print_xyze(LOGICAL_AXIS_ARGS_(const_float_t) FSTR_P const prefix/*=nullptr*/, FSTR_P const suffix/*=nullptr*/) {
void print_xyze(LOGICAL_AXIS_ARGS_(const float) FSTR_P const prefix/*=nullptr*/, FSTR_P const suffix/*=nullptr*/) {
_print_xyz(NUM_AXIS_LIST_(x, y, z, i, j, k, u, v, w) prefix);
#if HAS_EXTRUDERS
SERIAL_ECHOPGM_P(SP_E_STR, e);

View file

@ -236,16 +236,16 @@ void SERIAL_ECHO_SP(uint8_t count);
inline FSTR_P const ON_OFF(const bool onoff) { return onoff ? F("ON") : F("OFF"); }
inline FSTR_P const TRUE_FALSE(const bool tf) { return tf ? F("true") : F("false"); }
void serial_offset(const_float_t v, const uint8_t sp=0); // For v==0 draw space (sp==1) or plus (sp==2)
void serial_offset(const float v, const uint8_t sp=0); // For v==0 draw space (sp==1) or plus (sp==2)
void print_bin(const uint16_t val);
void print_xyz(NUM_AXIS_ARGS_(const_float_t) FSTR_P const prefix=nullptr, FSTR_P const suffix=nullptr);
void print_xyz(NUM_AXIS_ARGS_(const float) FSTR_P const prefix=nullptr, FSTR_P const suffix=nullptr);
inline void print_xyz(const xyz_pos_t &xyz, FSTR_P const prefix=nullptr, FSTR_P const suffix=nullptr) {
print_xyz(NUM_AXIS_ELEM_(xyz) prefix, suffix);
}
void print_xyze(LOGICAL_AXIS_ARGS_(const_float_t) FSTR_P const prefix=nullptr, FSTR_P const suffix=nullptr);
void print_xyze(LOGICAL_AXIS_ARGS_(const float) FSTR_P const prefix=nullptr, FSTR_P const suffix=nullptr);
inline void print_xyze(const xyze_pos_t &xyze, FSTR_P const prefix=nullptr, FSTR_P const suffix=nullptr) {
print_xyze(LOGICAL_AXIS_ELEM_LC_(xyze) prefix, suffix);
}

View file

@ -228,7 +228,7 @@ struct SerialBase {
// Handle negative numbers
if (number < 0.0) {
write('-');
number = -number;
number *= -1;
}
// Round correctly so that print(1.999, 2) prints as "2.00"

View file

@ -167,6 +167,21 @@ template <class L, class R> struct IF<true, L, R> { typedef L type; };
#define GANG_ITEM_E(N)
#endif
// Emitters for code that only cares about XYZE and not IJKUVW
#define CARTES_COUNT TERN(HAS_EXTRUDERS, INCREMENT(XYZ_COUNT), XYZ_COUNT)
#define CARTES_LIST(x,y,z,e) XYZ_LIST(x,y,z) LIST_ITEM_E(e)
#define CARTES_PAIRED_LIST(V...) LIST_N(DOUBLE(CARTES_COUNT), V)
#define CARTES_ARRAY(x,y,z,e) { CARTES_LIST(x,y,z,e) }
#define CARTES_CODE(x,y,z,e) XYZ_CODE(x,y,z) CODE_ITEM_E(e)
#define CARTES_GANG(x,y,z,e) XYZ_GANG(x,y,z) GANG_ITEM_E(e)
#define CARTES_AXIS_NAMES CARTES_LIST(X,Y,Z,E)
#define CARTES_MAP(F) MAP(F, CARTES_AXIS_NAMES)
#if CARTES_COUNT
#define CARTES_COMMA ,
#else
#define CARTES_COMMA
#endif
#define AXIS_COLLISION(L) (AXIS4_NAME == L || AXIS5_NAME == L || AXIS6_NAME == L || AXIS7_NAME == L || AXIS8_NAME == L || AXIS9_NAME == L)
// Helpers
@ -363,17 +378,6 @@ typedef uint16_t raw_adc_t;
typedef int16_t celsius_t;
typedef float celsius_float_t;
//
// On AVR pointers are only 2 bytes so use 'const float &' for 'const float'
//
#ifdef __AVR__
typedef const float & const_float_t;
#else
typedef const float const_float_t;
#endif
typedef const_float_t const_feedRate_t;
typedef const_float_t const_celsius_float_t;
// Type large enough to count leveling grid points
typedef IF<TERN0(ABL_USES_GRID, (GRID_MAX_POINTS > 255)), uint16_t, uint8_t>::type grid_count_t;
@ -382,7 +386,7 @@ typedef IF<TERN0(ABL_USES_GRID, (GRID_MAX_POINTS > 255)), uint16_t, uint8_t>::ty
#define MMS_TO_MMM(MM_S) (static_cast<float>(MM_S) * 60.0f)
// Packaged character for C macro and other usage
typedef struct SerialChar { char c; SerialChar(char n) : c(n) { } } serial_char_t;
typedef struct SerialChar { char c; SerialChar(const char n) : c(n) { } } serial_char_t;
#define C(c) serial_char_t(c)
// Packaged types: float with precision and/or width; a repeated space/character
@ -543,13 +547,18 @@ struct XYval {
FI constexpr T large() const { return _MAX(x, y); }
// Explicit copy and copies with conversion
FI constexpr XYval<T> copy() const { return *this; }
FI constexpr XYval<T> ABS() const { return { T(_ABS(x)), T(_ABS(y)) }; }
FI constexpr XYval<int16_t> asInt() const { return { int16_t(x), int16_t(y) }; }
FI constexpr XYval<int32_t> asLong() const { return { int32_t(x), int32_t(y) }; }
FI constexpr XYval<int32_t> ROUNDL() const { return { int32_t(LROUND(x)), int32_t(LROUND(y)) }; }
FI constexpr XYval<float> asFloat() const { return { static_cast<float>(x), static_cast<float>(y) }; }
FI constexpr XYval<float> reciprocal() const { return { _RECIP(x), _RECIP(y) }; }
FI constexpr XYval<T> copy() const { return *this; }
FI constexpr XYval<T> ABS() const { return { T(_ABS(x)), T(_ABS(y)) }; }
FI constexpr XYval<int32_t> ROUNDL() const { return { int32_t(LROUND(x)), int32_t(LROUND(y)) }; }
FI constexpr XYval<float> reciprocal() const { return { _RECIP(x), _RECIP(y) }; }
// Conversion to other types
FI constexpr XYval<int16_t> asInt16() const { return { int16_t(x), int16_t(y) }; }
FI constexpr XYval<int32_t> asInt32() const { return { int32_t(x), int32_t(y) }; }
FI constexpr XYval<uint32_t> asUInt32() const { return { uint32_t(x), uint32_t(y) }; }
FI constexpr XYval<int64_t> asInt64() const { return { int64_t(x), int64_t(y) }; }
FI constexpr XYval<uint64_t> asUInt64() const { return { uint64_t(x), uint64_t(y) }; }
FI constexpr XYval<float> asFloat() const { return { static_cast<float>(x), static_cast<float>(y) }; }
// Marlin workspace shifting is done with G92 and M206
FI XYval<float> asLogical() const { XYval<float> o = asFloat(); toLogical(o); return o; }
@ -621,6 +630,11 @@ struct XYval {
FI bool operator!=(const XYval<T> &rs) const { return !operator==(rs); }
FI bool operator!=(const XYZval<T> &rs) const { return !operator==(rs); }
FI bool operator!=(const XYZEval<T> &rs) const { return !operator==(rs); }
// Exact comparison to a single value
FI bool operator==(const T &p) const { return x == p && y == p; }
FI bool operator!=(const T &p) const { return !operator==(p); }
};
//
@ -697,12 +711,17 @@ struct XYZval {
// Explicit copy and copies with conversion
FI constexpr XYZval<T> copy() const { XYZval<T> o = *this; return o; }
FI constexpr XYZval<T> ABS() const { return NUM_AXIS_ARRAY(T(_ABS(x)), T(_ABS(y)), T(_ABS(z)), T(_ABS(i)), T(_ABS(j)), T(_ABS(k)), T(_ABS(u)), T(_ABS(v)), T(_ABS(w))); }
FI constexpr XYZval<int16_t> asInt() const { return NUM_AXIS_ARRAY(int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k), int16_t(u), int16_t(v), int16_t(w)); }
FI constexpr XYZval<int32_t> asLong() const { return NUM_AXIS_ARRAY(int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k), int32_t(u), int32_t(v), int32_t(w)); }
FI constexpr XYZval<int32_t> ROUNDL() const { return NUM_AXIS_ARRAY(int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(i)), int32_t(LROUND(j)), int32_t(LROUND(k)), int32_t(LROUND(u)), int32_t(LROUND(v)), int32_t(LROUND(w))); }
FI constexpr XYZval<float> asFloat() const { return NUM_AXIS_ARRAY(static_cast<float>(x), static_cast<float>(y), static_cast<float>(z), static_cast<float>(i), static_cast<float>(j), static_cast<float>(k), static_cast<float>(u), static_cast<float>(v), static_cast<float>(w)); }
FI constexpr XYZval<float> reciprocal() const { return NUM_AXIS_ARRAY(_RECIP(x), _RECIP(y), _RECIP(z), _RECIP(i), _RECIP(j), _RECIP(k), _RECIP(u), _RECIP(v), _RECIP(w)); }
// Conversion to other types
FI constexpr XYZval<int16_t> asInt16() const { return NUM_AXIS_ARRAY(int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k), int16_t(u), int16_t(v), int16_t(w)); }
FI constexpr XYZval<int32_t> asInt32() const { return NUM_AXIS_ARRAY(int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k), int32_t(u), int32_t(v), int32_t(w)); }
FI constexpr XYZval<uint32_t> asUInt32() const { return NUM_AXIS_ARRAY(uint32_t(x), uint32_t(y), uint32_t(z), uint32_t(i), uint32_t(j), uint32_t(k), uint32_t(u), uint32_t(v), uint32_t(w)); }
FI constexpr XYZval<int64_t> asInt64() const { return NUM_AXIS_ARRAY(int64_t(x), int64_t(y), int64_t(z), int64_t(i), int64_t(j), int64_t(k), int64_t(u), int64_t(v), int64_t(w)); }
FI constexpr XYZval<uint64_t> asUInt64() const { return NUM_AXIS_ARRAY(uint64_t(x), uint64_t(y), uint64_t(z), uint64_t(i), uint64_t(j), uint64_t(k), uint64_t(u), uint64_t(v), uint64_t(w)); }
FI constexpr XYZval<float> asFloat() const { return NUM_AXIS_ARRAY(static_cast<float>(x), static_cast<float>(y), static_cast<float>(z), static_cast<float>(i), static_cast<float>(j), static_cast<float>(k), static_cast<float>(u), static_cast<float>(v), static_cast<float>(w)); }
// Marlin workspace shifting is done with G92 and M206
FI XYZval<float> asLogical() const { XYZval<float> o = asFloat(); toLogical(o); return o; }
FI XYZval<float> asNative() const { XYZval<float> o = asFloat(); toNative(o); return o; }
@ -768,8 +787,13 @@ struct XYZval {
FI XYZval<T>& operator<<=(const int &p) { NUM_AXIS_CODE(_LSE(x), _LSE(y), _LSE(z), _LSE(i), _LSE(j), _LSE(k), _LSE(u), _LSE(v), _LSE(w)); return *this; }
// Exact comparisons. For floats a "NEAR" operation may be better.
FI bool operator==(const XYZEval<T> &rs) const { return true NUM_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k, && u == rs.u, && v == rs.v, && w == rs.w); }
FI bool operator==(const XYZEval<T> &rs) const { return ENABLED(HAS_X_AXIS) NUM_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k, && u == rs.u, && v == rs.v, && w == rs.w); }
FI bool operator!=(const XYZEval<T> &rs) const { return !operator==(rs); }
// Exact comparison to a single value
FI bool operator==(const T &p) const { return ENABLED(HAS_X_AXIS) NUM_AXIS_GANG(&& x == p, && y == p, && z == p, && i == p, && j == p, && k == p, && u == p, && v == p, && w == p); }
FI bool operator!=(const T &p) const { return !operator==(p); }
};
//
@ -845,13 +869,18 @@ struct XYZEval {
FI constexpr T large() const { return _MAX(LOGICAL_AXIS_LIST(e, x, y, z, i, j, k, u, v, w)); }
// Explicit copy and copies with conversion
FI constexpr XYZEval<T> copy() const { XYZEval<T> v = *this; return v; }
FI constexpr XYZEval<T> ABS() const { return LOGICAL_AXIS_ARRAY(T(_ABS(e)), T(_ABS(x)), T(_ABS(y)), T(_ABS(z)), T(_ABS(i)), T(_ABS(j)), T(_ABS(k)), T(_ABS(u)), T(_ABS(v)), T(_ABS(w))); }
FI constexpr XYZEval<int16_t> asInt() const { return LOGICAL_AXIS_ARRAY(int16_t(e), int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k), int16_t(u), int16_t(v), int16_t(w)); }
FI constexpr XYZEval<int32_t> asLong() const { return LOGICAL_AXIS_ARRAY(int32_t(e), int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k), int32_t(u), int32_t(v), int32_t(w)); }
FI constexpr XYZEval<int32_t> ROUNDL() const { return LOGICAL_AXIS_ARRAY(int32_t(LROUND(e)), int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(i)), int32_t(LROUND(j)), int32_t(LROUND(k)), int32_t(LROUND(u)), int32_t(LROUND(v)), int32_t(LROUND(w))); }
FI constexpr XYZEval<float> asFloat() const { return LOGICAL_AXIS_ARRAY(static_cast<float>(e), static_cast<float>(x), static_cast<float>(y), static_cast<float>(z), static_cast<float>(i), static_cast<float>(j), static_cast<float>(k), static_cast<float>(u), static_cast<float>(v), static_cast<float>(w)); }
FI constexpr XYZEval<float> reciprocal() const { return LOGICAL_AXIS_ARRAY(_RECIP(e), _RECIP(x), _RECIP(y), _RECIP(z), _RECIP(i), _RECIP(j), _RECIP(k), _RECIP(u), _RECIP(v), _RECIP(w)); }
FI constexpr XYZEval<T> copy() const { XYZEval<T> v = *this; return v; }
FI constexpr XYZEval<T> ABS() const { return LOGICAL_AXIS_ARRAY(T(_ABS(e)), T(_ABS(x)), T(_ABS(y)), T(_ABS(z)), T(_ABS(i)), T(_ABS(j)), T(_ABS(k)), T(_ABS(u)), T(_ABS(v)), T(_ABS(w))); }
FI constexpr XYZEval<int32_t> ROUNDL() const { return LOGICAL_AXIS_ARRAY(int32_t(LROUND(e)), int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(i)), int32_t(LROUND(j)), int32_t(LROUND(k)), int32_t(LROUND(u)), int32_t(LROUND(v)), int32_t(LROUND(w))); }
FI constexpr XYZEval<float> reciprocal() const { return LOGICAL_AXIS_ARRAY(_RECIP(e), _RECIP(x), _RECIP(y), _RECIP(z), _RECIP(i), _RECIP(j), _RECIP(k), _RECIP(u), _RECIP(v), _RECIP(w)); }
// Conversion to other types
FI constexpr XYZEval<int16_t> asInt16() const { return LOGICAL_AXIS_ARRAY(int16_t(e), int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k), int16_t(u), int16_t(v), int16_t(w)); }
FI constexpr XYZEval<int32_t> asInt32() const { return LOGICAL_AXIS_ARRAY(int32_t(e), int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k), int32_t(u), int32_t(v), int32_t(w)); }
FI constexpr XYZEval<uint32_t> asUInt32() const { return LOGICAL_AXIS_ARRAY(uint32_t(e), uint32_t(x), uint32_t(y), uint32_t(z), uint32_t(i), uint32_t(j), uint32_t(k), uint32_t(u), uint32_t(v), uint32_t(w)); }
FI constexpr XYZEval<int64_t> asInt64() const { return LOGICAL_AXIS_ARRAY(int64_t(e), int64_t(x), int64_t(y), int64_t(z), int64_t(i), int64_t(j), int64_t(k), int64_t(u), int64_t(v), int64_t(w)); }
FI constexpr XYZEval<uint64_t> asUInt64() const { return LOGICAL_AXIS_ARRAY(uint64_t(e), uint64_t(x), uint64_t(y), uint64_t(z), uint64_t(i), uint64_t(j), uint64_t(k), uint64_t(u), uint64_t(v), uint64_t(w)); }
FI constexpr XYZEval<float> asFloat() const { return LOGICAL_AXIS_ARRAY(static_cast<float>(e), static_cast<float>(x), static_cast<float>(y), static_cast<float>(z), static_cast<float>(i), static_cast<float>(j), static_cast<float>(k), static_cast<float>(u), static_cast<float>(v), static_cast<float>(w)); }
// Marlin workspace shifting is done with G92 and M206
FI XYZEval<float> asLogical() const { XYZEval<float> o = asFloat(); toLogical(o); return o; }
@ -885,7 +914,10 @@ struct XYZEval {
FI constexpr XYZEval<T> operator- (const XYZEval<T> &rs) const { return LOGICAL_AXIS_ARRAY(T(e - rs.e), T(x - rs.x), T(y - rs.y), T(z - rs.z), T(i - rs.i), T(j - rs.j), T(k - rs.k), T(u - rs.u), T(v - rs.v), T(w - rs.w)); }
FI constexpr XYZEval<T> operator* (const XYZEval<T> &rs) const { return LOGICAL_AXIS_ARRAY(T(e * rs.e), T(x * rs.x), T(y * rs.y), T(z * rs.z), T(i * rs.i), T(j * rs.j), T(k * rs.k), T(u * rs.u), T(v * rs.v), T(w * rs.w)); }
FI constexpr XYZEval<T> operator/ (const XYZEval<T> &rs) const { return LOGICAL_AXIS_ARRAY(T(e / rs.e), T(x / rs.x), T(y / rs.y), T(z / rs.z), T(i / rs.i), T(j / rs.j), T(k / rs.k), T(u / rs.u), T(v / rs.v), T(w / rs.w)); }
FI constexpr XYZEval<T> operator+ (const uint32_t &p) const { return LOGICAL_AXIS_ARRAY(T(e + p), T(x + p), T(y + p), T(z + p), T(i + p), T(j + p), T(k + p), T(u + p), T(v + p), T(w + p)); }
FI constexpr XYZEval<T> operator* (const float &p) const { return LOGICAL_AXIS_ARRAY(T(e * p), T(x * p), T(y * p), T(z * p), T(i * p), T(j * p), T(k * p), T(u * p), T(v * p), T(w * p)); }
FI constexpr XYZEval<T> operator* (const uint32_t &p) const { return LOGICAL_AXIS_ARRAY(T(e * p), T(x * p), T(y * p), T(z * p), T(i * p), T(j * p), T(k * p), T(u * p), T(v * p), T(w * p)); }
FI constexpr XYZEval<T> operator& (const int64_t &p) const { return LOGICAL_AXIS_ARRAY(T(e & p), T(x & p), T(y & p), T(z & p), T(i & p), T(j & p), T(k & p), T(u & p), T(v & p), T(w & p)); }
FI constexpr XYZEval<T> operator* (const int &p) const { return LOGICAL_AXIS_ARRAY(e * p, x * p, y * p, z * p, i * p, j * p, k * p, u * p, v * p, w * p); }
FI constexpr XYZEval<T> operator/ (const float &p) const { return LOGICAL_AXIS_ARRAY(T(e / p), T(x / p), T(y / p), T(z / p), T(i / p), T(j / p), T(k / p), T(u / p), T(v / p), T(w / p)); }
FI constexpr XYZEval<T> operator/ (const int &p) const { return LOGICAL_AXIS_ARRAY(e / p, x / p, y / p, z / p, i / p, j / p, k / p, u / p, v / p, w / p); }
@ -916,14 +948,22 @@ struct XYZEval {
FI XYZEval<T>& operator<<=(const int &p) { LOGICAL_AXIS_CODE(_LSE(e), _LSE(x), _LSE(y), _LSE(z), _LSE(i), _LSE(j), _LSE(k), _LSE(u), _LSE(v), _LSE(w)); return *this; }
// Exact comparisons. For floats a "NEAR" operation may be better.
FI bool operator==(const XYZval<T> &rs) const { return true NUM_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k, && u == rs.u, && v == rs.v, && w == rs.w); }
FI bool operator==(const XYZEval<T> &rs) const { return true LOGICAL_AXIS_GANG(&& e == rs.e, && x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k, && u == rs.u, && v == rs.v, && w == rs.w); }
FI bool operator==(const XYZval<T> &rs) const { return ENABLED(HAS_X_AXIS) NUM_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k, && u == rs.u, && v == rs.v, && w == rs.w); }
FI bool operator==(const XYZEval<T> &rs) const { return ANY(HAS_X_AXIS, HAS_EXTRUDERS) LOGICAL_AXIS_GANG(&& e == rs.e, && x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k, && u == rs.u, && v == rs.v, && w == rs.w); }
FI bool operator!=(const XYZval<T> &rs) const { return !operator==(rs); }
FI bool operator!=(const XYZEval<T> &rs) const { return !operator==(rs); }
// Exact comparison to a single value
FI bool operator==(const T &p) const { return ENABLED(HAS_X_AXIS) LOGICAL_AXIS_GANG(&& e == p, && x == p, && y == p, && z == p, && i == p, && j == p, && k == p, && u == p, && v == p, && w == p); }
FI bool operator!=(const T &p) const { return !operator==(p); }
};
#include <string.h> // for memset
//
// Axis indexed arrays of type T (x[SIZE], y[SIZE], etc.)
//
template<typename T, int SIZE>
struct XYZarray {
typedef T el[SIZE];
@ -1023,6 +1063,9 @@ struct XYZEarray {
FI XYZEval<T> operator[](const int n) const { return XYZval<T>(LOGICAL_AXIS_ARRAY(e[n], x[n], y[n], z[n], i[n], j[n], k[n], u[n], v[n], w[n])); }
};
//
// Axes mapped to bits in a mask of minimum size, bits_t(NUM_AXIS_HEADS)
//
class AxisBits {
public:
typedef bits_t(NUM_AXIS_HEADS) el;

View file

@ -54,12 +54,12 @@ void Babystep::step_axis(const AxisEnum axis) {
}
}
void Babystep::add_mm(const AxisEnum axis, const_float_t mm) {
void Babystep::add_mm(const AxisEnum axis, const float mm) {
add_steps(axis, mm * planner.settings.axis_steps_per_mm[axis]);
}
#if ENABLED(BD_SENSOR)
void Babystep::set_mm(const AxisEnum axis, const_float_t mm) {
void Babystep::set_mm(const AxisEnum axis, const float mm) {
//if (DISABLED(BABYSTEP_WITHOUT_HOMING) && axis_should_home(axis)) return;
const int16_t distance = mm * planner.settings.axis_steps_per_mm[axis];
accum = distance; // Count up babysteps for the UI

View file

@ -61,7 +61,7 @@ public:
static bool can_babystep(const AxisEnum axis);
static void add_steps(const AxisEnum axis, const int16_t distance);
static void add_mm(const AxisEnum axis, const_float_t mm);
static void add_mm(const AxisEnum axis, const float mm);
#if ENABLED(EP_BABYSTEPPING)
// Step Z for M293 / M294
@ -79,7 +79,7 @@ public:
#endif // EP_BABYSTEPPING
#if ENABLED(BD_SENSOR)
static void set_mm(const AxisEnum axis, const_float_t mm);
static void set_mm(const AxisEnum axis, const float mm);
#endif
static bool has_steps() {

View file

@ -81,10 +81,10 @@ public:
static void set_correction(const float v) { set_correction_uint8(_MAX(0, _MIN(1.0, v)) * all_on + 0.5f); }
static float get_correction() { return float(get_correction_uint8()) / all_on; }
static void set_distance_mm(const AxisEnum axis, const float v);
static float get_distance_mm(const AxisEnum axis) {return distance_mm[axis];}
static float get_distance_mm(const AxisEnum axis) { return distance_mm[axis]; }
#ifdef BACKLASH_SMOOTHING_MM
static void set_smoothing_mm(const float v);
static float get_smoothing_mm() {return smoothing_mm;}
static float get_smoothing_mm() { return smoothing_mm; }
#endif
#endif

View file

@ -229,7 +229,7 @@ void LevelingBilinear::print_leveling_grid(const bed_mesh_t* _z_values/*=nullptr
) * 0.5f;
}
float LevelingBilinear::virt_2cmr(const uint8_t x, const uint8_t y, const_float_t tx, const_float_t ty) {
float LevelingBilinear::virt_2cmr(const uint8_t x, const uint8_t y, const float tx, const float ty) {
float row[4], column[4];
for (uint8_t i = 0; i < 4; ++i) {
for (uint8_t j = 0; j < 4; ++j) {
@ -369,7 +369,7 @@ float LevelingBilinear::get_z_correction(const xy_pos_t &raw) {
* Prepare a bilinear-leveled linear move on Cartesian,
* splitting the move where it crosses grid borders.
*/
void LevelingBilinear::line_to_destination(const_feedRate_t scaled_fr_mm_s, uint16_t x_splits, uint16_t y_splits) {
void LevelingBilinear::line_to_destination(const feedRate_t scaled_fr_mm_s, uint16_t x_splits, uint16_t y_splits) {
// Get current and destination cells for this line
xy_int_t c1 { CELL_INDEX(x, current_position.x), CELL_INDEX(y, current_position.y) },
c2 { CELL_INDEX(x, destination.x), CELL_INDEX(y, destination.y) };

View file

@ -45,7 +45,7 @@ private:
static float virt_coord(const uint8_t x, const uint8_t y);
static float virt_cmr(const float p[4], const uint8_t i, const float t);
static float virt_2cmr(const uint8_t x, const uint8_t y, const_float_t tx, const_float_t ty);
static float virt_2cmr(const uint8_t x, const uint8_t y, const float tx, const float ty);
static void subdivide_mesh();
#endif
@ -63,7 +63,7 @@ public:
static constexpr float get_z_offset() { return 0.0f; }
#if IS_CARTESIAN && DISABLED(SEGMENT_LEVELED_MOVES)
static void line_to_destination(const_feedRate_t scaled_fr_mm_s, uint16_t x_splits=0xFFFF, uint16_t y_splits=0xFFFF);
static void line_to_destination(const feedRate_t scaled_fr_mm_s, uint16_t x_splits=0xFFFF, uint16_t y_splits=0xFFFF);
#endif
};

View file

@ -101,7 +101,7 @@ bool BDS_Leveling::check(const uint16_t data, const bool raw_data/*=false*/, con
}
float BDS_Leveling::interpret(const uint16_t data) {
return (data & 0x3FF) / 100.0f;
return (data & 0x3FF) * 0.01f;
}
float BDS_Leveling::read() {

View file

@ -91,7 +91,7 @@ TemporaryBedLevelingState::TemporaryBedLevelingState(const bool enable) : saved(
#if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
void set_z_fade_height(const_float_t zfh, const bool do_report/*=true*/) {
void set_z_fade_height(const float zfh, const bool do_report/*=true*/) {
if (planner.z_fade_height == zfh) return;

View file

@ -38,7 +38,7 @@ void set_bed_leveling_enabled(const bool enable=true);
void reset_bed_level();
#if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
void set_z_fade_height(const_float_t zfh, const bool do_report=true);
void set_z_fade_height(const float zfh, const bool do_report=true);
#endif
#if ANY(MESH_BED_LEVELING, PROBE_MANUALLY)

View file

@ -61,7 +61,7 @@
* Prepare a mesh-leveled linear move in a Cartesian setup,
* splitting the move where it crosses mesh borders.
*/
void mesh_bed_leveling::line_to_destination(const_feedRate_t scaled_fr_mm_s, uint8_t x_splits, uint8_t y_splits) {
void mesh_bed_leveling::line_to_destination(const feedRate_t scaled_fr_mm_s, uint8_t x_splits, uint8_t y_splits) {
// Get current and destination cells for this line
xy_uint8_t scel = cell_indexes(current_position), ecel = cell_indexes(destination);
NOMORE(scel.x, GRID_MAX_CELLS_X - 1);

View file

@ -55,7 +55,7 @@ public:
static bool mesh_is_valid() { return has_mesh(); }
static void set_z(const int8_t px, const int8_t py, const_float_t z) { z_values[px][py] = z; }
static void set_z(const int8_t px, const int8_t py, const float z) { z_values[px][py] = z; }
static void zigzag(const int8_t index, int8_t &px, int8_t &py) {
px = index % (GRID_MAX_POINTS_X);
@ -63,7 +63,7 @@ public:
if (py & 1) px = (GRID_MAX_POINTS_X) - 1 - px; // Zig zag
}
static void set_zigzag_z(const int8_t index, const_float_t z) {
static void set_zigzag_z(const int8_t index, const float z) {
int8_t px, py;
zigzag(index, px, py);
set_z(px, py, z);
@ -72,33 +72,33 @@ public:
static float get_mesh_x(const uint8_t i) { return index_to_xpos[i]; }
static float get_mesh_y(const uint8_t i) { return index_to_ypos[i]; }
static uint8_t cell_index_x(const_float_t x) {
static uint8_t cell_index_x(const float x) {
int8_t cx = (x - (MESH_MIN_X)) * RECIPROCAL(MESH_X_DIST);
return constrain(cx, 0, GRID_MAX_CELLS_X - 1);
}
static uint8_t cell_index_y(const_float_t y) {
static uint8_t cell_index_y(const float y) {
int8_t cy = (y - (MESH_MIN_Y)) * RECIPROCAL(MESH_Y_DIST);
return constrain(cy, 0, GRID_MAX_CELLS_Y - 1);
}
static xy_uint8_t cell_indexes(const_float_t x, const_float_t y) {
static xy_uint8_t cell_indexes(const float x, const float y) {
return { cell_index_x(x), cell_index_y(y) };
}
static xy_uint8_t cell_indexes(const xy_pos_t &xy) { return cell_indexes(xy.x, xy.y); }
static int8_t probe_index_x(const_float_t x) {
static int8_t probe_index_x(const float x) {
int8_t px = (x - (MESH_MIN_X) + 0.5f * (MESH_X_DIST)) * RECIPROCAL(MESH_X_DIST);
return WITHIN(px, 0, (GRID_MAX_POINTS_X) - 1) ? px : -1;
}
static int8_t probe_index_y(const_float_t y) {
static int8_t probe_index_y(const float y) {
int8_t py = (y - (MESH_MIN_Y) + 0.5f * (MESH_Y_DIST)) * RECIPROCAL(MESH_Y_DIST);
return WITHIN(py, 0, (GRID_MAX_POINTS_Y) - 1) ? py : -1;
}
static xy_int8_t probe_indexes(const_float_t x, const_float_t y) {
static xy_int8_t probe_indexes(const float x, const float y) {
return { probe_index_x(x), probe_index_y(y) };
}
static xy_int8_t probe_indexes(const xy_pos_t &xy) { return probe_indexes(xy.x, xy.y); }
static float calc_z0(const_float_t a0, const_float_t a1, const_float_t z1, const_float_t a2, const_float_t z2) {
static float calc_z0(const float a0, const float a1, const float z1, const float a2, const float z2) {
const float delta_z = (z2 - z1) / (a2 - a1),
delta_a = a0 - a1;
return z1 + delta_a * delta_z;
@ -118,7 +118,7 @@ public:
}
#if IS_CARTESIAN && DISABLED(SEGMENT_LEVELED_MOVES)
static void line_to_destination(const_feedRate_t scaled_fr_mm_s, uint8_t x_splits=0xFF, uint8_t y_splits=0xFF);
static void line_to_destination(const feedRate_t scaled_fr_mm_s, uint8_t x_splits=0xFF, uint8_t y_splits=0xFF);
#endif
};

View file

@ -102,7 +102,7 @@ void unified_bed_leveling::invalidate() {
set_all_mesh_points_to_value(NAN);
}
void unified_bed_leveling::set_all_mesh_points_to_value(const_float_t value) {
void unified_bed_leveling::set_all_mesh_points_to_value(const float value) {
GRID_LOOP(x, y) {
z_values[x][y] = value;
TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, value));
@ -115,7 +115,7 @@ void unified_bed_leveling::set_all_mesh_points_to_value(const_float_t value) {
constexpr int16_t Z_STEPS_NAN = INT16_MAX;
void unified_bed_leveling::set_store_from_mesh(const bed_mesh_t &in_values, mesh_store_t &stored_values) {
auto z_to_store = [](const_float_t z) {
auto z_to_store = [](const float z) {
if (isnan(z)) return Z_STEPS_NAN;
const int32_t z_scaled = TRUNC(z * mesh_store_scaling);
if (z_scaled == Z_STEPS_NAN || !WITHIN(z_scaled, INT16_MIN, INT16_MAX))

View file

@ -67,15 +67,15 @@ private:
static G29_parameters_t param;
#if IS_NEWPANEL
static void move_z_with_encoder(const_float_t multiplier);
static void move_z_with_encoder(const float multiplier);
static float measure_point_with_encoder();
static float measure_business_card_thickness();
static void manually_probe_remaining_mesh(const xy_pos_t&, const_float_t, const_float_t, const bool) __O0;
static void manually_probe_remaining_mesh(const xy_pos_t&, const float, const float, const bool) __O0;
static void fine_tune_mesh(const xy_pos_t &pos, const bool do_ubl_mesh_map) __O0;
#endif
static bool G29_parse_parameters() __O0;
static void shift_mesh_height();
static void shift_mesh_height(const float zoffs);
static void probe_entire_mesh(const xy_pos_t &near, const bool do_ubl_mesh_map, const bool stow_probe, const bool do_furthest) __O0;
static void tilt_mesh_based_on_probed_grid(const bool do_ubl_mesh_map);
static bool smart_fill_one(const uint8_t x, const uint8_t y, const int8_t xdir, const int8_t ydir);
@ -101,13 +101,13 @@ public:
static mesh_index_pair find_furthest_invalid_mesh_point() __O0;
static void reset();
static void invalidate();
static void set_all_mesh_points_to_value(const_float_t value);
static void adjust_mesh_to_mean(const bool cflag, const_float_t value);
static void set_all_mesh_points_to_value(const float value);
static void adjust_mesh_to_mean(const bool cflag, const float value);
static bool sanity_check();
static void smart_fill_mesh();
static void G29() __O0; // O0 for no optimization
static void smart_fill_wlsf(const_float_t ) __O2; // O2 gives smaller code than Os on A2560
static void smart_fill_wlsf(const float ) __O2; // O2 gives smaller code than Os on A2560
static int8_t storage_slot;
@ -130,42 +130,42 @@ public:
unified_bed_leveling();
FORCE_INLINE static void set_z(const int8_t px, const int8_t py, const_float_t z) { z_values[px][py] = z; }
FORCE_INLINE static void set_z(const int8_t px, const int8_t py, const float z) { z_values[px][py] = z; }
static int8_t cell_index_x_raw(const_float_t x) {
static int8_t cell_index_x_raw(const float x) {
return FLOOR((x - (MESH_MIN_X)) * RECIPROCAL(MESH_X_DIST));
}
static int8_t cell_index_y_raw(const_float_t y) {
static int8_t cell_index_y_raw(const float y) {
return FLOOR((y - (MESH_MIN_Y)) * RECIPROCAL(MESH_Y_DIST));
}
static bool cell_index_x_valid(const_float_t x) {
static bool cell_index_x_valid(const float x) {
return WITHIN(cell_index_x_raw(x), 0, GRID_MAX_CELLS_X - 1);
}
static bool cell_index_y_valid(const_float_t y) {
static bool cell_index_y_valid(const float y) {
return WITHIN(cell_index_y_raw(y), 0, GRID_MAX_CELLS_Y - 1);
}
static uint8_t cell_index_x(const_float_t x) {
static uint8_t cell_index_x(const float x) {
return constrain(cell_index_x_raw(x), 0, GRID_MAX_CELLS_X - 1);
}
static uint8_t cell_index_y(const_float_t y) {
static uint8_t cell_index_y(const float y) {
return constrain(cell_index_y_raw(y), 0, GRID_MAX_CELLS_Y - 1);
}
static xy_uint8_t cell_indexes(const_float_t x, const_float_t y) {
static xy_uint8_t cell_indexes(const float x, const float y) {
return { cell_index_x(x), cell_index_y(y) };
}
static xy_uint8_t cell_indexes(const xy_pos_t &xy) { return cell_indexes(xy.x, xy.y); }
static int8_t closest_x_index(const_float_t x) {
static int8_t closest_x_index(const float x) {
const int8_t px = (x - (MESH_MIN_X) + (MESH_X_DIST) * 0.5) * RECIPROCAL(MESH_X_DIST);
return WITHIN(px, 0, (GRID_MAX_POINTS_X) - 1) ? px : -1;
}
static int8_t closest_y_index(const_float_t y) {
static int8_t closest_y_index(const float y) {
const int8_t py = (y - (MESH_MIN_Y) + (MESH_Y_DIST) * 0.5) * RECIPROCAL(MESH_Y_DIST);
return WITHIN(py, 0, (GRID_MAX_POINTS_Y) - 1) ? py : -1;
}
@ -188,7 +188,7 @@ public:
* It is fairly expensive with its 4 floating point additions and 2 floating point
* multiplications.
*/
FORCE_INLINE static float calc_z0(const_float_t a0, const_float_t a1, const_float_t z1, const_float_t a2, const_float_t z2) {
FORCE_INLINE static float calc_z0(const float a0, const float a1, const float z1, const float a2, const float z2) {
return z1 + (z2 - z1) * (a0 - a1) / (a2 - a1);
}
@ -202,7 +202,7 @@ public:
* z_correction_for_x_on_horizontal_mesh_line is an optimization for
* the case where the printer is making a vertical line that only crosses horizontal mesh lines.
*/
static float z_correction_for_x_on_horizontal_mesh_line(const_float_t rx0, const int x1_i, const int yi) {
static float z_correction_for_x_on_horizontal_mesh_line(const float rx0, const int x1_i, const int yi) {
if (!WITHIN(x1_i, 0, (GRID_MAX_POINTS_X) - 1) || !WITHIN(yi, 0, (GRID_MAX_POINTS_Y) - 1)) {
if (DEBUGGING(LEVELING)) {
@ -225,7 +225,7 @@ public:
//
// See comments above for z_correction_for_x_on_horizontal_mesh_line
//
static float z_correction_for_y_on_vertical_mesh_line(const_float_t ry0, const int xi, const int y1_i) {
static float z_correction_for_y_on_vertical_mesh_line(const float ry0, const int xi, const int y1_i) {
if (!WITHIN(xi, 0, (GRID_MAX_POINTS_X) - 1) || !WITHIN(y1_i, 0, (GRID_MAX_POINTS_Y) - 1)) {
if (DEBUGGING(LEVELING)) {
@ -251,7 +251,7 @@ public:
* Z-Height at both ends. Then it does a linear interpolation of these heights based
* on the Y position within the cell.
*/
static float get_z_correction(const_float_t rx0, const_float_t ry0) {
static float get_z_correction(const float rx0, const float ry0) {
const int8_t cx = cell_index_x(rx0), cy = cell_index_y(ry0); // return values are clamped
/**
@ -295,9 +295,9 @@ public:
}
#if UBL_SEGMENTED
static bool line_to_destination_segmented(const_feedRate_t scaled_fr_mm_s);
static bool line_to_destination_segmented(const feedRate_t scaled_fr_mm_s);
#else
static void line_to_destination_cartesian(const_feedRate_t scaled_fr_mm_s, const uint8_t e);
static void line_to_destination_cartesian(const feedRate_t scaled_fr_mm_s, const uint8_t e);
#endif
static bool mesh_is_valid() {

View file

@ -48,7 +48,7 @@
#include "../hilbert_curve.h"
#endif
#if FT_MOTION_DISABLE_FOR_PROBING
#if ENABLED(FT_MOTION)
#include "../../../module/ft_motion.h"
#endif
@ -313,9 +313,8 @@ void unified_bed_leveling::G29() {
const uint8_t p_val = parser.byteval('P');
const bool may_move = p_val == 1 || p_val == 2 || p_val == 4 || parser.seen_test('J');
#if FT_MOTION_DISABLE_FOR_PROBING
FTMotionDisableInScope FT_Disabler; // Disable Fixed-Time Motion for probing
#endif
// Potentially disable Fixed-Time Motion for probing
TERN_(FT_MOTION, FTMotionDisableInScope FT_Disabler);
// Check for commands that require the printer to be homed
if (may_move) {
@ -612,7 +611,7 @@ void unified_bed_leveling::G29() {
case 5: adjust_mesh_to_mean(param.C_seen, param.C_constant); break;
case 6: shift_mesh_height(); break;
case 6: shift_mesh_height(param.C_constant); break;
}
}
@ -716,7 +715,7 @@ void unified_bed_leveling::G29() {
* G29 P5 C<value> : Adjust Mesh To Mean (and subtract the given offset).
* Find the mean average and shift the mesh to center on that value.
*/
void unified_bed_leveling::adjust_mesh_to_mean(const bool cflag, const_float_t offset) {
void unified_bed_leveling::adjust_mesh_to_mean(const bool cflag, const float offset) {
float sum = 0;
uint8_t n = 0;
GRID_LOOP(x, y)
@ -752,10 +751,10 @@ void unified_bed_leveling::adjust_mesh_to_mean(const bool cflag, const_float_t o
/**
* G29 P6 C<offset> : Shift Mesh Height by a uniform constant.
*/
void unified_bed_leveling::shift_mesh_height() {
void unified_bed_leveling::shift_mesh_height(const float zoffs) {
GRID_LOOP(x, y)
if (!isnan(z_values[x][y])) {
z_values[x][y] += param.C_constant;
z_values[x][y] += zoffs;
TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, z_values[x][y]));
}
}
@ -782,7 +781,7 @@ void unified_bed_leveling::shift_mesh_height() {
const grid_count_t point_num = (GRID_MAX_POINTS - count) + 1;
SERIAL_ECHOLNPGM("Probing mesh point ", point_num, "/", GRID_MAX_POINTS, ".");
TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/%i"), GET_TEXT_F(MSG_PROBING_POINT), point_num, int(GRID_MAX_POINTS)));
TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_POINT), point_num, int(GRID_MAX_POINTS)));
TERN_(HAS_BACKLIGHT_TIMEOUT, ui.refresh_backlight_timeout());
#if HAS_MARLINUI_MENU
@ -870,7 +869,7 @@ void set_message_with_feedback(FSTR_P const fstr) {
return false;
}
void unified_bed_leveling::move_z_with_encoder(const_float_t multiplier) {
void unified_bed_leveling::move_z_with_encoder(const float multiplier) {
ui.wait_for_release();
while (!ui.button_pressed()) {
idle();
@ -953,7 +952,7 @@ void set_message_with_feedback(FSTR_P const fstr) {
* Move to INVALID points and
* NOTE: Blocks the G-code queue and captures Marlin UI during use.
*/
void unified_bed_leveling::manually_probe_remaining_mesh(const xy_pos_t &pos, const_float_t z_clearance, const_float_t thick, const bool do_ubl_mesh_map) {
void unified_bed_leveling::manually_probe_remaining_mesh(const xy_pos_t &pos, const float z_clearance, const float thick, const bool do_ubl_mesh_map) {
ui.capture();
TERN_(EXTENSIBLE_UI, ExtUI::onLevelingStart());
@ -1511,7 +1510,7 @@ void unified_bed_leveling::smart_fill_mesh() {
for (uint8_t i = 0; i < 3; ++i) {
SERIAL_ECHOLNPGM("Tilting mesh (", i + 1, "/3)");
TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/3"), GET_TEXT_F(MSG_LCD_TILTING_MESH), i + 1));
TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/3"), GET_TEXT(MSG_LCD_TILTING_MESH), i + 1));
measured_z = probe.probe_at_point(points[i], i < 2 ? PROBE_PT_RAISE : PROBE_PT_LAST_STOW, param.V_verbosity);
if ((abort_flag = isnan(measured_z))) break;
@ -1567,7 +1566,7 @@ void unified_bed_leveling::smart_fill_mesh() {
#endif
SERIAL_ECHOLNPGM("Tilting mesh point ", point_num, "/", total_points, "\n");
TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/%i"), GET_TEXT_F(MSG_LCD_TILTING_MESH), point_num, total_points));
TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/%i"), GET_TEXT(MSG_LCD_TILTING_MESH), point_num, total_points));
measured_z = probe.probe_at_point(rpos, parser.seen_test('E') ? PROBE_PT_STOW : PROBE_PT_RAISE, param.V_verbosity); // TODO: Needs error handling
@ -1661,10 +1660,10 @@ void unified_bed_leveling::smart_fill_mesh() {
*/
#if ENABLED(VALIDATE_MESH_TILT)
auto d_from = []{ DEBUG_ECHOPGM("D from "); };
auto normed = [&](const xy_pos_t &pos, const_float_t zadd) {
auto normed = [&](const xy_pos_t &pos, const float zadd) {
return normal.x * pos.x + normal.y * pos.y + zadd;
};
auto debug_pt = [](const int num, const xy_pos_t &pos, const_float_t zadd) {
auto debug_pt = [](const int num, const xy_pos_t &pos, const float zadd) {
d_from();
DEBUG_ECHOLN(F("Point "), num, C(':'), p_float_t(normed(pos, zadd), 6), F(" Z error = "), p_float_t(zadd - get_z_correction(pos), 6));
};
@ -1685,7 +1684,7 @@ void unified_bed_leveling::smart_fill_mesh() {
#endif // HAS_BED_PROBE
#if ENABLED(UBL_G29_P31)
void unified_bed_leveling::smart_fill_wlsf(const_float_t weight_factor) {
void unified_bed_leveling::smart_fill_wlsf(const float weight_factor) {
// For each undefined mesh point, compute a distance-weighted least squares fit
// from all the originally populated mesh points, weighted toward the point

View file

@ -47,7 +47,7 @@
// corners of cells. To fix the issue, simply check if the start/end of the line
// is very close to a cell boundary in advance and don't split the line there.
void unified_bed_leveling::line_to_destination_cartesian(const_feedRate_t scaled_fr_mm_s, const uint8_t extruder) {
void unified_bed_leveling::line_to_destination_cartesian(const feedRate_t scaled_fr_mm_s, const uint8_t extruder) {
/**
* Much of the nozzle movement will be within the same cell. So we will do as little computation
* as possible to determine if this is the case. If this move is within the same cell, we will
@ -351,7 +351,7 @@
* Returns true if did NOT move, false if moved (requires current_position update).
*/
bool __O2 unified_bed_leveling::line_to_destination_segmented(const_feedRate_t scaled_fr_mm_s) {
bool __O2 unified_bed_leveling::line_to_destination_segmented(const feedRate_t scaled_fr_mm_s) {
if (!position_is_reachable(destination)) // fail if moving outside reachable boundary
return true; // did not move, so current_position still accurate

View file

@ -68,7 +68,7 @@ void StepperDAC::set_current_value(const uint8_t channel, uint16_t val) {
}
void StepperDAC::set_current_percent(const uint8_t channel, float val) {
set_current_value(channel, _MIN(val, 100.0f) * (DAC_STEPPER_MAX) / 100.0f);
set_current_value(channel, _MIN(val, 100.0f) * (DAC_STEPPER_MAX) * 0.01f);
}
static float dac_perc(int8_t n) { return mcp4728.getDrvPct(dac_order[n]); }

View file

@ -188,7 +188,7 @@ class I2CPositionEncoder {
FORCE_INLINE void set_ec_method(const byte method) { ecMethod = method; }
FORCE_INLINE float get_ec_threshold() { return ecThreshold; }
FORCE_INLINE void set_ec_threshold(const_float_t newThreshold) { ecThreshold = newThreshold; }
FORCE_INLINE void set_ec_threshold(const float newThreshold) { ecThreshold = newThreshold; }
FORCE_INLINE int get_encoder_ticks_mm() {
switch (type) {

View file

@ -67,7 +67,7 @@ public:
}
// Convert raw measurement to mm
static float raw_to_mm(const uint16_t v) { return v * (float(ADC_VREF_MV) / 1000.0f) * RECIPROCAL(float(MAX_RAW_THERMISTOR_VALUE)); }
static float raw_to_mm(const uint16_t v) { return v * (float(ADC_VREF_MV) * 0.001f) * RECIPROCAL(float(MAX_RAW_THERMISTOR_VALUE)); }
static float raw_to_mm() { return raw_to_mm(raw); }
// A scaled reading is ready
@ -78,7 +78,7 @@ public:
static void update_measured_mm() { measured_mm = raw_to_mm(); }
// Update ring buffer used to delay filament measurements
static void advance_e(const_float_t e_move) {
static void advance_e(const float e_move) {
// Increment counters with the E distance
e_count += e_move;

View file

@ -283,7 +283,7 @@ void Max7219::set(const uint8_t line, const uint8_t bits) {
}
// Draw a float with a decimal point and optional digits
void Max7219::print(const uint8_t start, const_float_t value, const uint8_t pre_size, const uint8_t post_size, const bool leadzero=false) {
void Max7219::print(const uint8_t start, const float value, const uint8_t pre_size, const uint8_t post_size, const bool leadzero=false) {
if (pre_size) print(start, value, pre_size, leadzero, !!post_size);
if (post_size) {
const int16_t after = ABS(value) * (10 ^ post_size);

View file

@ -166,7 +166,7 @@ public:
// Draw an integer with optional leading zeros and optional decimal point
void print(const uint8_t start, int16_t value, uint8_t size, const bool leadzero=false, bool dec=false);
// Draw a float with a decimal point and optional digits
void print(const uint8_t start, const_float_t value, const uint8_t pre_size, const uint8_t post_size, const bool leadzero=false);
void print(const uint8_t start, const float value, const uint8_t pre_size, const uint8_t post_size, const bool leadzero=false);
#endif
// Set a single LED by XY coordinate

View file

@ -166,7 +166,7 @@ void Mixer::refresh_collector(const float proportion/*=1.0*/, const uint8_t t/*=
float Mixer::prev_z; // = 0
void Mixer::update_gradient_for_z(const_float_t z) {
void Mixer::update_gradient_for_z(const float z) {
if (z == prev_z) return;
prev_z = z;

View file

@ -174,9 +174,9 @@ class Mixer {
static float prev_z;
// Update the current mix from the gradient for a given Z
static void update_gradient_for_z(const_float_t z);
static void update_gradient_for_z(const float z);
static void update_gradient_for_planner_z();
static void gradient_control(const_float_t z) {
static void gradient_control(const float z) {
if (gradient.enabled) {
if (z >= gradient.end_z)
T(gradient.end_vtool);

View file

@ -7,9 +7,9 @@ When initialized, MMU sends
We follow with
- MMU <= 'S1\n'
- MMU => 'ok*Firmware version*\n'
- MMU => 'ok<_Firmware version_>\n'
- MMU <= 'S2\n'
- MMU => 'ok*Build number*\n'
- MMU => 'ok<_Build number_>\n'
#if (12V_mode)
@ -19,25 +19,25 @@ We follow with
#endif
- MMU <= 'P0\n'
- MMU => '_FINDA status_\n'
- MMU => '<_FINDA status_>\n'
Now we are sure MMU is available and ready. If there was a timeout or other communication problem somewhere, printer will be killed.
- _Firmware version_ is an integer value, but we don't care about it
- _Build number_ is an integer value and has to be >=126, or =>132 if 12V mode is enabled
- _FINDA status_ is 1 if the filament is loaded to the extruder, 0 otherwise
- <_Firmware version_> is an integer value, but we don't care about it.
- <_Build number_> is an integer value and has to be >=126, or =>132 if 12V mode is enabled.
- <_FINDA status_> is 1 if the filament is loaded to the extruder, 0 otherwise.
_Build number_ is checked against the required value, if it does not match, printer is halted.
<_Build number_> is checked against the required value, if it does not match, printer is halted.
# Toolchange
- MMU <= 'T*Filament index*\n'
- MMU <= 'T<_Filament index_>\n'
MMU sends
- MMU => 'ok\n'
as soon as the filament is fed down to the extruder. We follow with
as soon as the filament is fed down to the extruder. We follow with:
- MMU <= 'C0\n'
@ -52,15 +52,15 @@ be one or more extruder moves to feed the filament into the hotend.
# FINDA status
- MMU <= 'P0\n'
- MMU => '_FINDA status_\n'
- MMU => '<_FINDA status_>\n'
_FINDA status_ is 1 if the is filament loaded to the extruder, 0 otherwise. This could be used as filament runout sensor if probed regularly.
# Load filament
- MMU <= 'L*Filament index*\n'
- MMU <= 'L<_Filament index_>\n'
MMU will feed filament down to the extruder, when done
MMU will feed filament down to the extruder, when done:
- MMU => 'ok\n'
@ -68,11 +68,11 @@ MMU will feed filament down to the extruder, when done
- MMU <= 'U0\n'
MMU will retract current filament from the extruder, when done
MMU will retract current filament from the extruder, when done:
- MMU => 'ok\n'
# Eject filament
- MMU <= 'E*Filament index*\n'
- MMU <= 'E<_Filament index_>\n'
- MMU => 'ok\n'

View file

@ -96,7 +96,7 @@ struct E_Step {
feedRate_t feedRate; //!< feed rate in mm/s
};
inline void unscaled_mmu2_e_move(const float &dist, const feedRate_t fr_mm_s, const bool sync=true) {
inline void unscaled_mmu2_e_move(const float dist, const feedRate_t fr_mm_s, const bool sync=true) {
current_position.e += dist / planner.e_factor[active_extruder];
line_to_current_position(fr_mm_s);
if (sync) planner.synchronize();

View file

@ -867,7 +867,7 @@ namespace MMU3 {
nozzle_timer.start();
LogEchoEvent(F("Cooling Timeout started"));
}
else if (nozzle_timer.duration() > (PAUSE_PARK_NOZZLE_TIMEOUT * 1000ul)) { // mins->msec.
else if (nozzle_timer.duration() > (PAUSE_PARK_NOZZLE_TIMEOUT * 1000UL)) { // mins->msec.
mmu_print_saved &= ~(SavedState::CooldownPending);
mmu_print_saved |= SavedState::Cooldown;
thermal_setTargetHotend(0);

View file

@ -33,10 +33,10 @@ namespace MMU3 {
// - Unify implementation among MK3 and Buddy FW
// - Enable unit testing of MMU top layer
void extruder_move(const_float_t distance, const_float_t feedRate_mm_s, const bool sync=true);
void extruder_schedule_turning(const_float_t feedRate_mm_s);
void extruder_move(const float distance, const float feedRate_mm_s, const bool sync=true);
void extruder_schedule_turning(const float feedRate_mm_s);
float move_raise_z(const_float_t delta);
float move_raise_z(const float delta);
void planner_abort_queued_moves();
void planner_synchronize();

View file

@ -49,13 +49,13 @@ namespace MMU3 {
planner_synchronize();
}
void extruder_move(const_float_t delta, const_float_t feedRate_mm_s, const bool sync/*=true*/) {
void extruder_move(const float delta, const float feedRate_mm_s, const bool sync/*=true*/) {
current_position.e += delta / planner.e_factor[active_extruder];
planner_line_to_current_position(feedRate_mm_s);
if (sync) planner.synchronize();
}
float move_raise_z(const_float_t delta) {
float move_raise_z(const float delta) {
//return raise_z(delta);
xyze_pos_t current_position_before = current_position;
do_z_clearance_by(delta);

View file

@ -707,7 +707,7 @@ namespace MMU3 {
}
bool ProtocolLogic::Elapsed(uint32_t timeout) const {
return _millis() >= (lastUARTActivityMs + timeout);
return ELAPSED(_millis(), lastUARTActivityMs + timeout);
}
void ProtocolLogic::RecordUARTActivity() {
@ -716,7 +716,7 @@ namespace MMU3 {
void ProtocolLogic::RecordReceivedByte(uint8_t c) {
lastReceivedBytes[lrb] = c;
lrb = (lrb + 1) % lastReceivedBytes.size();
lrb = (lrb + 1) % COUNT(lastReceivedBytes);
}
constexpr char NibbleToChar(uint8_t c) {
@ -728,13 +728,13 @@ namespace MMU3 {
}
void ProtocolLogic::FormatLastReceivedBytes(char *dst) {
for (uint8_t i = 0; i < lastReceivedBytes.size(); ++i) {
uint8_t b = lastReceivedBytes[(lrb - i - 1) % lastReceivedBytes.size()];
for (uint8_t i = 0; i < COUNT(lastReceivedBytes); ++i) {
uint8_t b = lastReceivedBytes[(COUNT(lastReceivedBytes) - 1 + (lrb - i)) % COUNT(lastReceivedBytes)];
dst[i * 3] = NibbleToChar(b >> 4);
dst[i * 3 + 1] = NibbleToChar(b & 0xf);
dst[i * 3 + 2] = ' ';
}
dst[(lastReceivedBytes.size() - 1) * 3 + 2] = 0; // terminate properly
dst[(COUNT(lastReceivedBytes) - 1) * 3 + 2] = 0; // terminate properly
}
void ProtocolLogic::FormatLastResponseMsgAndClearLRB(char *dst) {
@ -777,18 +777,18 @@ namespace MMU3 {
}
void ProtocolLogic::LogError(const char *reason_P) {
char lrb[lastReceivedBytes.size() * 3];
FormatLastReceivedBytes(lrb);
char _lrb[COUNT(lastReceivedBytes) * 3];
FormatLastReceivedBytes(_lrb);
MMU2_ERROR_MSGRPGM(reason_P);
SERIAL_ECHOPGM(", last bytes: ");
SERIAL_ECHOLN(lrb);
SERIAL_ECHOLN(_lrb);
}
void ProtocolLogic::LogResponse() {
char lrb[lastReceivedBytes.size()];
FormatLastResponseMsgAndClearLRB(lrb);
MMU2_ECHO_MSGLN(lrb);
char _lrb[COUNT(lastReceivedBytes)];
FormatLastResponseMsgAndClearLRB(_lrb);
MMU2_ECHO_MSGLN(_lrb);
}
StepStatus ProtocolLogic::SuppressShortDropOuts(const char *msg_P, StepStatus ss) {

View file

@ -36,24 +36,8 @@
#include "mmu_hw/buttons.h"
#include "mmu_hw/registers.h"
#include "mmu3_protocol.h"
// #include <array> std array is not available on AVR ... we need to "fake" it
namespace std {
template <typename T, uint8_t N>
class array {
T data[N];
public:
array() = default;
inline constexpr T *begin() const { return data; }
inline constexpr T *end() const { return data + N; }
static constexpr uint8_t size() { return N; }
inline T &operator[](uint8_t i) { return data[i]; }
};
} // std
#else // !__AVR__
#include <array>
#include "mmu_hw/error_codes.h"
#include "mmu_hw/progress_codes.h"
@ -351,8 +335,7 @@ namespace MMU3 {
Protocol protocol; //!< protocol codec
std::array<uint8_t, 16> lastReceivedBytes; //!< remembers the last few bytes of incoming communication for diagnostic purposes
uint8_t lrb;
uint8_t lrb, lastReceivedBytes[16]; //!< keep the last few bytes of incoming communication for diagnostic purposes
ErrorCode errorCode; //!< last received error code from the MMU
ProgressCode progressCode; //!< last received progress code from the MMU

View file

@ -188,10 +188,8 @@ static bool ensure_safe_temperature(const bool wait=true, const PauseMode mode=P
*
* Returns 'true' if load was completed, 'false' for abort
*/
bool load_filament(const_float_t slow_load_length/*=0*/, const_float_t fast_load_length/*=0*/, const_float_t purge_length/*=0*/, const int8_t max_beep_count/*=0*/,
const bool show_lcd/*=false*/, const bool pause_for_user/*=false*/,
const PauseMode mode/*=PAUSE_MODE_PAUSE_PRINT*/
DXC_ARGS
bool load_filament(const float slow_load_length/*=0*/, const float fast_load_length/*=0*/, const float purge_length/*=0*/, const int8_t max_beep_count/*=0*/,
const bool show_lcd/*=false*/, const bool pause_for_user/*=false*/, const PauseMode mode/*=PAUSE_MODE_PAUSE_PRINT*/ DXC_ARGS
) {
DEBUG_SECTION(lf, "load_filament", true);
DEBUG_ECHOLNPGM("... slowlen:", slow_load_length, " fastlen:", fast_load_length, " purgelen:", purge_length, " maxbeep:", max_beep_count, " showlcd:", show_lcd, " pauseforuser:", pause_for_user, " pausemode:", mode DXC_SAY);
@ -344,10 +342,10 @@ inline void disable_active_extruder() {
*
* Returns 'true' if unload was completed, 'false' for abort
*/
bool unload_filament(const_float_t unload_length, const bool show_lcd/*=false*/,
bool unload_filament(const float unload_length, const bool show_lcd/*=false*/,
const PauseMode mode/*=PAUSE_MODE_PAUSE_PRINT*/
#if ALL(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER)
, const_float_t mix_multiplier/*=1.0*/
, const float mix_multiplier/*=1.0*/
#endif
) {
DEBUG_SECTION(uf, "unload_filament", true);
@ -418,7 +416,7 @@ bool unload_filament(const_float_t unload_length, const bool show_lcd/*=false*/,
*/
uint8_t did_pause_print = 0;
bool pause_print(const_float_t retract, const xyz_pos_t &park_point, const bool show_lcd/*=false*/, const_float_t unload_length/*=0*/ DXC_ARGS) {
bool pause_print(const float retract, const xyz_pos_t &park_point, const bool show_lcd/*=false*/, const float unload_length/*=0*/ DXC_ARGS) {
DEBUG_SECTION(pp, "pause_print", true);
DEBUG_ECHOLNPGM("... park.x:", park_point.x, " y:", park_point.y, " z:", park_point.z, " unloadlen:", unload_length, " showlcd:", show_lcd DXC_SAY);
@ -639,9 +637,9 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep
* - Resume the current SD print job, if any
*/
void resume_print(
const_float_t slow_load_length/*=0*/,
const_float_t fast_load_length/*=0*/,
const_float_t purge_length/*=ADVANCED_PAUSE_PURGE_LENGTH*/,
const float slow_load_length/*=0*/,
const float fast_load_length/*=0*/,
const float purge_length/*=ADVANCED_PAUSE_PURGE_LENGTH*/,
const int8_t max_beep_count/*=0*/,
const celsius_t targetTemp/*=0*/,
const bool show_lcd/*=true*/,

View file

@ -91,10 +91,10 @@ extern uint8_t did_pause_print;
// Pause the print. If unload_length is set, do a Filament Unload
bool pause_print(
const_float_t retract, // (mm) Retraction length
const float retract, // (mm) Retraction length
const xyz_pos_t &park_point, // Parking XY Position and Z Raise
const bool show_lcd=false, // Set LCD status messages?
const_float_t unload_length=0 // (mm) Filament Change Unload Length - 0 to skip
const float unload_length=0 // (mm) Filament Change Unload Length - 0 to skip
DXC_PARAMS // Dual-X-Carriage extruder index
);
@ -105,9 +105,9 @@ void wait_for_confirmation(
);
void resume_print(
const_float_t slow_load_length=0, // (mm) Slow Load Length for finishing move
const_float_t fast_load_length=0, // (mm) Fast Load Length for initial move
const_float_t purge_length=ADVANCED_PAUSE_PURGE_LENGTH, // (mm) Purge length
const float slow_load_length=0, // (mm) Slow Load Length for finishing move
const float fast_load_length=0, // (mm) Fast Load Length for initial move
const float purge_length=ADVANCED_PAUSE_PURGE_LENGTH, // (mm) Purge length
const int8_t max_beep_count=0, // Beep alert for attention
const celsius_t targetTemp=0, // (°C) A target temperature for the hotend
const bool show_lcd=true, // Set LCD status messages?
@ -116,9 +116,9 @@ void resume_print(
);
bool load_filament(
const_float_t slow_load_length=0, // (mm) Slow Load Length for finishing move
const_float_t fast_load_length=0, // (mm) Fast Load Length for initial move
const_float_t purge_length=0, // (mm) Purge length
const float slow_load_length=0, // (mm) Slow Load Length for finishing move
const float fast_load_length=0, // (mm) Fast Load Length for initial move
const float purge_length=0, // (mm) Purge length
const int8_t max_beep_count=0, // Beep alert for attention
const bool show_lcd=false, // Set LCD status messages?
const bool pause_for_user=false, // Pause for user before returning?
@ -127,11 +127,11 @@ bool load_filament(
);
bool unload_filament(
const_float_t unload_length, // (mm) Filament Unload Length - 0 to skip
const float unload_length, // (mm) Filament Unload Length - 0 to skip
const bool show_lcd=false, // Set LCD status messages?
const PauseMode mode=PAUSE_MODE_PAUSE_PRINT // Pause Mode to apply
#if ALL(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER)
, const_float_t mix_multiplier=1.0f // Extrusion multiplier (for a Mixing Extruder)
, const float mix_multiplier=1.0f // Extrusion multiplier (for a Mixing Extruder)
#endif
);

View file

@ -270,7 +270,7 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=POW
#if ENABLED(BACKUP_POWER_SUPPLY)
void PrintJobRecovery::retract_and_lift(const_float_t zraise) {
void PrintJobRecovery::retract_and_lift(const float zraise) {
#if POWER_LOSS_RETRACT_LEN || POWER_LOSS_ZRAISE
gcode.set_relative_mode(true); // Use relative coordinates

View file

@ -237,7 +237,7 @@ class PrintJobRecovery {
static void write();
#if ENABLED(BACKUP_POWER_SUPPLY)
static void retract_and_lift(const_float_t zraise);
static void retract_and_lift(const float zraise);
#endif
#if PIN_EXISTS(POWER_LOSS) || ENABLED(DEBUG_POWER_LOSS_RECOVERY)

View file

@ -104,12 +104,12 @@ void ProbeTempComp::print_offsets() {
#endif
}
void ProbeTempComp::prepare_new_calibration(const_float_t init_meas_z) {
void ProbeTempComp::prepare_new_calibration(const float init_meas_z) {
calib_idx = 0;
init_measurement = init_meas_z;
}
void ProbeTempComp::push_back_new_measurement(const TempSensorID tsi, const_float_t meas_z) {
void ProbeTempComp::push_back_new_measurement(const TempSensorID tsi, const float meas_z) {
if (calib_idx >= cali_info[tsi].measurements) return;
sensor_z_offsets[tsi][calib_idx++] = static_cast<int16_t>((meas_z - init_measurement) * 1000.0f);
}
@ -186,7 +186,7 @@ void ProbeTempComp::compensate_measurement(const TempSensorID tsi, const celsius
};
// Interpolate Z based on a temperature being within a given range
auto linear_interp = [](const_float_t x, xy_float_t p1, xy_float_t p2) {
auto linear_interp = [](const float x, xy_float_t p1, xy_float_t p2) {
// zoffs1 + zoffset_per_toffset * toffset
return p1.y + (p2.y - p1.y) / (p2.x - p1.x) * (x - p1.x);
};
@ -212,7 +212,7 @@ void ProbeTempComp::compensate_measurement(const TempSensorID tsi, const celsius
}
// convert offset to mm and apply it
meas_z -= offset / 1000.0f;
meas_z -= offset * 0.001f;
}
bool ProbeTempComp::linear_regression(const TempSensorID tsi, float &k, float &d) {

View file

@ -84,8 +84,8 @@ class ProbeTempComp {
}
static bool set_offset(const TempSensorID tsi, const uint8_t idx, const int16_t offset);
static void print_offsets();
static void prepare_new_calibration(const_float_t init_meas_z);
static void push_back_new_measurement(const TempSensorID tsi, const_float_t meas_z);
static void prepare_new_calibration(const float init_meas_z);
static void push_back_new_measurement(const TempSensorID tsi, const float meas_z);
static bool finish_calibration(const TempSensorID tsi);
static void set_enabled(const bool ena) { enabled = ena; }

View file

@ -51,7 +51,6 @@ bool FilamentMonitorBase::enabled = true,
#if ENABLED(FILAMENT_MOTION_SENSOR)
uint8_t FilamentSensorEncoder::motion_detected;
#endif
#if ENABLED(FILAMENT_SWITCH_AND_MOTION)
bool RunoutResponseDelayed::ignore_motion = false;
float RunoutResponseDelayed::motion_distance_mm = FILAMENT_MOTION_DISTANCE_MM;

View file

@ -123,12 +123,12 @@ class TFilamentMonitor : public FilamentMonitorBase {
response.filament_motion_present(extruder);
}
static float& motion_distance() { return response.motion_distance_mm; }
static void set_motion_distance(const_float_t mm) { response.motion_distance_mm = mm; }
static void set_motion_distance(const float mm) { response.motion_distance_mm = mm; }
#endif
#if HAS_FILAMENT_RUNOUT_DISTANCE
static float& runout_distance() { return response.runout_distance_mm; }
static void set_runout_distance(const_float_t mm) { response.runout_distance_mm = mm; }
static void set_runout_distance(const float mm) { response.runout_distance_mm = mm; }
#endif
// Handle a block completion. RunoutResponseDelayed uses this to
@ -143,38 +143,37 @@ class TFilamentMonitor : public FilamentMonitorBase {
// Give the response a chance to update its counter.
static void run() {
if (enabled && !filament_ran_out && should_monitor_runout()) {
TERN_(HAS_FILAMENT_RUNOUT_DISTANCE, cli()); // Prevent RunoutResponseDelayed::block_completed from accumulating here
response.run();
sensor.run();
const runout_flags_t runout_flags = response.has_run_out();
TERN_(HAS_FILAMENT_RUNOUT_DISTANCE, sei());
#if MULTI_FILAMENT_SENSOR
#if ENABLED(WATCH_ALL_RUNOUT_SENSORS)
const bool ran_out = bool(runout_flags); // any sensor triggers
uint8_t extruder = 0;
if (ran_out) while (!runout_flags.test(extruder)) extruder++;
#else
const bool ran_out = runout_flags[active_extruder]; // suppress non active extruders
uint8_t extruder = active_extruder;
#endif
if (!enabled || filament_ran_out || !should_monitor_runout()) return;
TERN_(HAS_FILAMENT_RUNOUT_DISTANCE, cli()); // Prevent RunoutResponseDelayed::block_completed from accumulating here
response.run();
sensor.run();
const runout_flags_t runout_flags = response.has_run_out();
TERN_(HAS_FILAMENT_RUNOUT_DISTANCE, sei());
#if MULTI_FILAMENT_SENSOR
#if ENABLED(WATCH_ALL_RUNOUT_SENSORS)
const bool ran_out = bool(runout_flags); // any sensor triggers
uint8_t extruder = 0;
if (ran_out) while (!runout_flags.test(extruder)) extruder++;
#else
const bool ran_out = bool(runout_flags);
const bool ran_out = runout_flags[active_extruder]; // suppress non active extruders
uint8_t extruder = active_extruder;
#endif
#else
const bool ran_out = bool(runout_flags);
uint8_t extruder = active_extruder;
#endif
if (ran_out) {
#if ENABLED(FILAMENT_RUNOUT_SENSOR_DEBUG)
SERIAL_ECHOPGM("Runout Sensors: ");
for (uint8_t i = 0; i < 8; ++i) SERIAL_CHAR('0' + char(runout_flags[i]));
SERIAL_ECHOLNPGM(" -> ", extruder, " RUN OUT");
#endif
if (!ran_out) return;
filament_ran_out = true;
event_filament_runout(extruder);
planner.synchronize();
}
}
#if ENABLED(FILAMENT_RUNOUT_SENSOR_DEBUG)
SERIAL_ECHOPGM("Runout Sensors: ");
for (uint8_t i = 0; i < 8; ++i) SERIAL_CHAR('0' + char(runout_flags[i]));
SERIAL_ECHOLNPGM(" -> ", extruder, " RUN OUT");
#endif
filament_ran_out = true;
event_filament_runout(extruder);
planner.synchronize();
}
// Reset after a filament runout or upon resuming a job
@ -376,7 +375,9 @@ class FilamentSensorBase {
class RunoutResponseDelayed {
private:
static countdown_t mm_countdown;
static bool ignore_motion; // Flag to ignore the encoder
#if ENABLED(FILAMENT_SWITCH_AND_MOTION)
static bool ignore_motion; // Flag to ignore the encoder
#endif
public:
static float runout_distance_mm;
@ -385,13 +386,17 @@ class FilamentSensorBase {
static float motion_distance_mm;
#endif
static void set_ignore_motion(const bool ignore=true) { ignore_motion = ignore; }
static void set_ignore_motion(const bool ignore=true) {
UNUSED(ignore);
TERN_(FILAMENT_SWITCH_AND_MOTION, ignore_motion = ignore);
}
static void reset() {
for (uint8_t i = 0; i < NUM_RUNOUT_SENSORS; ++i) filament_present(i);
#if ENABLED(FILAMENT_SWITCH_AND_MOTION)
for (uint8_t i = 0; i < NUM_MOTION_SENSORS; ++i) filament_motion_present(i);
#endif
set_ignore_motion(false);
}
static void run() {
@ -413,13 +418,24 @@ class FilamentSensorBase {
// Get runout status for all presence sensors and motion sensors
static runout_flags_t has_run_out() {
runout_flags_t runout_flags{0};
// Runout based on filament presence
for (uint8_t i = 0; i < NUM_RUNOUT_SENSORS; ++i) if (mm_countdown.runout[i] < 0) runout_flags.set(i);
// Runout based on filament motion
#if ENABLED(FILAMENT_SWITCH_AND_MOTION)
if (!ignore_motion)
for (uint8_t i = 0; i < NUM_MOTION_SENSORS; ++i) if (mm_countdown.motion[i] < 0) runout_flags.set(i);
// Runout based on filament motion
if (!ignore_motion) {
for (uint8_t i = 0; i < NUM_MOTION_SENSORS; ++i) {
if (mm_countdown.motion[i] < 0) {
runout_flags.set(i);
mm_countdown.runout[i] = -1; // For a filament jam don't wait for runout_distance_mm!
}
}
}
#endif
// Runout based on filament presence
for (uint8_t i = 0; i < NUM_RUNOUT_SENSORS; ++i)
if (mm_countdown.runout[i] < 0)
runout_flags.set(i);
return runout_flags;
}
@ -471,8 +487,8 @@ class FilamentSensorBase {
if (mm_countdown.runout_reset[e]) filament_present(e); // Reset pending. Try to reset.
}
// Apply E distance to motion countdown, reset if flagged
#if ENABLED(FILAMENT_SWITCH_AND_MOTION)
// Apply E distance to motion countdown, reset if flagged
if (!ignore_motion && e < NUM_MOTION_SENSORS) {
mm_countdown.motion[e] -= mm;
if (mm_countdown.motion_reset[e]) filament_motion_present(e); // Reset pending. Try to reset.
@ -484,7 +500,7 @@ class FilamentSensorBase {
static void init_for_restart(const bool onoff=true) {
UNUSED(onoff);
#if ENABLED(FILAMENT_SWITCH_AND_MOTION)
reset();
reset(); // also calls set_ignore_motion(false)
set_ignore_motion(!onoff);
#endif
}

View file

@ -54,13 +54,13 @@ class SpindleLaser {
public:
static CutterMode cutter_mode;
static constexpr uint8_t pct_to_ocr(const_float_t pct) { return uint8_t(PCT_TO_PWM(pct)); }
static constexpr uint8_t pct_to_ocr(const float pct) { return uint8_t(PCT_TO_PWM(pct)); }
// cpower = configured values (e.g., SPEED_POWER_MAX)
// Convert configured power range to a percentage
static constexpr cutter_cpower_t power_floor = TERN(CUTTER_POWER_RELATIVE, SPEED_POWER_MIN, 0);
static constexpr uint8_t cpwr_to_pct(const cutter_cpower_t cpwr) {
return cpwr ? round(100.0f * (cpwr - power_floor) / (SPEED_POWER_MAX - power_floor)) : 0;
return cpwr ? LROUND(100.0f * (cpwr - power_floor) / (SPEED_POWER_MAX - power_floor)) : 0;
}
// Convert config defines from RPM to %, angle or PWM when in Spindle mode
@ -164,7 +164,7 @@ public:
*/
static cutter_power_t power_to_range(const cutter_power_t pwr, const uint8_t pwrUnit=_CUTTER_POWER(CUTTER_POWER_UNIT)) {
static constexpr float
min_pct = TERN(CUTTER_POWER_RELATIVE, 0, TERN(SPINDLE_FEATURE, round(100.0f * (SPEED_POWER_MIN) / (SPEED_POWER_MAX)), SPEED_POWER_MIN)),
min_pct = TERN(CUTTER_POWER_RELATIVE, 0, TERN(SPINDLE_FEATURE, roundf(100.0f * (SPEED_POWER_MIN) / (SPEED_POWER_MAX)), SPEED_POWER_MIN)),
max_pct = TERN(SPINDLE_FEATURE, 100, SPEED_POWER_MAX);
if (pwr <= 0) return 0;
cutter_power_t upwr;

View file

@ -31,7 +31,7 @@ static uint32_t axis_plug_backward = 0;
void stepper_driver_backward_error(FSTR_P const fstr) {
SERIAL_ERROR_START();
SERIAL_ECHOLN(fstr, F(" driver is backward!"));
ui.status_printf(2, F(S_FMT S_FMT), FTOP(fstr), GET_TEXT_F(MSG_DRIVER_BACKWARD));
ui.status_printf(2, F(S_FMT S_FMT), FTOP(fstr), GET_TEXT(MSG_DRIVER_BACKWARD));
}
void stepper_driver_backward_check() {

View file

@ -89,7 +89,9 @@
#if HAS_TMCX1X0
static uint32_t get_pwm_scale(TMC2130Stepper &st) { return st.PWM_SCALE(); }
#if ENABLED(TMC_DEBUG)
static uint32_t get_pwm_scale(TMC2130Stepper &st) { return st.PWM_SCALE(); }
#endif
static TMC_driver_data get_driver_data(TMC2130Stepper &st) {
constexpr uint8_t OT_bp = 25, OTPW_bp = 26;
@ -148,7 +150,9 @@
#if HAS_DRIVER(TMC2240)
static uint32_t get_pwm_scale(TMC2240Stepper &st) { return st.PWM_SCALE(); }
#if ENABLED(TMC_DEBUG)
static uint32_t get_pwm_scale(TMC2240Stepper &st) { return st.PWM_SCALE(); }
#endif
static TMC_driver_data get_driver_data(TMC2240Stepper &st) {
constexpr uint8_t OT_bp = 25, OTPW_bp = 26;
@ -207,7 +211,9 @@
#if HAS_TMC220x
static uint32_t get_pwm_scale(TMC2208Stepper &st) { return st.pwm_scale_sum(); }
#if ENABLED(TMC_DEBUG)
static uint32_t get_pwm_scale(TMC2208Stepper &st) { return st.pwm_scale_sum(); }
#endif
static TMC_driver_data get_driver_data(TMC2208Stepper &st) {
constexpr uint8_t OTPW_bp = 0, OT_bp = 1;
@ -242,7 +248,9 @@
#if HAS_DRIVER(TMC2660)
static uint32_t get_pwm_scale(TMC2660Stepper) { return 0; }
#if ENABLED(TMC_DEBUG)
static uint32_t get_pwm_scale(TMC2660Stepper) { return 0; }
#endif
static TMC_driver_data get_driver_data(TMC2660Stepper &st) {
constexpr uint8_t OT_bp = 1, OTPW_bp = 2;
@ -965,14 +973,14 @@
TMC_REPORT("[mm/s]\t", TMC_TPWMTHRS_MMS);
TMC_REPORT("OT prewarn", TMC_DEBUG_OTPW);
#if ENABLED(MONITOR_DRIVER_STATUS)
TMC_REPORT("triggered\n OTP\t", TMC_OTPW_TRIGGERED);
TMC_REPORT("OTPW trig.\t", TMC_OTPW_TRIGGERED);
#endif
#if HAS_TMC220x
TMC_REPORT("pwm scale sum", TMC_PWM_SCALE_SUM);
TMC_REPORT("pwm scale auto", TMC_PWM_SCALE_AUTO);
TMC_REPORT("pwm offset auto", TMC_PWM_OFS_AUTO);
TMC_REPORT("pwm grad auto", TMC_PWM_GRAD_AUTO);
TMC_REPORT("pwm scale sum", TMC_PWM_SCALE_SUM);
TMC_REPORT("pwm scale auto", TMC_PWM_SCALE_AUTO);
TMC_REPORT("pwm offset auto", TMC_PWM_OFS_AUTO);
TMC_REPORT("pwm grad auto", TMC_PWM_GRAD_AUTO);
#endif
TMC_REPORT("off time", TMC_TOFF);

View file

@ -53,7 +53,7 @@ void XATC::print_points() {
SERIAL_EOL();
}
float lerp(const_float_t t, const_float_t a, const_float_t b) { return a + t * (b - a); }
float lerp(const float t, const float a, const float b) { return a + t * (b - a); }
float XATC::compensation(const xy_pos_t &raw) {
if (!enabled) return 0;

View file

@ -170,7 +170,7 @@ float g26_random_deviation = 0.0;
#endif
void move_to(const_float_t rx, const_float_t ry, const_float_t z, const_float_t e_delta) {
void move_to(const float rx, const float ry, const float z, const float e_delta) {
static float last_z = -999.99;
const xy_pos_t dest = { rx, ry };
@ -196,7 +196,7 @@ void move_to(const_float_t rx, const_float_t ry, const_float_t z, const_float_t
prepare_internal_move_to_destination(fr_mm_s);
}
void move_to(const xyz_pos_t &where, const_float_t de) { move_to(where.x, where.y, where.z, de); }
void move_to(const xyz_pos_t &where, const float de) { move_to(where.x, where.y, where.z, de); }
typedef struct {
float extrusion_multiplier = EXTRUSION_MULTIPLIER,

View file

@ -59,7 +59,7 @@
#define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE)
#include "../../../core/debug_out.h"
#if DISABLED(PROBE_MANUALLY) && FT_MOTION_DISABLE_FOR_PROBING
#if DISABLED(PROBE_MANUALLY) && ENABLED(FT_MOTION)
#include "../../../module/ft_motion.h"
#endif
@ -275,8 +275,9 @@ G29_TYPE GcodeSuite::G29() {
// Set and report "probing" state to host
TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_PROBE, false));
#if DISABLED(PROBE_MANUALLY) && FT_MOTION_DISABLE_FOR_PROBING
FTMotionDisableInScope FT_Disabler; // Disable Fixed-Time Motion for probing
#if DISABLED(PROBE_MANUALLY) && ENABLED(FT_MOTION)
// Potentially disable Fixed-Time Motion for probing
FTMotionDisableInScope FT_Disabler;
#endif
/**
@ -708,7 +709,7 @@ G29_TYPE GcodeSuite::G29() {
if (TERN0(IS_KINEMATIC, !probe.can_reach(abl.probePos))) continue;
if (abl.verbose_level) SERIAL_ECHOLNPGM("Probing mesh point ", pt_index, "/", abl.abl_points, ".");
TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/%i"), GET_TEXT_F(MSG_PROBING_POINT), int(pt_index), int(abl.abl_points)));
TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_POINT), int(pt_index), int(abl.abl_points)));
#if ENABLED(BD_SENSOR_PROBE_NO_STOP)
if (PR_INNER_VAR == inStart) {
@ -813,7 +814,7 @@ G29_TYPE GcodeSuite::G29() {
for (uint8_t i = 0; i < 3; ++i) {
if (abl.verbose_level) SERIAL_ECHOLNPGM("Probing point ", i + 1, "/3.");
TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/3"), GET_TEXT_F(MSG_PROBING_POINT), int(i + 1)));
TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/3"), GET_TEXT(MSG_PROBING_POINT), int(i + 1)));
// Retain the last probe position
abl.probePos = xy_pos_t(points[i]);

View file

@ -45,7 +45,7 @@
#define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE)
#include "../../../core/debug_out.h"
#if FT_MOTION_DISABLE_FOR_PROBING
#if ENABLED(FT_MOTION)
#include "../../module/ft_motion.h"
#endif
@ -67,9 +67,8 @@ inline void echo_not_entered(const char c) { SERIAL_CHAR(c); SERIAL_ECHOLNPGM("
*/
void GcodeSuite::G29() {
#if FT_MOTION_DISABLE_FOR_PROBING
FTMotionDisableInScope FT_Disabler; // Disable Fixed-Time Motion for probing
#endif
// Potentially disable Fixed-Time Motion for probing
TERN_(FT_MOTION, FTMotionDisableInScope FT_Disabler);
DEBUG_SECTION(log_G29, "G29", true);
@ -261,7 +260,7 @@ void GcodeSuite::G29() {
if (state == MeshNext) {
SERIAL_ECHOLNPGM("MBL G29 point ", _MIN(mbl_probe_index, GRID_MAX_POINTS), " of ", GRID_MAX_POINTS);
if (mbl_probe_index > 0) TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/%i"), GET_TEXT_F(MSG_PROBING_POINT), _MIN(mbl_probe_index, GRID_MAX_POINTS), int(GRID_MAX_POINTS)));
if (mbl_probe_index > 0) TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_POINT), _MIN(mbl_probe_index, GRID_MAX_POINTS), int(GRID_MAX_POINTS)));
}
report_current_position();

View file

@ -52,7 +52,7 @@
#include "../../feature/bltouch.h"
#endif
#if FT_MOTION_DISABLE_FOR_PROBING
#if ENABLED(FT_MOTION)
#include "../../module/ft_motion.h"
#endif
@ -130,9 +130,8 @@
inline void home_z_safely() {
#if FT_MOTION_DISABLE_FOR_PROBING
FTMotionDisableInScope FT_Disabler; // Disable Fixed-Time Motion for homing
#endif
// Potentially disable Fixed-Time Motion for homing
TERN_(FT_MOTION, FTMotionDisableInScope FT_Disabler);
DEBUG_SECTION(log_G28, "home_z_safely", DEBUGGING(LEVELING));
@ -290,9 +289,8 @@ void GcodeSuite::G28() {
motion_state_t saved_motion_state = begin_slow_homing();
#endif
#if FT_MOTION_DISABLE_FOR_PROBING
FTMotionDisableInScope FT_Disabler; // Disable Fixed-Time Motion for homing
#endif
// Potentially disable Fixed-Time Motion for homing
TERN_(FT_MOTION, FTMotionDisableInScope FT_Disabler);
// Always home with tool 0 active
#if HAS_MULTI_HOTEND

View file

@ -87,7 +87,7 @@ void ac_cleanup() {
TERN_(HAS_BED_PROBE, probe.use_probing_tool(false));
}
void print_signed_float(FSTR_P const prefix, const_float_t f) {
void print_signed_float(FSTR_P const prefix, const float f) {
SERIAL_ECHO(F(" "), prefix, C(':'));
serial_offset(f);
}
@ -154,7 +154,7 @@ static float std_dev_points(float z_pt[NPP + 1], const bool _0p_cal, const bool
S2 += sq(z_pt[rad]);
N++;
}
return LROUND(SQRT(S2 / N) * 1000.0f) / 1000.0f + 0.00001f;
return LROUND(SQRT(S2 / N) * 1000.0f) * 0.001f + 0.00001f;
}
}
return 0.00001f;
@ -315,7 +315,7 @@ static void calc_kinematics_diff_probe_points(float z_pt[NPP + 1], const float d
static float auto_tune_h(const float dcr) {
const float r_quot = dcr / delta_radius;
return RECIPROCAL(r_quot / (2.0f / 3.0f)); // (2/3)/CR
return RECIPROCAL(r_quot * (3.0f / 2.0f)); // (2/3)/CR
}
static float auto_tune_r(const float dcr) {
@ -490,7 +490,7 @@ void GcodeSuite::G33() {
float z_at_pt[NPP + 1] = { 0.0f };
test_precision = zero_std_dev_old != 999.0f ? (zero_std_dev + zero_std_dev_old) / 2.0f : zero_std_dev;
test_precision = zero_std_dev_old != 999.0f ? (zero_std_dev + zero_std_dev_old) * 0.5f : zero_std_dev;
iterations++;
// Probe the points
@ -527,7 +527,7 @@ void GcodeSuite::G33() {
* - Definition of the matrix scaling parameters
* - Matrices for 4 and 7 point calibration
*/
#define ZP(N,I) ((N) * z_at_pt[I] / 4.0f) // 4.0 = divider to normalize to integers
#define ZP(N,I) ((N) * z_at_pt[I] * 0.25f) // 4.0 = divider to normalize to integers
#define Z12(I) ZP(12, I)
#define Z4(I) ZP(4, I)
#define Z2(I) ZP(2, I)

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