From 50e4545255605eb506c20eb107270038b0fe7bdb Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 29 Sep 2019 04:25:39 -0500 Subject: [PATCH] Add custom types for position (#15204) --- Marlin/Configuration_adv.h | 4 +- Marlin/src/Marlin.cpp | 12 +- Marlin/src/core/enum.h | 63 --- Marlin/src/core/macros.h | 7 +- Marlin/src/core/serial.cpp | 7 +- Marlin/src/core/serial.h | 12 +- Marlin/src/core/types.h | 486 +++++++++++++++++ Marlin/src/core/utility.cpp | 50 +- Marlin/src/core/utility.h | 26 +- Marlin/src/feature/I2CPositionEncoder.cpp | 39 +- Marlin/src/feature/I2CPositionEncoder.h | 2 - Marlin/src/feature/backlash.cpp | 24 +- Marlin/src/feature/backlash.h | 8 +- Marlin/src/feature/bedlevel/abl/abl.cpp | 162 +++--- Marlin/src/feature/bedlevel/abl/abl.h | 12 +- Marlin/src/feature/bedlevel/bedlevel.cpp | 32 +- Marlin/src/feature/bedlevel/bedlevel.h | 22 +- .../bedlevel/mbl/mesh_bed_leveling.cpp | 55 +- .../feature/bedlevel/mbl/mesh_bed_leveling.h | 34 +- Marlin/src/feature/bedlevel/ubl/ubl.cpp | 5 +- Marlin/src/feature/bedlevel/ubl/ubl.h | 47 +- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 490 +++++++++--------- .../src/feature/bedlevel/ubl/ubl_motion.cpp | 355 ++++++------- Marlin/src/feature/dac/dac_mcp4728.cpp | 6 +- Marlin/src/feature/dac/dac_mcp4728.h | 4 +- Marlin/src/feature/dac/stepper_dac.cpp | 8 +- Marlin/src/feature/dac/stepper_dac.h | 2 +- Marlin/src/feature/fwretract.cpp | 14 +- Marlin/src/feature/joystick.cpp | 29 +- Marlin/src/feature/joystick.h | 4 +- Marlin/src/feature/pause.cpp | 22 +- Marlin/src/feature/pause.h | 2 +- Marlin/src/feature/power_loss_recovery.cpp | 32 +- Marlin/src/feature/power_loss_recovery.h | 6 +- Marlin/src/feature/prusa_MMU2/mmu2.cpp | 16 +- Marlin/src/feature/runout.h | 4 +- Marlin/src/feature/tmc_util.h | 4 +- Marlin/src/gcode/bedlevel/G26.cpp | 297 +++++------ Marlin/src/gcode/bedlevel/G42.cpp | 11 +- Marlin/src/gcode/bedlevel/M420.cpp | 11 +- Marlin/src/gcode/bedlevel/abl/G29.cpp | 316 +++++------ Marlin/src/gcode/bedlevel/mbl/G29.cpp | 8 +- Marlin/src/gcode/bedlevel/ubl/M421.cpp | 19 +- Marlin/src/gcode/calibrate/G28.cpp | 50 +- Marlin/src/gcode/calibrate/G33.cpp | 166 +++--- Marlin/src/gcode/calibrate/G34_M422.cpp | 41 +- Marlin/src/gcode/calibrate/G425.cpp | 154 +++--- Marlin/src/gcode/calibrate/M48.cpp | 34 +- Marlin/src/gcode/calibrate/M665.cpp | 22 +- Marlin/src/gcode/config/M200-M205.cpp | 10 +- Marlin/src/gcode/config/M218.cpp | 14 +- Marlin/src/gcode/config/M92.cpp | 2 +- Marlin/src/gcode/control/M211.cpp | 12 +- Marlin/src/gcode/control/M605.cpp | 8 +- Marlin/src/gcode/feature/camera/M240.cpp | 32 +- Marlin/src/gcode/feature/pause/M125.cpp | 5 +- Marlin/src/gcode/feature/pause/M600.cpp | 6 +- Marlin/src/gcode/feature/pause/M701_M702.cpp | 13 +- Marlin/src/gcode/feature/trinamic/M122.cpp | 10 +- .../src/gcode/feature/trinamic/M911-M914.cpp | 16 +- Marlin/src/gcode/gcode.cpp | 19 +- Marlin/src/gcode/gcode.h | 2 +- Marlin/src/gcode/geometry/G53-G59.cpp | 4 +- Marlin/src/gcode/geometry/G92.cpp | 4 +- Marlin/src/gcode/geometry/M206_M428.cpp | 2 +- Marlin/src/gcode/host/M114.cpp | 40 +- Marlin/src/gcode/motion/G0_G1.cpp | 10 +- Marlin/src/gcode/motion/G2_G3.cpp | 73 ++- Marlin/src/gcode/motion/G5.cpp | 16 +- Marlin/src/gcode/motion/M290.cpp | 22 +- Marlin/src/gcode/probe/G30.cpp | 11 +- Marlin/src/gcode/probe/G38.cpp | 7 +- Marlin/src/gcode/probe/M851.cpp | 12 +- Marlin/src/gcode/scara/M360-M364.cpp | 2 +- Marlin/src/inc/Conditionals_post.h | 11 +- Marlin/src/inc/MarlinConfig.h | 2 +- Marlin/src/inc/MarlinConfigPre.h | 1 - Marlin/src/inc/SanityCheck.h | 7 +- Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp | 20 +- Marlin/src/lcd/dogm/status_screen_DOGM.cpp | 7 +- .../lcd/dogm/status_screen_lite_ST7920.cpp | 12 +- .../src/lcd/dogm/status_screen_lite_ST7920.h | 3 +- Marlin/src/lcd/dogm/ultralcd_DOGM.cpp | 6 +- .../lib/dgus/DGUSDisplayDefinition.cpp | 8 +- .../lib/lulzbot/screens/bio_status_screen.cpp | 33 +- .../screens/change_filament_screen.cpp | 4 +- .../lib/lulzbot/screens/move_axis_screen.cpp | 4 +- .../lulzbot/screens/nudge_nozzle_screen.cpp | 23 +- .../lib/lulzbot/screens/screen_data.h | 2 +- Marlin/src/lcd/extensible_ui/ui_api.cpp | 74 ++- Marlin/src/lcd/extensible_ui/ui_api.h | 9 +- Marlin/src/lcd/menu/menu.cpp | 18 +- Marlin/src/lcd/menu/menu_advanced.cpp | 4 +- Marlin/src/lcd/menu/menu_bed_corners.cpp | 14 +- Marlin/src/lcd/menu/menu_bed_leveling.cpp | 6 +- Marlin/src/lcd/menu/menu_configuration.cpp | 10 +- Marlin/src/lcd/menu/menu_delta_calibrate.cpp | 38 +- Marlin/src/lcd/menu/menu_motion.cpp | 20 +- Marlin/src/lcd/menu/menu_ubl.cpp | 15 +- Marlin/src/lcd/ultralcd.cpp | 2 +- Marlin/src/lcd/ultralcd.h | 1 - Marlin/src/libs/L6470/L6470_Marlin.cpp | 26 +- Marlin/src/libs/least_squares_fit.h | 6 + Marlin/src/libs/nozzle.cpp | 77 ++- Marlin/src/libs/nozzle.h | 19 +- Marlin/src/libs/point_t.h | 55 -- Marlin/src/libs/vector_3.cpp | 94 ++-- Marlin/src/libs/vector_3.h | 35 +- Marlin/src/module/configuration_store.cpp | 147 +++--- Marlin/src/module/delta.cpp | 85 ++- Marlin/src/module/delta.h | 41 +- Marlin/src/module/motion.cpp | 326 ++++++------ Marlin/src/module/motion.h | 99 ++-- Marlin/src/module/planner.cpp | 432 +++++++-------- Marlin/src/module/planner.h | 102 ++-- Marlin/src/module/planner_bezier.cpp | 56 +- Marlin/src/module/planner_bezier.h | 9 +- Marlin/src/module/probe.cpp | 80 ++- Marlin/src/module/probe.h | 18 +- Marlin/src/module/scara.cpp | 43 +- Marlin/src/module/scara.h | 6 +- Marlin/src/module/stepper.cpp | 109 ++-- Marlin/src/module/stepper.h | 26 +- Marlin/src/module/tool_change.cpp | 175 +++---- Marlin/src/module/tool_change.h | 3 +- config/default/Configuration_adv.h | 4 +- .../3DFabXYZ/Migbot/Configuration_adv.h | 4 +- .../ADIMLab/Gantry v1/Configuration_adv.h | 4 +- .../ADIMLab/Gantry v2/Configuration_adv.h | 4 +- .../AlephObjects/TAZ4/Configuration_adv.h | 4 +- .../Alfawise/U20-bltouch/Configuration_adv.h | 4 +- .../examples/Alfawise/U20/Configuration_adv.h | 4 +- .../AliExpress/UM2pExt/Configuration_adv.h | 4 +- config/examples/Anet/A2/Configuration_adv.h | 4 +- .../examples/Anet/A2plus/Configuration_adv.h | 4 +- config/examples/Anet/A6/Configuration_adv.h | 4 +- config/examples/Anet/A8/Configuration_adv.h | 4 +- .../examples/Anet/A8plus/Configuration_adv.h | 4 +- config/examples/Anet/E16/Configuration_adv.h | 4 +- .../examples/AnyCubic/i3/Configuration_adv.h | 4 +- config/examples/ArmEd/Configuration_adv.h | 4 +- .../BIBO/TouchX/cyclops/Configuration_adv.h | 4 +- .../BIBO/TouchX/default/Configuration_adv.h | 4 +- .../examples/BQ/Hephestos/Configuration_adv.h | 4 +- .../BQ/Hephestos_2/Configuration_adv.h | 4 +- config/examples/BQ/WITBOX/Configuration_adv.h | 4 +- config/examples/Cartesio/Configuration_adv.h | 4 +- .../Creality/CR-10/Configuration_adv.h | 4 +- .../Creality/CR-10S/Configuration_adv.h | 4 +- .../Creality/CR-10_5S/Configuration_adv.h | 4 +- .../Creality/CR-10mini/Configuration_adv.h | 4 +- .../Creality/CR-20 Pro/Configuration_adv.h | 4 +- .../Creality/CR-20/Configuration_adv.h | 4 +- .../Creality/CR-8/Configuration_adv.h | 4 +- .../Creality/Ender-2/Configuration_adv.h | 4 +- .../Creality/Ender-3/Configuration_adv.h | 4 +- .../Creality/Ender-4/Configuration_adv.h | 4 +- .../Creality/Ender-5/Configuration_adv.h | 4 +- .../Dagoma/Disco Ultimate/Configuration_adv.h | 4 +- .../Sidewinder X1/Configuration_adv.h | 4 +- .../examples/Einstart-S/Configuration_adv.h | 4 +- .../FYSETC/AIO_II/Configuration_adv.h | 4 +- .../Cheetah 1.2/BLTouch/Configuration_adv.h | 4 +- .../Cheetah 1.2/base/Configuration_adv.h | 4 +- .../Cheetah/BLTouch/Configuration_adv.h | 4 +- .../FYSETC/Cheetah/base/Configuration_adv.h | 4 +- .../examples/FYSETC/F6_13/Configuration_adv.h | 4 +- config/examples/Felix/Configuration_adv.h | 4 +- .../FlashForge/CreatorPro/Configuration_adv.h | 4 +- .../FolgerTech/i3-2020/Configuration_adv.h | 4 +- .../Formbot/Raptor/Configuration_adv.h | 4 +- .../Formbot/T_Rex_2+/Configuration_adv.h | 4 +- .../Formbot/T_Rex_3/Configuration_adv.h | 4 +- .../examples/Geeetech/A10/Configuration_adv.h | 4 +- .../Geeetech/A10M/Configuration_adv.h | 4 +- .../Geeetech/A20M/Configuration_adv.h | 4 +- .../Geeetech/MeCreator2/Configuration_adv.h | 4 +- .../Prusa i3 Pro C/Configuration_adv.h | 4 +- .../Prusa i3 Pro W/Configuration_adv.h | 4 +- config/examples/HMS434/Configuration_adv.h | 4 +- .../Infitary/i3-M508/Configuration_adv.h | 4 +- .../examples/JGAurora/A1/Configuration_adv.h | 4 +- .../examples/JGAurora/A5/Configuration_adv.h | 4 +- .../examples/JGAurora/A5S/Configuration_adv.h | 4 +- .../examples/MakerParts/Configuration_adv.h | 4 +- .../examples/Malyan/M150/Configuration_adv.h | 4 +- .../examples/Malyan/M200/Configuration_adv.h | 4 +- .../Micromake/C1/enhanced/Configuration_adv.h | 4 +- config/examples/Mks/Robin/Configuration_adv.h | 4 +- config/examples/Mks/Sbase/Configuration_adv.h | 4 +- .../RapideLite/RL200/Configuration_adv.h | 4 +- config/examples/RigidBot/Configuration_adv.h | 4 +- config/examples/SCARA/Configuration_adv.h | 4 +- .../Black_STM32F407VET6/Configuration_adv.h | 4 +- .../examples/Sanguinololu/Configuration_adv.h | 4 +- .../Tevo/Michelangelo/Configuration_adv.h | 4 +- .../Tevo/Tarantula Pro/Configuration_adv.h | 4 +- .../Tornado/V1 (MKS Base)/Configuration_adv.h | 4 +- .../V2 (MKS GEN-L)/Configuration_adv.h | 4 +- config/examples/TheBorg/Configuration_adv.h | 4 +- config/examples/TinyBoy2/Configuration_adv.h | 4 +- .../examples/Tronxy/X3A/Configuration_adv.h | 4 +- .../Tronxy/X5S-2E/Configuration_adv.h | 4 +- .../UltiMachine/Archim1/Configuration_adv.h | 4 +- .../UltiMachine/Archim2/Configuration_adv.h | 4 +- .../examples/VORONDesign/Configuration_adv.h | 4 +- .../Velleman/K8200/Configuration_adv.h | 4 +- .../Velleman/K8400/Configuration_adv.h | 4 +- .../WASP/PowerWASP/Configuration_adv.h | 4 +- .../Wanhao/Duplicator 6/Configuration_adv.h | 4 +- .../Duplicator i3 Mini/Configuration_adv.h | 4 +- .../delta/Anycubic/Kossel/Configuration_adv.h | 4 +- .../Dreammaker/Overlord/Configuration_adv.h | 4 +- .../Overlord_Pro/Configuration_adv.h | 4 +- .../FLSUN/auto_calibrate/Configuration_adv.h | 4 +- .../delta/FLSUN/kossel/Configuration_adv.h | 4 +- .../FLSUN/kossel_mini/Configuration_adv.h | 4 +- .../Geeetech/Rostock 301/Configuration_adv.h | 4 +- .../delta/MKS/SBASE/Configuration_adv.h | 4 +- .../Tevo Little Monster/Configuration_adv.h | 4 +- .../delta/generic/Configuration_adv.h | 4 +- .../delta/kossel_mini/Configuration_adv.h | 4 +- .../delta/kossel_xl/Configuration_adv.h | 4 +- .../gCreate/gMax1.5+/Configuration_adv.h | 4 +- config/examples/makibox/Configuration_adv.h | 4 +- .../tvrrug/Round2/Configuration_adv.h | 4 +- config/examples/wt150/Configuration_adv.h | 4 +- 227 files changed, 3151 insertions(+), 3268 deletions(-) delete mode 100644 Marlin/src/core/enum.h create mode 100644 Marlin/src/core/types.h delete mode 100644 Marlin/src/libs/point_t.h diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index fa45ad078..9a8682ca1 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/Marlin/src/Marlin.cpp b/Marlin/src/Marlin.cpp index 89501e9bf..d21570198 100644 --- a/Marlin/src/Marlin.cpp +++ b/Marlin/src/Marlin.cpp @@ -582,10 +582,10 @@ void manage_inactivity(const bool ignore_stepper_queue/*=false*/) { } #endif // !SWITCHING_EXTRUDER - const float olde = current_position[E_AXIS]; - current_position[E_AXIS] += EXTRUDER_RUNOUT_EXTRUDE; - planner.buffer_line(current_position, MMM_TO_MMS(EXTRUDER_RUNOUT_SPEED), active_extruder); - current_position[E_AXIS] = olde; + const float olde = current_position.e; + current_position.e += EXTRUDER_RUNOUT_EXTRUDE; + line_to_current_position(MMM_TO_MMS(EXTRUDER_RUNOUT_SPEED)); + current_position.e = olde; planner.set_e_position_mm(olde); planner.synchronize(); @@ -629,7 +629,7 @@ void manage_inactivity(const bool ignore_stepper_queue/*=false*/) { if (delayed_move_time && ELAPSED(ms, delayed_move_time + 1000UL) && IsRunning()) { // travel moves have been received so enact them delayed_move_time = 0xFFFFFFFFUL; // force moves to be done - set_destination_from_current(); + destination = current_position; prepare_move_to_destination(); } #endif @@ -1002,7 +1002,7 @@ void setup() { #if HAS_M206_COMMAND // Initialize current position based on home_offset - LOOP_XYZ(a) current_position[a] += home_offset[a]; + current_position += home_offset; #endif // Vital to init stepper/planner equivalent for current_position diff --git a/Marlin/src/core/enum.h b/Marlin/src/core/enum.h deleted file mode 100644 index 15118f7b2..000000000 --- a/Marlin/src/core/enum.h +++ /dev/null @@ -1,63 +0,0 @@ -/** - * Marlin 3D Printer Firmware - * Copyright (c) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * - * Based on Sprinter and grbl. - * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ -#pragma once - -/** - * Axis indices as enumerated constants - * - * - X_AXIS, Y_AXIS, and Z_AXIS should be used for axes in Cartesian space - * - A_AXIS, B_AXIS, and C_AXIS should be used for Steppers, corresponding to XYZ on Cartesians - * - X_HEAD, Y_HEAD, and Z_HEAD should be used for Steppers on Core kinematics - */ -enum AxisEnum : unsigned char { - X_AXIS = 0, - A_AXIS = 0, - Y_AXIS = 1, - B_AXIS = 1, - Z_AXIS = 2, - C_AXIS = 2, - E_AXIS = 3, - X_HEAD = 4, - Y_HEAD = 5, - Z_HEAD = 6, - E0_AXIS = 3, - E1_AXIS = 4, - E2_AXIS = 5, - E3_AXIS = 6, - E4_AXIS = 7, - E5_AXIS = 8, - ALL_AXES = 0xFE, - NO_AXIS = 0xFF -}; - -#define LOOP_S_LE_N(VAR, S, N) for (uint8_t VAR=(S); VAR<=(N); VAR++) -#define LOOP_S_L_N(VAR, S, N) for (uint8_t VAR=(S); VAR<(N); VAR++) -#define LOOP_LE_N(VAR, N) LOOP_S_LE_N(VAR, 0, N) -#define LOOP_L_N(VAR, N) LOOP_S_L_N(VAR, 0, N) - -#define LOOP_NA(VAR) LOOP_L_N(VAR, NUM_AXIS) -#define LOOP_XYZ(VAR) LOOP_S_LE_N(VAR, X_AXIS, Z_AXIS) -#define LOOP_XYZE(VAR) LOOP_S_LE_N(VAR, X_AXIS, E_AXIS) -#define LOOP_XYZE_N(VAR) LOOP_S_L_N(VAR, X_AXIS, XYZE_N) -#define LOOP_ABC(VAR) LOOP_S_LE_N(VAR, A_AXIS, C_AXIS) -#define LOOP_ABCE(VAR) LOOP_S_LE_N(VAR, A_AXIS, E_AXIS) -#define LOOP_ABCE_N(VAR) LOOP_S_L_N(VAR, A_AXIS, XYZE_N) diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index faf3859f1..c13b34260 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -26,6 +26,7 @@ #define XYZE 4 #define ABC 3 #define XYZ 3 +#define XY 2 #define _AXIS(A) (A##_AXIS) @@ -252,12 +253,6 @@ #define DECREMENT_(n) DEC_##n #define DECREMENT(n) DECREMENT_(n) -// Feedrate -typedef float feedRate_t; -#define MMM_TO_MMS(MM_M) ((MM_M)/60.0f) -#define MMS_TO_MMM(MM_S) ((MM_S)*60.0f) -#define MMS_SCALED(V) ((V) * 0.01f * feedrate_percentage) - #define NOOP (void(0)) #define CEILING(x,y) (((x) + (y) - 1) / (y)) diff --git a/Marlin/src/core/serial.cpp b/Marlin/src/core/serial.cpp index a468802ec..2369c3acb 100644 --- a/Marlin/src/core/serial.cpp +++ b/Marlin/src/core/serial.cpp @@ -22,7 +22,6 @@ #include "serial.h" #include "language.h" -#include "enum.h" uint8_t marlin_debug_flags = MARLIN_DEBUG_NONE; @@ -68,12 +67,8 @@ void print_bin(const uint16_t val) { } } -void print_xyz(PGM_P const prefix, PGM_P const suffix, const float &x, const float &y, const float &z) { +void print_xyz(const float &x, const float &y, const float &z, PGM_P const prefix/*=nullptr*/, PGM_P const suffix/*=nullptr*/) { serialprintPGM(prefix); SERIAL_ECHOPAIR(" " MSG_X, x, " " MSG_Y, y, " " MSG_Z, z); if (suffix) serialprintPGM(suffix); else SERIAL_EOL(); } - -void print_xyz(PGM_P const prefix, PGM_P const suffix, const float xyz[]) { - print_xyz(prefix, suffix, xyz[X_AXIS], xyz[Y_AXIS], xyz[Z_AXIS]); -} diff --git a/Marlin/src/core/serial.h b/Marlin/src/core/serial.h index f1b18c214..f4c2570ca 100644 --- a/Marlin/src/core/serial.h +++ b/Marlin/src/core/serial.h @@ -213,7 +213,11 @@ void serial_spaces(uint8_t count); void print_bin(const uint16_t val); -void print_xyz(PGM_P const prefix, PGM_P const suffix, const float xyz[]); -void print_xyz(PGM_P const prefix, PGM_P const suffix, const float &x, const float &y, const float &z); -#define SERIAL_POS(SUFFIX,VAR) do { print_xyz(PSTR(" " STRINGIFY(VAR) "="), PSTR(" : " SUFFIX "\n"), VAR); }while(0) -#define SERIAL_XYZ(PREFIX,V...) do { print_xyz(PSTR(PREFIX), nullptr, V); }while(0) +void print_xyz(const float &x, const float &y, const float &z, PGM_P const prefix=nullptr, PGM_P const suffix=nullptr); + +inline void print_xyz(const xyz_pos_t &xyz, PGM_P const prefix=nullptr, PGM_P const suffix=nullptr) { + print_xyz(xyz.x, xyz.y, xyz.z, prefix, suffix); +} + +#define SERIAL_POS(SUFFIX,VAR) do { print_xyz(VAR, PSTR(" " STRINGIFY(VAR) "="), PSTR(" : " SUFFIX "\n")); }while(0) +#define SERIAL_XYZ(PREFIX,V...) do { print_xyz(V, PSTR(PREFIX), nullptr); }while(0) diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h new file mode 100644 index 000000000..567b35c8b --- /dev/null +++ b/Marlin/src/core/types.h @@ -0,0 +1,486 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ +#pragma once + +#include +#include + +#include "millis_t.h" + +// +// Enumerated axis indices +// +// - X_AXIS, Y_AXIS, and Z_AXIS should be used for axes in Cartesian space +// - A_AXIS, B_AXIS, and C_AXIS should be used for Steppers, corresponding to XYZ on Cartesians +// - X_HEAD, Y_HEAD, and Z_HEAD should be used for Steppers on Core kinematics +// +enum AxisEnum : uint8_t { + X_AXIS = 0, A_AXIS = 0, + Y_AXIS = 1, B_AXIS = 1, + Z_AXIS = 2, C_AXIS = 2, + E_AXIS = 3, + X_HEAD = 4, Y_HEAD = 5, Z_HEAD = 6, + E0_AXIS = 3, + E1_AXIS = 4, + E2_AXIS = 5, + E3_AXIS = 6, + E4_AXIS = 7, + E5_AXIS = 8, + ALL_AXES = 0xFE, NO_AXIS = 0xFF +}; + +// +// Loop over XYZE axes +// + +#define LOOP_S_LE_N(VAR, S, N) for (uint8_t VAR=(S); VAR<=(N); VAR++) +#define LOOP_S_L_N(VAR, S, N) for (uint8_t VAR=(S); VAR<(N); VAR++) +#define LOOP_LE_N(VAR, N) LOOP_S_LE_N(VAR, 0, N) +#define LOOP_L_N(VAR, N) LOOP_S_L_N(VAR, 0, N) + +#define LOOP_XYZ(VAR) LOOP_S_LE_N(VAR, X_AXIS, Z_AXIS) +#define LOOP_XYZE(VAR) LOOP_S_LE_N(VAR, X_AXIS, E_AXIS) +#define LOOP_XYZE_N(VAR) LOOP_S_L_N(VAR, X_AXIS, XYZE_N) +#define LOOP_ABC(VAR) LOOP_S_LE_N(VAR, A_AXIS, C_AXIS) +#define LOOP_ABCE(VAR) LOOP_S_LE_N(VAR, A_AXIS, E_AXIS) +#define LOOP_ABCE_N(VAR) LOOP_S_L_N(VAR, A_AXIS, XYZE_N) + +// +// Conditional type assignment magic. For example... +// +// typename IF<(MYOPT==12), int, float>::type myvar; +// +template +struct IF { typedef R type; }; +template +struct IF { typedef L type; }; + +// +// feedRate_t is just a humble float +// +typedef float feedRate_t; + +// Conversion macros +#define MMM_TO_MMS(MM_M) feedRate_t(float(MM_M) / 60.0f) +#define MMS_TO_MMM(MM_S) (float(MM_S) * 60.0f) +#define MMS_SCALED(V) ((V) * 0.01f * feedrate_percentage) + +// +// Coordinates structures for XY, XYZ, XYZE... +// + +// Helpers +#define _RECIP(N) ((N) ? 1.0f / float(N) : 0.0f) +#define _ABS(N) ((N) < 0 ? -(N) : (N)) +#define _LS(N) (N = (T)(uint32_t(N) << v)) +#define _RS(N) (N = (T)(uint32_t(N) >> v)) +#define FI FORCE_INLINE + +// Forward declarations +template struct XYval; +template struct XYZval; +template struct XYZEval; + +typedef struct XYval xy_bool_t; +typedef struct XYZval xyz_bool_t; +typedef struct XYZEval xyze_bool_t; + +typedef struct XYval xy_char_t; +typedef struct XYZval xyz_char_t; +typedef struct XYZEval xyze_char_t; + +typedef struct XYval xy_uchar_t; +typedef struct XYZval xyz_uchar_t; +typedef struct XYZEval xyze_uchar_t; + +typedef struct XYval xy_int8_t; +typedef struct XYZval xyz_int8_t; +typedef struct XYZEval xyze_int8_t; + +typedef struct XYval xy_uint8_t; +typedef struct XYZval xyz_uint8_t; +typedef struct XYZEval xyze_uint8_t; + +typedef struct XYval xy_int_t; +typedef struct XYZval xyz_int_t; +typedef struct XYZEval xyze_int_t; + +typedef struct XYval xy_uint_t; +typedef struct XYZval xyz_uint_t; +typedef struct XYZEval xyze_uint_t; + +typedef struct XYval xy_long_t; +typedef struct XYZval xyz_long_t; +typedef struct XYZEval xyze_long_t; + +typedef struct XYval xy_ulong_t; +typedef struct XYZval xyz_ulong_t; +typedef struct XYZEval xyze_ulong_t; + +typedef struct XYZval xyz_vlong_t; +typedef struct XYZEval xyze_vlong_t; + +typedef struct XYval xy_float_t; +typedef struct XYZval xyz_float_t; +typedef struct XYZEval xyze_float_t; + +typedef struct XYval xy_feedrate_t; +typedef struct XYZval xyz_feedrate_t; +typedef struct XYZEval xyze_feedrate_t; + +typedef xy_uint8_t xy_byte_t; +typedef xyz_uint8_t xyz_byte_t; +typedef xyze_uint8_t xyze_byte_t; + +typedef xyz_long_t abc_long_t; +typedef xyze_long_t abce_long_t; +typedef xyz_ulong_t abc_ulong_t; +typedef xyze_ulong_t abce_ulong_t; + +typedef xy_float_t xy_pos_t; +typedef xyz_float_t xyz_pos_t; +typedef xyze_float_t xyze_pos_t; + +typedef xy_float_t ab_float_t; +typedef xyz_float_t abc_float_t; +typedef xyze_float_t abce_float_t; + +typedef ab_float_t ab_pos_t; +typedef abc_float_t abc_pos_t; +typedef abce_float_t abce_pos_t; + +// External conversion methods +void toLogical(xy_pos_t &raw); +void toLogical(xyz_pos_t &raw); +void toLogical(xyze_pos_t &raw); +void toNative(xy_pos_t &raw); +void toNative(xyz_pos_t &raw); +void toNative(xyze_pos_t &raw); + +// +// XY coordinates, counters, etc. +// +template +struct XYval { + union { + struct { T x, y; }; + struct { T a, b; }; + T pos[2]; + }; + FI void set(const T px) { x = px; } + FI void set(const T px, const T py) { x = px; y = py; } + FI void reset() { x = y = 0; } + FI T magnitude() const { return (T)sqrtf(x*x + y*y); } + FI operator T* () { return pos; } + FI operator bool() { return x || y; } + FI XYval copy() const { return *this; } + FI XYval ABS() const { return { T(_ABS(x)), T(_ABS(y)) }; } + FI XYval asInt() { return { int16_t(x), int16_t(y) }; } + FI XYval asInt() const { return { int16_t(x), int16_t(y) }; } + FI XYval asLong() { return { int32_t(x), int32_t(y) }; } + FI XYval asLong() const { return { int32_t(x), int32_t(y) }; } + FI XYval asFloat() { return { float(x), float(y) }; } + FI XYval asFloat() const { return { float(x), float(y) }; } + FI XYval reciprocal() const { return { _RECIP(x), _RECIP(y) }; } + FI XYval asLogical() const { XYval o = asFloat(); toLogical(o); return o; } + FI XYval asNative() const { XYval o = asFloat(); toNative(o); return o; } + FI operator XYZval() { return { x, y }; } + FI operator XYZval() const { return { x, y }; } + FI operator XYZEval() { return { x, y }; } + FI operator XYZEval() const { return { x, y }; } + FI T& operator[](const int i) { return pos[i]; } + FI const T& operator[](const int i) const { return pos[i]; } + FI XYval& operator= (const T v) { set(v, v ); return *this; } + FI XYval& operator= (const XYZval &rs) { set(rs.x, rs.y); return *this; } + FI XYval& operator= (const XYZEval &rs) { set(rs.x, rs.y); return *this; } + FI XYval operator+ (const XYval &rs) const { XYval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } + FI XYval operator+ (const XYval &rs) { XYval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } + FI XYval operator- (const XYval &rs) const { XYval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } + FI XYval operator- (const XYval &rs) { XYval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } + FI XYval operator* (const XYval &rs) const { XYval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } + FI XYval operator* (const XYval &rs) { XYval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } + FI XYval operator/ (const XYval &rs) const { XYval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } + FI XYval operator/ (const XYval &rs) { XYval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } + FI XYval operator+ (const XYZval &rs) const { XYval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } + FI XYval operator+ (const XYZval &rs) { XYval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } + FI XYval operator- (const XYZval &rs) const { XYval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } + FI XYval operator- (const XYZval &rs) { XYval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } + FI XYval operator* (const XYZval &rs) const { XYval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } + FI XYval operator* (const XYZval &rs) { XYval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } + FI XYval operator/ (const XYZval &rs) const { XYval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } + FI XYval operator/ (const XYZval &rs) { XYval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } + FI XYval operator+ (const XYZEval &rs) const { XYval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } + FI XYval operator+ (const XYZEval &rs) { XYval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } + FI XYval operator- (const XYZEval &rs) const { XYval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } + FI XYval operator- (const XYZEval &rs) { XYval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } + FI XYval operator* (const XYZEval &rs) const { XYval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } + FI XYval operator* (const XYZEval &rs) { XYval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } + FI XYval operator/ (const XYZEval &rs) const { XYval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } + FI XYval operator/ (const XYZEval &rs) { XYval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } + FI XYval operator* (const float &v) const { XYval ls = *this; ls.x *= v; ls.y *= v; return ls; } + FI XYval operator* (const float &v) { XYval ls = *this; ls.x *= v; ls.y *= v; return ls; } + FI XYval operator* (const int &v) const { XYval ls = *this; ls.x *= v; ls.y *= v; return ls; } + FI XYval operator* (const int &v) { XYval ls = *this; ls.x *= v; ls.y *= v; return ls; } + FI XYval operator/ (const float &v) const { XYval ls = *this; ls.x /= v; ls.y /= v; return ls; } + FI XYval operator/ (const float &v) { XYval ls = *this; ls.x /= v; ls.y /= v; return ls; } + FI XYval operator/ (const int &v) const { XYval ls = *this; ls.x /= v; ls.y /= v; return ls; } + FI XYval operator/ (const int &v) { XYval ls = *this; ls.x /= v; ls.y /= v; return ls; } + FI XYval operator>>(const int &v) const { XYval ls = *this; _RS(ls.x); _RS(ls.y); return ls; } + FI XYval operator>>(const int &v) { XYval ls = *this; _RS(ls.x); _RS(ls.y); return ls; } + FI XYval operator<<(const int &v) const { XYval ls = *this; _LS(ls.x); _LS(ls.y); return ls; } + FI XYval operator<<(const int &v) { XYval ls = *this; _LS(ls.x); _LS(ls.y); return ls; } + FI XYval& operator+=(const XYval &rs) { x += rs.x; y += rs.y; return *this; } + FI XYval& operator-=(const XYval &rs) { x -= rs.x; y -= rs.y; return *this; } + FI XYval& operator*=(const XYval &rs) { x *= rs.x; y *= rs.y; return *this; } + FI XYval& operator+=(const XYZval &rs) { x += rs.x; y += rs.y; return *this; } + FI XYval& operator-=(const XYZval &rs) { x -= rs.x; y -= rs.y; return *this; } + FI XYval& operator*=(const XYZval &rs) { x *= rs.x; y *= rs.y; return *this; } + FI XYval& operator+=(const XYZEval &rs) { x += rs.x; y += rs.y; return *this; } + FI XYval& operator-=(const XYZEval &rs) { x -= rs.x; y -= rs.y; return *this; } + FI XYval& operator*=(const XYZEval &rs) { x *= rs.x; y *= rs.y; return *this; } + FI XYval& operator*=(const float &v) { x *= v; y *= v; return *this; } + FI XYval& operator*=(const int &v) { x *= v; y *= v; return *this; } + FI XYval& operator>>=(const int &v) { _RS(x); _RS(y); return *this; } + FI XYval& operator<<=(const int &v) { _LS(x); _LS(y); return *this; } + FI bool operator==(const XYval &rs) { return x == rs.x && y == rs.y; } + FI bool operator==(const XYZval &rs) { return x == rs.x && y == rs.y; } + FI bool operator==(const XYZEval &rs) { return x == rs.x && y == rs.y; } + FI bool operator==(const XYval &rs) const { return x == rs.x && y == rs.y; } + FI bool operator==(const XYZval &rs) const { return x == rs.x && y == rs.y; } + FI bool operator==(const XYZEval &rs) const { return x == rs.x && y == rs.y; } + FI bool operator!=(const XYval &rs) { return !operator==(rs); } + FI bool operator!=(const XYZval &rs) { return !operator==(rs); } + FI bool operator!=(const XYZEval &rs) { return !operator==(rs); } + FI bool operator!=(const XYval &rs) const { return !operator==(rs); } + FI bool operator!=(const XYZval &rs) const { return !operator==(rs); } + FI bool operator!=(const XYZEval &rs) const { return !operator==(rs); } + FI XYval operator-() { XYval o = *this; o.x = -x; o.y = -y; return o; } + FI const XYval operator-() const { XYval o = *this; o.x = -x; o.y = -y; return o; } +}; + +// +// XYZ coordinates, counters, etc. +// +template +struct XYZval { + union { + struct { T x, y, z; }; + struct { T a, b, c; }; + T pos[3]; + }; + FI void set(const T px) { x = px; } + FI void set(const T px, const T py) { x = px; y = py; } + FI void set(const T px, const T py, const T pz) { x = px; y = py; z = pz; } + FI void set(const XYval pxy, const T pz) { x = pxy.x; y = pxy.y; z = pz; } + FI void reset() { x = y = z = 0; } + FI T magnitude() const { return (T)sqrtf(x*x + y*y + z*z); } + FI operator T* () { return pos; } + FI operator bool() { return z || x || y; } + FI XYZval copy() const { XYZval o = *this; return o; } + FI XYZval ABS() const { return { T(_ABS(x)), T(_ABS(y)), T(_ABS(z)) }; } + FI XYZval asInt() { return { int16_t(x), int16_t(y), int16_t(z) }; } + FI XYZval asInt() const { return { int16_t(x), int16_t(y), int16_t(z) }; } + FI XYZval asLong() { return { int32_t(x), int32_t(y), int32_t(z) }; } + FI XYZval asLong() const { return { int32_t(x), int32_t(y), int32_t(z) }; } + FI XYZval asFloat() { return { float(x), float(y), float(z) }; } + FI XYZval asFloat() const { return { float(x), float(y), float(z) }; } + FI XYZval reciprocal() const { return { _RECIP(x), _RECIP(y), _RECIP(z) }; } + FI XYZval asLogical() const { XYZval o = asFloat(); toLogical(o); return o; } + FI XYZval asNative() const { XYZval o = asFloat(); toNative(o); return o; } + FI operator XYval&() { return *(XYval*)this; } + FI operator const XYval&() const { return *(const XYval*)this; } + FI operator XYZEval() const { return { x, y, z }; } + FI T& operator[](const int i) { return pos[i]; } + FI const T& operator[](const int i) const { return pos[i]; } + FI XYZval& operator= (const T v) { set(v, v, v ); return *this; } + FI XYZval& operator= (const XYval &rs) { set(rs.x, rs.y ); return *this; } + FI XYZval& operator= (const XYZEval &rs) { set(rs.x, rs.y, rs.z); return *this; } + FI XYZval operator+ (const XYval &rs) const { XYZval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } + FI XYZval operator+ (const XYval &rs) { XYZval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } + FI XYZval operator- (const XYval &rs) const { XYZval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } + FI XYZval operator- (const XYval &rs) { XYZval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } + FI XYZval operator* (const XYval &rs) const { XYZval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } + FI XYZval operator* (const XYval &rs) { XYZval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } + FI XYZval operator/ (const XYval &rs) const { XYZval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } + FI XYZval operator/ (const XYval &rs) { XYZval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } + FI XYZval operator+ (const XYZval &rs) const { XYZval ls = *this; ls.x += rs.x; ls.y += rs.y; ls.z += rs.z; return ls; } + FI XYZval operator+ (const XYZval &rs) { XYZval ls = *this; ls.x += rs.x; ls.y += rs.y; ls.z += rs.z; return ls; } + FI XYZval operator- (const XYZval &rs) const { XYZval ls = *this; ls.x -= rs.x; ls.y -= rs.y; ls.z -= rs.z; return ls; } + FI XYZval operator- (const XYZval &rs) { XYZval ls = *this; ls.x -= rs.x; ls.y -= rs.y; ls.z -= rs.z; return ls; } + FI XYZval operator* (const XYZval &rs) const { XYZval ls = *this; ls.x *= rs.x; ls.y *= rs.y; ls.z *= rs.z; return ls; } + FI XYZval operator* (const XYZval &rs) { XYZval ls = *this; ls.x *= rs.x; ls.y *= rs.y; ls.z *= rs.z; return ls; } + FI XYZval operator/ (const XYZval &rs) const { XYZval ls = *this; ls.x /= rs.x; ls.y /= rs.y; ls.z /= rs.z; return ls; } + FI XYZval operator/ (const XYZval &rs) { XYZval ls = *this; ls.x /= rs.x; ls.y /= rs.y; ls.z /= rs.z; return ls; } + FI XYZval operator+ (const XYZEval &rs) const { XYZval ls = *this; ls.x += rs.x; ls.y += rs.y; ls.z += rs.z; return ls; } + FI XYZval operator+ (const XYZEval &rs) { XYZval ls = *this; ls.x += rs.x; ls.y += rs.y; ls.z += rs.z; return ls; } + FI XYZval operator- (const XYZEval &rs) const { XYZval ls = *this; ls.x -= rs.x; ls.y -= rs.y; ls.z -= rs.z; return ls; } + FI XYZval operator- (const XYZEval &rs) { XYZval ls = *this; ls.x -= rs.x; ls.y -= rs.y; ls.z -= rs.z; return ls; } + FI XYZval operator* (const XYZEval &rs) const { XYZval ls = *this; ls.x *= rs.x; ls.y *= rs.y; ls.z *= rs.z; return ls; } + FI XYZval operator* (const XYZEval &rs) { XYZval ls = *this; ls.x *= rs.x; ls.y *= rs.y; ls.z *= rs.z; return ls; } + FI XYZval operator/ (const XYZEval &rs) const { XYZval ls = *this; ls.x /= rs.x; ls.y /= rs.y; ls.z /= rs.z; return ls; } + FI XYZval operator/ (const XYZEval &rs) { XYZval ls = *this; ls.x /= rs.x; ls.y /= rs.y; ls.z /= rs.z; return ls; } + FI XYZval operator* (const float &v) const { XYZval ls = *this; ls.x *= v; ls.y *= v; ls.z *= z; return ls; } + FI XYZval operator* (const float &v) { XYZval ls = *this; ls.x *= v; ls.y *= v; ls.z *= z; return ls; } + FI XYZval operator* (const int &v) const { XYZval ls = *this; ls.x *= v; ls.y *= v; ls.z *= z; return ls; } + FI XYZval operator* (const int &v) { XYZval ls = *this; ls.x *= v; ls.y *= v; ls.z *= z; return ls; } + FI XYZval operator/ (const float &v) const { XYZval ls = *this; ls.x /= v; ls.y /= v; ls.z /= z; return ls; } + FI XYZval operator/ (const float &v) { XYZval ls = *this; ls.x /= v; ls.y /= v; ls.z /= z; return ls; } + FI XYZval operator/ (const int &v) const { XYZval ls = *this; ls.x /= v; ls.y /= v; ls.z /= z; return ls; } + FI XYZval operator/ (const int &v) { XYZval ls = *this; ls.x /= v; ls.y /= v; ls.z /= z; return ls; } + FI XYZval operator>>(const int &v) const { XYZval ls = *this; _RS(ls.x); _RS(ls.y); _RS(ls.z); return ls; } + FI XYZval operator>>(const int &v) { XYZval ls = *this; _RS(ls.x); _RS(ls.y); _RS(ls.z); return ls; } + FI XYZval operator<<(const int &v) const { XYZval ls = *this; _LS(ls.x); _LS(ls.y); _LS(ls.z); return ls; } + FI XYZval operator<<(const int &v) { XYZval ls = *this; _LS(ls.x); _LS(ls.y); _LS(ls.z); return ls; } + FI XYZval& operator+=(const XYval &rs) { x += rs.x; y += rs.y; return *this; } + FI XYZval& operator-=(const XYval &rs) { x -= rs.x; y -= rs.y; return *this; } + FI XYZval& operator*=(const XYval &rs) { x *= rs.x; y *= rs.y; return *this; } + FI XYZval& operator/=(const XYval &rs) { x /= rs.x; y /= rs.y; return *this; } + FI XYZval& operator+=(const XYZval &rs) { x += rs.x; y += rs.y; z += rs.z; return *this; } + FI XYZval& operator-=(const XYZval &rs) { x -= rs.x; y -= rs.y; z -= rs.z; return *this; } + FI XYZval& operator*=(const XYZval &rs) { x *= rs.x; y *= rs.y; z *= rs.z; return *this; } + FI XYZval& operator/=(const XYZval &rs) { x /= rs.x; y /= rs.y; z /= rs.z; return *this; } + FI XYZval& operator+=(const XYZEval &rs) { x += rs.x; y += rs.y; z += rs.z; return *this; } + FI XYZval& operator-=(const XYZEval &rs) { x -= rs.x; y -= rs.y; z -= rs.z; return *this; } + FI XYZval& operator*=(const XYZEval &rs) { x *= rs.x; y *= rs.y; z *= rs.z; return *this; } + FI XYZval& operator/=(const XYZEval &rs) { x /= rs.x; y /= rs.y; z /= rs.z; return *this; } + FI XYZval& operator*=(const float &v) { x *= v; y *= v; z *= v; return *this; } + FI XYZval& operator*=(const int &v) { x *= v; y *= v; z *= v; return *this; } + FI XYZval& operator>>=(const int &v) { _RS(x); _RS(y); _RS(z); return *this; } + FI XYZval& operator<<=(const int &v) { _LS(x); _LS(y); _LS(z); return *this; } + FI bool operator==(const XYZEval &rs) { return x == rs.x && y == rs.y && z == rs.z; } + FI bool operator!=(const XYZEval &rs) { return !operator==(rs); } + FI bool operator==(const XYZEval &rs) const { return x == rs.x && y == rs.y && z == rs.z; } + FI bool operator!=(const XYZEval &rs) const { return !operator==(rs); } + FI XYZval operator-() { XYZval o = *this; o.x = -x; o.y = -y; o.z = -z; return o; } + FI const XYZval operator-() const { XYZval o = *this; o.x = -x; o.y = -y; o.z = -z; return o; } +}; + +// +// XYZE coordinates, counters, etc. +// +template +struct XYZEval { + union { + struct{ T x, y, z, e; }; + struct{ T a, b, c; }; + T pos[4]; + }; + FI void reset() { x = y = z = e = 0; } + FI T magnitude() const { return (T)sqrtf(x*x + y*y + z*z + e*e); } + FI operator T* () { return pos; } + FI operator bool() { return e || z || x || y; } + FI void set(const T px) { x = px; } + FI void set(const T px, const T py) { x = px; y = py; } + FI void set(const T px, const T py, const T pz) { x = px; y = py; z = pz; } + FI void set(const T px, const T py, const T pz, const T pe) { x = px; y = py; z = pz; e = pe; } + FI void set(const XYval pxy) { x = pxy.x; y = pxy.y; } + FI void set(const XYval pxy, const T pz) { x = pxy.x; y = pxy.y; z = pz; } + FI void set(const XYZval pxyz) { x = pxyz.x; y = pxyz.y; z = pxyz.z; } + FI void set(const XYval pxy, const T pz, const T pe) { x = pxy.x; y = pxy.y; z = pz; e = pe; } + FI void set(const XYval pxy, const XYval pze) { x = pxy.x; y = pxy.y; z = pze.z; e = pze.e; } + FI void set(const XYZval pxyz, const T pe) { x = pxyz.x; y = pxyz.y; z = pxyz.z; e = pe; } + FI XYZEval copy() const { return *this; } + FI XYZEval ABS() const { return { T(_ABS(x)), T(_ABS(y)), T(_ABS(z)), T(_ABS(e)) }; } + FI XYZEval asInt() { return { int16_t(x), int16_t(y), int16_t(z), int16_t(e) }; } + FI XYZEval asInt() const { return { int16_t(x), int16_t(y), int16_t(z), int16_t(e) }; } + FI XYZEval asLong() const { return { int32_t(x), int32_t(y), int32_t(z), int32_t(e) }; } + FI XYZEval asLong() { return { int32_t(x), int32_t(y), int32_t(z), int32_t(e) }; } + FI XYZEval asFloat() { return { float(x), float(y), float(z), float(e) }; } + FI XYZEval asFloat() const { return { float(x), float(y), float(z), float(e) }; } + FI XYZEval reciprocal() const { return { _RECIP(x), _RECIP(y), _RECIP(z), _RECIP(e) }; } + FI XYZEval asLogical() const { XYZEval o = asFloat(); toLogical(o); return o; } + FI XYZEval asNative() const { XYZEval o = asFloat(); toNative(o); return o; } + FI operator XYval&() { return *(XYval*)this; } + FI operator const XYval&() const { return *(const XYval*)this; } + FI operator XYZval&() { return *(XYZval*)this; } + FI operator const XYZval&() const { return *(const XYZval*)this; } + FI T& operator[](const int i) { return pos[i]; } + FI const T& operator[](const int i) const { return pos[i]; } + FI XYZEval& operator= (const T v) { set(v, v, v, v); return *this; } + FI XYZEval& operator= (const XYval &rs) { set(rs.x, rs.y); return *this; } + FI XYZEval& operator= (const XYZval &rs) { set(rs.x, rs.y, rs.z); return *this; } + FI XYZEval operator+ (const XYval &rs) const { XYZEval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } + FI XYZEval operator+ (const XYval &rs) { XYZEval ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; } + FI XYZEval operator- (const XYval &rs) const { XYZEval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } + FI XYZEval operator- (const XYval &rs) { XYZEval ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; } + FI XYZEval operator* (const XYval &rs) const { XYZEval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } + FI XYZEval operator* (const XYval &rs) { XYZEval ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; } + FI XYZEval operator/ (const XYval &rs) const { XYZEval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } + FI XYZEval operator/ (const XYval &rs) { XYZEval ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; } + FI XYZEval operator+ (const XYZval &rs) const { XYZEval ls = *this; ls.x += rs.x; ls.y += rs.y; ls.z += rs.z; return ls; } + FI XYZEval operator+ (const XYZval &rs) { XYZEval ls = *this; ls.x += rs.x; ls.y += rs.y; ls.z += rs.z; return ls; } + FI XYZEval operator- (const XYZval &rs) const { XYZEval ls = *this; ls.x -= rs.x; ls.y -= rs.y; ls.z -= rs.z; return ls; } + FI XYZEval operator- (const XYZval &rs) { XYZEval ls = *this; ls.x -= rs.x; ls.y -= rs.y; ls.z -= rs.z; return ls; } + FI XYZEval operator* (const XYZval &rs) const { XYZEval ls = *this; ls.x *= rs.x; ls.y *= rs.y; ls.z *= rs.z; return ls; } + FI XYZEval operator* (const XYZval &rs) { XYZEval ls = *this; ls.x *= rs.x; ls.y *= rs.y; ls.z *= rs.z; return ls; } + FI XYZEval operator/ (const XYZval &rs) const { XYZEval ls = *this; ls.x /= rs.x; ls.y /= rs.y; ls.z /= rs.z; return ls; } + FI XYZEval operator/ (const XYZval &rs) { XYZEval ls = *this; ls.x /= rs.x; ls.y /= rs.y; ls.z /= rs.z; return ls; } + FI XYZEval operator+ (const XYZEval &rs) const { XYZEval ls = *this; ls.x += rs.x; ls.y += rs.y; ls.z += rs.z; ls.e += rs.e; return ls; } + FI XYZEval operator+ (const XYZEval &rs) { XYZEval ls = *this; ls.x += rs.x; ls.y += rs.y; ls.z += rs.z; ls.e += rs.e; return ls; } + FI XYZEval operator- (const XYZEval &rs) const { XYZEval ls = *this; ls.x -= rs.x; ls.y -= rs.y; ls.z -= rs.z; ls.e -= rs.e; return ls; } + FI XYZEval operator- (const XYZEval &rs) { XYZEval ls = *this; ls.x -= rs.x; ls.y -= rs.y; ls.z -= rs.z; ls.e -= rs.e; return ls; } + FI XYZEval operator* (const XYZEval &rs) const { XYZEval ls = *this; ls.x *= rs.x; ls.y *= rs.y; ls.z *= rs.z; ls.e *= rs.e; return ls; } + FI XYZEval operator* (const XYZEval &rs) { XYZEval ls = *this; ls.x *= rs.x; ls.y *= rs.y; ls.z *= rs.z; ls.e *= rs.e; return ls; } + FI XYZEval operator/ (const XYZEval &rs) const { XYZEval ls = *this; ls.x /= rs.x; ls.y /= rs.y; ls.z /= rs.z; ls.e /= rs.e; return ls; } + FI XYZEval operator/ (const XYZEval &rs) { XYZEval ls = *this; ls.x /= rs.x; ls.y /= rs.y; ls.z /= rs.z; ls.e /= rs.e; return ls; } + FI XYZEval operator* (const float &v) const { XYZEval ls = *this; ls.x *= v; ls.y *= v; ls.z *= v; ls.e *= v; return ls; } + FI XYZEval operator* (const float &v) { XYZEval ls = *this; ls.x *= v; ls.y *= v; ls.z *= v; ls.e *= v; return ls; } + FI XYZEval operator* (const int &v) const { XYZEval ls = *this; ls.x *= v; ls.y *= v; ls.z *= v; ls.e *= v; return ls; } + FI XYZEval operator* (const int &v) { XYZEval ls = *this; ls.x *= v; ls.y *= v; ls.z *= v; ls.e *= v; return ls; } + FI XYZEval operator/ (const float &v) const { XYZEval ls = *this; ls.x /= v; ls.y /= v; ls.z /= v; ls.e /= v; return ls; } + FI XYZEval operator/ (const float &v) { XYZEval ls = *this; ls.x /= v; ls.y /= v; ls.z /= v; ls.e /= v; return ls; } + FI XYZEval operator/ (const int &v) const { XYZEval ls = *this; ls.x /= v; ls.y /= v; ls.z /= v; ls.e /= v; return ls; } + FI XYZEval operator/ (const int &v) { XYZEval ls = *this; ls.x /= v; ls.y /= v; ls.z /= v; ls.e /= v; return ls; } + FI XYZEval operator>>(const int &v) const { XYZEval ls = *this; _RS(ls.x); _RS(ls.y); _RS(ls.z); _RS(ls.e); return ls; } + FI XYZEval operator>>(const int &v) { XYZEval ls = *this; _RS(ls.x); _RS(ls.y); _RS(ls.z); _RS(ls.e); return ls; } + FI XYZEval operator<<(const int &v) const { XYZEval ls = *this; _LS(ls.x); _LS(ls.y); _LS(ls.z); _LS(ls.e); return ls; } + FI XYZEval operator<<(const int &v) { XYZEval ls = *this; _LS(ls.x); _LS(ls.y); _LS(ls.z); _LS(ls.e); return ls; } + FI XYZEval& operator+=(const XYval &rs) { x += rs.x; y += rs.y; return *this; } + FI XYZEval& operator-=(const XYval &rs) { x -= rs.x; y -= rs.y; return *this; } + FI XYZEval& operator*=(const XYval &rs) { x *= rs.x; y *= rs.y; return *this; } + FI XYZEval& operator/=(const XYval &rs) { x /= rs.x; y /= rs.y; return *this; } + FI XYZEval& operator+=(const XYZval &rs) { x += rs.x; y += rs.y; z += rs.z; return *this; } + FI XYZEval& operator-=(const XYZval &rs) { x -= rs.x; y -= rs.y; z -= rs.z; return *this; } + FI XYZEval& operator*=(const XYZval &rs) { x *= rs.x; y *= rs.y; z *= rs.z; return *this; } + FI XYZEval& operator/=(const XYZval &rs) { x /= rs.x; y /= rs.y; z /= rs.z; return *this; } + FI XYZEval& operator+=(const XYZEval &rs) { x += rs.x; y += rs.y; z += rs.z; e += rs.e; return *this; } + FI XYZEval& operator-=(const XYZEval &rs) { x -= rs.x; y -= rs.y; z -= rs.z; e -= rs.e; return *this; } + FI XYZEval& operator*=(const XYZEval &rs) { x *= rs.x; y *= rs.y; z *= rs.z; e *= rs.e; return *this; } + FI XYZEval& operator/=(const XYZEval &rs) { x /= rs.x; y /= rs.y; z /= rs.z; e /= rs.e; return *this; } + FI XYZEval& operator*=(const T &v) { x *= v; y *= v; z *= v; e *= v; return *this; } + FI XYZEval& operator>>=(const int &v) { _RS(x); _RS(y); _RS(z); _RS(e); return *this; } + FI XYZEval& operator<<=(const int &v) { _LS(x); _LS(y); _LS(z); _LS(e); return *this; } + FI bool operator==(const XYZval &rs) { return x == rs.x && y == rs.y && z == rs.z; } + FI bool operator!=(const XYZval &rs) { return !operator==(rs); } + FI bool operator==(const XYZval &rs) const { return x == rs.x && y == rs.y && z == rs.z; } + FI bool operator!=(const XYZval &rs) const { return !operator==(rs); } + FI XYZEval operator-() { return { -x, -y, -z, -e }; } + FI const XYZEval operator-() const { return { -x, -y, -z, -e }; } +}; + +#undef _RECIP +#undef _ABS +#undef _LS +#undef _RS +#undef FI + +const xyze_char_t axis_codes { 'X', 'Y', 'Z', 'E' }; diff --git a/Marlin/src/core/utility.cpp b/Marlin/src/core/utility.cpp index 5ebd84afd..ca8cd67cc 100644 --- a/Marlin/src/core/utility.cpp +++ b/Marlin/src/core/utility.cpp @@ -79,36 +79,36 @@ void safe_delay(millis_t ms) { ); #if HAS_BED_PROBE - SERIAL_ECHOPAIR("Probe Offset X:", probe_offset[X_AXIS], " Y:", probe_offset[Y_AXIS], " Z:", probe_offset[Z_AXIS]); - if (probe_offset[X_AXIS] > 0) + SERIAL_ECHOPAIR("Probe Offset X", probe_offset.x, " Y", probe_offset.y, " Z", probe_offset.z); + if (probe_offset.x > 0) SERIAL_ECHOPGM(" (Right"); - else if (probe_offset[X_AXIS] < 0) + else if (probe_offset.x < 0) SERIAL_ECHOPGM(" (Left"); - else if (probe_offset[Y_AXIS] != 0) + else if (probe_offset.y != 0) SERIAL_ECHOPGM(" (Middle"); else SERIAL_ECHOPGM(" (Aligned With"); - if (probe_offset[Y_AXIS] > 0) { + if (probe_offset.y > 0) { #if IS_SCARA SERIAL_ECHOPGM("-Distal"); #else SERIAL_ECHOPGM("-Back"); #endif } - else if (probe_offset[Y_AXIS] < 0) { + else if (probe_offset.y < 0) { #if IS_SCARA SERIAL_ECHOPGM("-Proximal"); #else SERIAL_ECHOPGM("-Front"); #endif } - else if (probe_offset[X_AXIS] != 0) + else if (probe_offset.x != 0) SERIAL_ECHOPGM("-Center"); - if (probe_offset[Z_AXIS] < 0) + if (probe_offset.z < 0) SERIAL_ECHOPGM(" & Below"); - else if (probe_offset[Z_AXIS] > 0) + else if (probe_offset.z > 0) SERIAL_ECHOPGM(" & Above"); else SERIAL_ECHOPGM(" & Same Z as"); @@ -134,24 +134,18 @@ void safe_delay(millis_t ms) { SERIAL_ECHOLNPAIR("Z Fade: ", planner.z_fade_height); #endif #if ABL_PLANAR - const float diff[XYZ] = { - planner.get_axis_position_mm(X_AXIS) - current_position[X_AXIS], - planner.get_axis_position_mm(Y_AXIS) - current_position[Y_AXIS], - planner.get_axis_position_mm(Z_AXIS) - current_position[Z_AXIS] - }; SERIAL_ECHOPGM("ABL Adjustment X"); - if (diff[X_AXIS] > 0) SERIAL_CHAR('+'); - SERIAL_ECHO(diff[X_AXIS]); - SERIAL_ECHOPGM(" Y"); - if (diff[Y_AXIS] > 0) SERIAL_CHAR('+'); - SERIAL_ECHO(diff[Y_AXIS]); - SERIAL_ECHOPGM(" Z"); - if (diff[Z_AXIS] > 0) SERIAL_CHAR('+'); - SERIAL_ECHO(diff[Z_AXIS]); + LOOP_XYZ(a) { + float v = planner.get_axis_position_mm(AxisEnum(a)) - current_position[a]; + SERIAL_CHAR(' '); + SERIAL_CHAR('X' + char(a)); + if (v > 0) SERIAL_CHAR('+'); + SERIAL_ECHO(v); + } #else #if ENABLED(AUTO_BED_LEVELING_UBL) SERIAL_ECHOPGM("UBL Adjustment Z"); - const float rz = ubl.get_z_correction(current_position[X_AXIS], current_position[Y_AXIS]); + const float rz = ubl.get_z_correction(current_position); #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) SERIAL_ECHOPGM("ABL Adjustment Z"); const float rz = bilinear_z_offset(current_position); @@ -159,7 +153,7 @@ void safe_delay(millis_t ms) { SERIAL_ECHO(ftostr43sign(rz, '+')); #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) if (planner.z_fade_height) { - SERIAL_ECHOPAIR(" (", ftostr43sign(rz * planner.fade_scaling_factor_for_z(current_position[Z_AXIS]), '+')); + SERIAL_ECHOPAIR(" (", ftostr43sign(rz * planner.fade_scaling_factor_for_z(current_position.z), '+')); SERIAL_CHAR(')'); } #endif @@ -175,15 +169,11 @@ void safe_delay(millis_t ms) { SERIAL_ECHOPGM("Mesh Bed Leveling"); if (planner.leveling_active) { SERIAL_ECHOLNPGM(" (enabled)"); - SERIAL_ECHOPAIR("MBL Adjustment Z", ftostr43sign(mbl.get_z(current_position[X_AXIS], current_position[Y_AXIS] - #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - , 1.0 - #endif - ), '+')); + SERIAL_ECHOPAIR("MBL Adjustment Z", ftostr43sign(mbl.get_z(current_position), '+')); #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) if (planner.z_fade_height) { SERIAL_ECHOPAIR(" (", ftostr43sign( - mbl.get_z(current_position[X_AXIS], current_position[Y_AXIS], planner.fade_scaling_factor_for_z(current_position[Z_AXIS])), '+' + mbl.get_z(current_position, planner.fade_scaling_factor_for_z(current_position.z)), '+' )); SERIAL_CHAR(')'); } diff --git a/Marlin/src/core/utility.h b/Marlin/src/core/utility.h index 4ae6a9671..2956f9289 100644 --- a/Marlin/src/core/utility.h +++ b/Marlin/src/core/utility.h @@ -22,8 +22,7 @@ #pragma once #include "../inc/MarlinConfigPre.h" - -constexpr char axis_codes[XYZE] = { 'X', 'Y', 'Z', 'E' }; +#include "../core/types.h" // Delay that ensures heaters and watchdog are kept alive void safe_delay(millis_t ms); @@ -37,10 +36,25 @@ inline void serial_delay(const millis_t ms) { #endif } -// 16x16 bit arrays -FORCE_INLINE void bitmap_clear(uint16_t bits[16], const uint8_t x, const uint8_t y) { CBI(bits[y], x); } -FORCE_INLINE void bitmap_set(uint16_t bits[16], const uint8_t x, const uint8_t y) { SBI(bits[y], x); } -FORCE_INLINE bool is_bitmap_set(uint16_t bits[16], const uint8_t x, const uint8_t y) { return TEST(bits[y], x); } +#if GRID_MAX_POINTS_X && GRID_MAX_POINTS_Y + + // 16x16 bit arrays + template + struct FlagBits { + typename IF<(W>8), uint16_t, uint8_t>::type bits[H]; + void fill() { memset(bits, 0xFF, sizeof(bits)); } + void reset() { memset(bits, 0x00, sizeof(bits)); } + void unmark(const uint8_t x, const uint8_t y) { CBI(bits[y], x); } + void mark(const uint8_t x, const uint8_t y) { SBI(bits[y], x); } + bool marked(const uint8_t x, const uint8_t y) { return TEST(bits[y], x); } + inline void unmark(const xy_int8_t &xy) { unmark(xy.y, xy.x); } + inline void mark(const xy_int8_t &xy) { mark(xy.y, xy.x); } + inline bool marked(const xy_int8_t &xy) { return marked(xy.y, xy.x); } + }; + + typedef FlagBits MeshFlags; + +#endif #if ENABLED(DEBUG_LEVELING_FEATURE) void log_machine_info(); diff --git a/Marlin/src/feature/I2CPositionEncoder.cpp b/Marlin/src/feature/I2CPositionEncoder.cpp index 1f73f1417..c3b182c72 100644 --- a/Marlin/src/feature/I2CPositionEncoder.cpp +++ b/Marlin/src/feature/I2CPositionEncoder.cpp @@ -326,25 +326,23 @@ bool I2CPositionEncoder::test_axis() { //only works on XYZ cartesian machines for the time being if (!(encoderAxis == X_AXIS || encoderAxis == Y_AXIS || encoderAxis == Z_AXIS)) return false; - float startCoord[NUM_AXIS] = { 0 }, endCoord[NUM_AXIS] = { 0 }; - - const float startPosition = soft_endstop[encoderAxis].min + 10, - endPosition = soft_endstop[encoderAxis].max - 10; + const float startPosition = soft_endstop.min[encoderAxis] + 10, + endPosition = soft_endstop.max[encoderAxis] - 10; const feedRate_t fr_mm_s = FLOOR(MMM_TO_MMS((encoderAxis == Z_AXIS) ? HOMING_FEEDRATE_Z : HOMING_FEEDRATE_XY)); ec = false; - LOOP_XYZ(i) { - startCoord[i] = planner.get_axis_position_mm((AxisEnum)i); - endCoord[i] = planner.get_axis_position_mm((AxisEnum)i); + xyze_pos_t startCoord, endCoord; + LOOP_XYZ(a) { + startCoord[a] = planner.get_axis_position_mm((AxisEnum)a); + endCoord[a] = planner.get_axis_position_mm((AxisEnum)a); } startCoord[encoderAxis] = startPosition; endCoord[encoderAxis] = endPosition; planner.synchronize(); - - planner.buffer_line(startCoord[X_AXIS], startCoord[Y_AXIS], startCoord[Z_AXIS], - planner.get_axis_position_mm(E_AXIS), fr_mm_s, 0); + startCoord.e = planner.get_axis_position_mm(E_AXIS); + planner.buffer_line(startCoord, fr_mm_s, 0); planner.synchronize(); // if the module isn't currently trusted, wait until it is (or until it should be if things are working) @@ -355,8 +353,8 @@ bool I2CPositionEncoder::test_axis() { } if (trusted) { // if trusted, commence test - planner.buffer_line(endCoord[X_AXIS], endCoord[Y_AXIS], endCoord[Z_AXIS], - planner.get_axis_position_mm(E_AXIS), fr_mm_s, 0); + endCoord.e = planner.get_axis_position_mm(E_AXIS); + planner.buffer_line(endCoord, fr_mm_s, 0); planner.synchronize(); } @@ -376,8 +374,7 @@ void I2CPositionEncoder::calibrate_steps_mm(const uint8_t iter) { float old_steps_mm, new_steps_mm, startDistance, endDistance, - travelDistance, travelledDistance, total = 0, - startCoord[NUM_AXIS] = { 0 }, endCoord[NUM_AXIS] = { 0 }; + travelDistance, travelledDistance, total = 0; int32_t startCount, stopCount; @@ -387,31 +384,31 @@ void I2CPositionEncoder::calibrate_steps_mm(const uint8_t iter) { ec = false; startDistance = 20; - endDistance = soft_endstop[encoderAxis].max - 20; + endDistance = soft_endstop.max[encoderAxis] - 20; travelDistance = endDistance - startDistance; + xyze_pos_t startCoord, endCoord; LOOP_XYZ(a) { startCoord[a] = planner.get_axis_position_mm((AxisEnum)a); endCoord[a] = planner.get_axis_position_mm((AxisEnum)a); } - startCoord[encoderAxis] = startDistance; endCoord[encoderAxis] = endDistance; planner.synchronize(); LOOP_L_N(i, iter) { - planner.buffer_line(startCoord[X_AXIS], startCoord[Y_AXIS], startCoord[Z_AXIS], - planner.get_axis_position_mm(E_AXIS), fr_mm_s, 0); + startCoord.e = planner.get_axis_position_mm(E_AXIS); + planner.buffer_line(startCoord, fr_mm_s, 0); planner.synchronize(); delay(250); startCount = get_position(); - //do_blocking_move_to(endCoord[X_AXIS],endCoord[Y_AXIS],endCoord[Z_AXIS]); + //do_blocking_move_to(endCoord); - planner.buffer_line(endCoord[X_AXIS], endCoord[Y_AXIS], endCoord[Z_AXIS], - planner.get_axis_position_mm(E_AXIS), fr_mm_s, 0); + endCoord.e = planner.get_axis_position_mm(E_AXIS); + planner.buffer_line(endCoord, fr_mm_s, 0); planner.synchronize(); //Read encoder distance diff --git a/Marlin/src/feature/I2CPositionEncoder.h b/Marlin/src/feature/I2CPositionEncoder.h index ad3e30a51..25350b278 100644 --- a/Marlin/src/feature/I2CPositionEncoder.h +++ b/Marlin/src/feature/I2CPositionEncoder.h @@ -93,8 +93,6 @@ #define LOOP_PE(VAR) LOOP_L_N(VAR, I2CPE_ENCODER_CNT) #define CHECK_IDX() do{ if (!WITHIN(idx, 0, I2CPE_ENCODER_CNT - 1)) return; }while(0) -extern const char axis_codes[XYZE]; - typedef union { volatile int32_t val = 0; uint8_t bval[4]; diff --git a/Marlin/src/feature/backlash.cpp b/Marlin/src/feature/backlash.cpp index 8f708c14f..f1a14df49 100644 --- a/Marlin/src/feature/backlash.cpp +++ b/Marlin/src/feature/backlash.cpp @@ -31,9 +31,9 @@ #ifdef BACKLASH_DISTANCE_MM #if ENABLED(BACKLASH_GCODE) - float Backlash::distance_mm[XYZ] = BACKLASH_DISTANCE_MM; + xyz_float_t Backlash::distance_mm = BACKLASH_DISTANCE_MM; #else - const float Backlash::distance_mm[XYZ] = BACKLASH_DISTANCE_MM; + const xyz_float_t Backlash::distance_mm = BACKLASH_DISTANCE_MM; #endif #endif @@ -45,8 +45,8 @@ #endif #if ENABLED(MEASURE_BACKLASH_WHEN_PROBING) - float Backlash::measured_mm[XYZ] = { 0 }; - uint8_t Backlash::measured_count[XYZ] = { 0 }; + xyz_float_t Backlash::measured_mm{0}; + xyz_uint8_t Backlash::measured_count{0}; #endif Backlash backlash; @@ -80,12 +80,12 @@ void Backlash::add_correction_steps(const int32_t &da, const int32_t &db, const // Residual error carried forward across multiple segments, so correction can be applied // to segments where there is no direction change. - static int32_t residual_error[XYZ] = { 0 }; + static xyz_long_t residual_error{0}; #else // No direction change, no correction. if (!changed_dir) return; // No leftover residual error from segment to segment - int32_t residual_error[XYZ] = { 0 }; + xyz_long_t residual_error{0}; #endif const float f_corr = float(correction) / 255.0f; @@ -131,15 +131,15 @@ void Backlash::add_correction_steps(const int32_t &da, const int32_t &db, const // Measure Z backlash by raising nozzle in increments until probe deactivates void Backlash::measure_with_probe() { - if (measured_count[Z_AXIS] == 255) return; + if (measured_count.z == 255) return; - float start_height = current_position[Z_AXIS]; - while (current_position[Z_AXIS] < (start_height + BACKLASH_MEASUREMENT_LIMIT) && TEST_PROBE_PIN) - do_blocking_move_to_z(current_position[Z_AXIS] + BACKLASH_MEASUREMENT_RESOLUTION, MMM_TO_MMS(BACKLASH_MEASUREMENT_FEEDRATE)); + const float start_height = current_position.z; + while (current_position.z < (start_height + BACKLASH_MEASUREMENT_LIMIT) && TEST_PROBE_PIN) + do_blocking_move_to_z(current_position.z + BACKLASH_MEASUREMENT_RESOLUTION, MMM_TO_MMS(BACKLASH_MEASUREMENT_FEEDRATE)); // The backlash from all probe points is averaged, so count the number of measurements - measured_mm[Z_AXIS] += current_position[Z_AXIS] - start_height; - measured_count[Z_AXIS]++; + measured_mm.z += current_position.z - start_height; + measured_count.z++; } #endif diff --git a/Marlin/src/feature/backlash.h b/Marlin/src/feature/backlash.h index 19d653491..0ded86565 100644 --- a/Marlin/src/feature/backlash.h +++ b/Marlin/src/feature/backlash.h @@ -29,7 +29,7 @@ constexpr uint8_t all_on = 0xFF, all_off = 0x00; class Backlash { public: #if ENABLED(BACKLASH_GCODE) - static float distance_mm[XYZ]; + static xyz_float_t distance_mm; static uint8_t correction; #ifdef BACKLASH_SMOOTHING_MM static float smoothing_mm; @@ -39,7 +39,7 @@ public: static inline float get_correction() { return float(ui8_to_percent(correction)) / 100.0f; } #else static constexpr uint8_t correction = (BACKLASH_CORRECTION) * 0xFF; - static const float distance_mm[XYZ]; + static const xyz_float_t distance_mm; #ifdef BACKLASH_SMOOTHING_MM static constexpr float smoothing_mm = BACKLASH_SMOOTHING_MM; #endif @@ -47,8 +47,8 @@ public: #if ENABLED(MEASURE_BACKLASH_WHEN_PROBING) private: - static float measured_mm[XYZ]; - static uint8_t measured_count[XYZ]; + static xyz_float_t measured_mm; + static xyz_uint8_t measured_count; public: static void measure_with_probe(); #endif diff --git a/Marlin/src/feature/bedlevel/abl/abl.cpp b/Marlin/src/feature/bedlevel/abl/abl.cpp index d1857af11..d5c5532ad 100644 --- a/Marlin/src/feature/bedlevel/abl/abl.cpp +++ b/Marlin/src/feature/bedlevel/abl/abl.cpp @@ -35,9 +35,9 @@ #include "../../../lcd/extensible_ui/ui_api.h" #endif -int bilinear_grid_spacing[2], bilinear_start[2]; -float bilinear_grid_factor[2], - z_values[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y]; +xy_int_t bilinear_grid_spacing, bilinear_start; +xy_float_t bilinear_grid_factor; +bed_mesh_t z_values; /** * Extrapolate a single point from its neighbors @@ -153,8 +153,8 @@ void print_bilinear_leveling_grid() { #define ABL_TEMP_POINTS_X (GRID_MAX_POINTS_X + 2) #define ABL_TEMP_POINTS_Y (GRID_MAX_POINTS_Y + 2) float z_values_virt[ABL_GRID_POINTS_VIRT_X][ABL_GRID_POINTS_VIRT_Y]; - int bilinear_grid_spacing_virt[2] = { 0 }; - float bilinear_grid_factor_virt[2] = { 0 }; + xy_int_t bilinear_grid_spacing_virt; + xy_float_t bilinear_grid_factor_virt; void print_bilinear_leveling_grid_virt() { SERIAL_ECHOLNPGM("Subdivided with CATMULL ROM Leveling Grid:"); @@ -207,7 +207,7 @@ void print_bilinear_leveling_grid() { + p[i] * (2 - 5 * sq(t) + 3 * t * sq(t)) + p[i+1] * t * (1 + 4 * t - 3 * sq(t)) - p[i+2] * sq(t) * (1 - t) - ) * 0.5; + ) * 0.5f; } static float bed_level_virt_2cmr(const uint8_t x, const uint8_t y, const float &tx, const float &ty) { @@ -222,10 +222,8 @@ void print_bilinear_leveling_grid() { } void bed_level_virt_interpolate() { - bilinear_grid_spacing_virt[X_AXIS] = bilinear_grid_spacing[X_AXIS] / (BILINEAR_SUBDIVISIONS); - bilinear_grid_spacing_virt[Y_AXIS] = bilinear_grid_spacing[Y_AXIS] / (BILINEAR_SUBDIVISIONS); - bilinear_grid_factor_virt[X_AXIS] = RECIPROCAL(bilinear_grid_spacing_virt[X_AXIS]); - bilinear_grid_factor_virt[Y_AXIS] = RECIPROCAL(bilinear_grid_spacing_virt[Y_AXIS]); + bilinear_grid_spacing_virt = bilinear_grid_spacing / (BILINEAR_SUBDIVISIONS); + bilinear_grid_factor_virt = bilinear_grid_spacing_virt.reciprocal(); for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) for (uint8_t ty = 0; ty < BILINEAR_SUBDIVISIONS; ty++) @@ -245,40 +243,38 @@ void print_bilinear_leveling_grid() { // Refresh after other values have been updated void refresh_bed_level() { - bilinear_grid_factor[X_AXIS] = RECIPROCAL(bilinear_grid_spacing[X_AXIS]); - bilinear_grid_factor[Y_AXIS] = RECIPROCAL(bilinear_grid_spacing[Y_AXIS]); + bilinear_grid_factor = bilinear_grid_spacing.reciprocal(); #if ENABLED(ABL_BILINEAR_SUBDIVISION) bed_level_virt_interpolate(); #endif } #if ENABLED(ABL_BILINEAR_SUBDIVISION) - #define ABL_BG_SPACING(A) bilinear_grid_spacing_virt[A] - #define ABL_BG_FACTOR(A) bilinear_grid_factor_virt[A] + #define ABL_BG_SPACING(A) bilinear_grid_spacing_virt.A + #define ABL_BG_FACTOR(A) bilinear_grid_factor_virt.A #define ABL_BG_POINTS_X ABL_GRID_POINTS_VIRT_X #define ABL_BG_POINTS_Y ABL_GRID_POINTS_VIRT_Y #define ABL_BG_GRID(X,Y) z_values_virt[X][Y] #else - #define ABL_BG_SPACING(A) bilinear_grid_spacing[A] - #define ABL_BG_FACTOR(A) bilinear_grid_factor[A] + #define ABL_BG_SPACING(A) bilinear_grid_spacing.A + #define ABL_BG_FACTOR(A) bilinear_grid_factor.A #define ABL_BG_POINTS_X GRID_MAX_POINTS_X #define ABL_BG_POINTS_Y GRID_MAX_POINTS_Y #define ABL_BG_GRID(X,Y) z_values[X][Y] #endif // Get the Z adjustment for non-linear bed leveling -float bilinear_z_offset(const float raw[XYZ]) { +float bilinear_z_offset(const xy_pos_t &raw) { - static float z1, d2, z3, d4, L, D, ratio_x, ratio_y, - last_x = -999.999, last_y = -999.999; + static float z1, d2, z3, d4, L, D; + + static xy_pos_t prev { -999.999, -999.999 }, ratio; // Whole units for the grid line indices. Constrained within bounds. - static int8_t gridx, gridy, nextx, nexty, - last_gridx = -99, last_gridy = -99; + static xy_int8_t thisg, nextg, lastg { -99, -99 }; // XY relative to the probed area - const float rx = raw[X_AXIS] - bilinear_start[X_AXIS], - ry = raw[Y_AXIS] - bilinear_start[Y_AXIS]; + xy_pos_t rel = raw - bilinear_start.asFloat(); #if ENABLED(EXTRAPOLATE_BEYOND_GRID) #define FAR_EDGE_OR_BOX 2 // Keep using the last grid box @@ -286,63 +282,62 @@ float bilinear_z_offset(const float raw[XYZ]) { #define FAR_EDGE_OR_BOX 1 // Just use the grid far edge #endif - if (last_x != rx) { - last_x = rx; - ratio_x = rx * ABL_BG_FACTOR(X_AXIS); - const float gx = constrain(FLOOR(ratio_x), 0, ABL_BG_POINTS_X - (FAR_EDGE_OR_BOX)); - ratio_x -= gx; // Subtract whole to get the ratio within the grid box + if (prev.x != rel.x) { + prev.x = rel.x; + ratio.x = rel.x * ABL_BG_FACTOR(x); + const float gx = constrain(FLOOR(ratio.x), 0, ABL_BG_POINTS_X - (FAR_EDGE_OR_BOX)); + ratio.x -= gx; // Subtract whole to get the ratio within the grid box #if DISABLED(EXTRAPOLATE_BEYOND_GRID) // Beyond the grid maintain height at grid edges - NOLESS(ratio_x, 0); // Never < 0.0. (> 1.0 is ok when nextx==gridx.) + NOLESS(ratio.x, 0); // Never <0 (>1 is ok when nextg.x==thisg.x) #endif - gridx = gx; - nextx = _MIN(gridx + 1, ABL_BG_POINTS_X - 1); + thisg.x = gx; + nextg.x = _MIN(thisg.x + 1, ABL_BG_POINTS_X - 1); } - if (last_y != ry || last_gridx != gridx) { + if (prev.y != rel.y || lastg.x != thisg.x) { - if (last_y != ry) { - last_y = ry; - ratio_y = ry * ABL_BG_FACTOR(Y_AXIS); - const float gy = constrain(FLOOR(ratio_y), 0, ABL_BG_POINTS_Y - (FAR_EDGE_OR_BOX)); - ratio_y -= gy; + if (prev.y != rel.y) { + prev.y = rel.y; + ratio.y = rel.y * ABL_BG_FACTOR(y); + const float gy = constrain(FLOOR(ratio.y), 0, ABL_BG_POINTS_Y - (FAR_EDGE_OR_BOX)); + ratio.y -= gy; #if DISABLED(EXTRAPOLATE_BEYOND_GRID) // Beyond the grid maintain height at grid edges - NOLESS(ratio_y, 0); // Never < 0.0. (> 1.0 is ok when nexty==gridy.) + NOLESS(ratio.y, 0); // Never < 0.0. (> 1.0 is ok when nextg.y==thisg.y.) #endif - gridy = gy; - nexty = _MIN(gridy + 1, ABL_BG_POINTS_Y - 1); + thisg.y = gy; + nextg.y = _MIN(thisg.y + 1, ABL_BG_POINTS_Y - 1); } - if (last_gridx != gridx || last_gridy != gridy) { - last_gridx = gridx; - last_gridy = gridy; + if (lastg != thisg) { + lastg = thisg; // Z at the box corners - z1 = ABL_BG_GRID(gridx, gridy); // left-front - d2 = ABL_BG_GRID(gridx, nexty) - z1; // left-back (delta) - z3 = ABL_BG_GRID(nextx, gridy); // right-front - d4 = ABL_BG_GRID(nextx, nexty) - z3; // right-back (delta) + z1 = ABL_BG_GRID(thisg.x, thisg.y); // left-front + d2 = ABL_BG_GRID(thisg.x, nextg.y) - z1; // left-back (delta) + z3 = ABL_BG_GRID(nextg.x, thisg.y); // right-front + d4 = ABL_BG_GRID(nextg.x, nextg.y) - z3; // right-back (delta) } - // Bilinear interpolate. Needed since ry or gridx has changed. - L = z1 + d2 * ratio_y; // Linear interp. LF -> LB - const float R = z3 + d4 * ratio_y; // Linear interp. RF -> RB + // Bilinear interpolate. Needed since rel.y or thisg.x has changed. + L = z1 + d2 * ratio.y; // Linear interp. LF -> LB + const float R = z3 + d4 * ratio.y; // Linear interp. RF -> RB D = R - L; } - const float offset = L + ratio_x * D; // the offset almost always changes + const float offset = L + ratio.x * D; // the offset almost always changes /* static float last_offset = 0; if (ABS(last_offset - offset) > 0.2) { - SERIAL_ECHOLNPAIR("Sudden Shift at x=", rx, " / ", bilinear_grid_spacing[X_AXIS], " -> gridx=", gridx); - SERIAL_ECHOLNPAIR(" y=", ry, " / ", bilinear_grid_spacing[Y_AXIS], " -> gridy=", gridy); - SERIAL_ECHOLNPAIR(" ratio_x=", ratio_x, " ratio_y=", ratio_y); + SERIAL_ECHOLNPAIR("Sudden Shift at x=", rel.x, " / ", bilinear_grid_spacing.x, " -> thisg.x=", thisg.x); + SERIAL_ECHOLNPAIR(" y=", rel.y, " / ", bilinear_grid_spacing.y, " -> thisg.y=", thisg.y); + SERIAL_ECHOLNPAIR(" ratio.x=", ratio.x, " ratio.y=", ratio.y); SERIAL_ECHOLNPAIR(" z1=", z1, " z2=", z2, " z3=", z3, " z4=", z4); SERIAL_ECHOLNPAIR(" L=", L, " R=", R, " offset=", offset); } @@ -354,7 +349,7 @@ float bilinear_z_offset(const float raw[XYZ]) { #if IS_CARTESIAN && DISABLED(SEGMENT_LEVELED_MOVES) - #define CELL_INDEX(A,V) ((V - bilinear_start[_AXIS(A)]) * ABL_BG_FACTOR(_AXIS(A))) + #define CELL_INDEX(A,V) ((V - bilinear_start.A) * ABL_BG_FACTOR(A)) /** * Prepare a bilinear-leveled linear move on Cartesian, @@ -362,62 +357,61 @@ float bilinear_z_offset(const float raw[XYZ]) { */ void bilinear_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 - int cx1 = CELL_INDEX(X, current_position[X_AXIS]), - cy1 = CELL_INDEX(Y, current_position[Y_AXIS]), - cx2 = CELL_INDEX(X, destination[X_AXIS]), - cy2 = CELL_INDEX(Y, destination[Y_AXIS]); - LIMIT(cx1, 0, ABL_BG_POINTS_X - 2); - LIMIT(cy1, 0, ABL_BG_POINTS_Y - 2); - LIMIT(cx2, 0, ABL_BG_POINTS_X - 2); - LIMIT(cy2, 0, ABL_BG_POINTS_Y - 2); + 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) }; + LIMIT(c1.x, 0, ABL_BG_POINTS_X - 2); + LIMIT(c1.y, 0, ABL_BG_POINTS_Y - 2); + LIMIT(c2.x, 0, ABL_BG_POINTS_X - 2); + LIMIT(c2.y, 0, ABL_BG_POINTS_Y - 2); // Start and end in the same cell? No split needed. - if (cx1 == cx2 && cy1 == cy2) { - set_current_from_destination(); + if (c1 == c2) { + current_position = destination; line_to_current_position(scaled_fr_mm_s); return; } - #define LINE_SEGMENT_END(A) (current_position[_AXIS(A)] + (destination[_AXIS(A)] - current_position[_AXIS(A)]) * normalized_dist) + #define LINE_SEGMENT_END(A) (current_position.A + (destination.A - current_position.A) * normalized_dist) - float normalized_dist, end[XYZE]; - const int8_t gcx = _MAX(cx1, cx2), gcy = _MAX(cy1, cy2); + float normalized_dist; + xyze_pos_t end; + const xy_int8_t gc { _MAX(c1.x, c2.x), _MAX(c1.y, c2.y) }; // Crosses on the X and not already split on this X? // The x_splits flags are insurance against rounding errors. - if (cx2 != cx1 && TEST(x_splits, gcx)) { + if (c2.x != c1.x && TEST(x_splits, gc.x)) { // Split on the X grid line - CBI(x_splits, gcx); - COPY(end, destination); - destination[X_AXIS] = bilinear_start[X_AXIS] + ABL_BG_SPACING(X_AXIS) * gcx; - normalized_dist = (destination[X_AXIS] - current_position[X_AXIS]) / (end[X_AXIS] - current_position[X_AXIS]); - destination[Y_AXIS] = LINE_SEGMENT_END(Y); + CBI(x_splits, gc.x); + end = destination; + destination.x = bilinear_start.x + ABL_BG_SPACING(x) * gc.x; + normalized_dist = (destination.x - current_position.x) / (end.x - current_position.x); + destination.y = LINE_SEGMENT_END(y); } // Crosses on the Y and not already split on this Y? - else if (cy2 != cy1 && TEST(y_splits, gcy)) { + else if (c2.y != c1.y && TEST(y_splits, gc.y)) { // Split on the Y grid line - CBI(y_splits, gcy); - COPY(end, destination); - destination[Y_AXIS] = bilinear_start[Y_AXIS] + ABL_BG_SPACING(Y_AXIS) * gcy; - normalized_dist = (destination[Y_AXIS] - current_position[Y_AXIS]) / (end[Y_AXIS] - current_position[Y_AXIS]); - destination[X_AXIS] = LINE_SEGMENT_END(X); + CBI(y_splits, gc.y); + end = destination; + destination.y = bilinear_start.y + ABL_BG_SPACING(y) * gc.y; + normalized_dist = (destination.y - current_position.y) / (end.y - current_position.y); + destination.x = LINE_SEGMENT_END(x); } else { // Must already have been split on these border(s) // This should be a rare case. - set_current_from_destination(); + current_position = destination; line_to_current_position(scaled_fr_mm_s); return; } - destination[Z_AXIS] = LINE_SEGMENT_END(Z); - destination[E_AXIS] = LINE_SEGMENT_END(E); + destination.z = LINE_SEGMENT_END(z); + destination.e = LINE_SEGMENT_END(e); // Do the split and look for more borders bilinear_line_to_destination(scaled_fr_mm_s, x_splits, y_splits); // Restore destination from stack - COPY(destination, end); + destination = end; bilinear_line_to_destination(scaled_fr_mm_s, x_splits, y_splits); } diff --git a/Marlin/src/feature/bedlevel/abl/abl.h b/Marlin/src/feature/bedlevel/abl/abl.h index 71c7d8363..84ab853f8 100644 --- a/Marlin/src/feature/bedlevel/abl/abl.h +++ b/Marlin/src/feature/bedlevel/abl/abl.h @@ -23,10 +23,10 @@ #include "../../../inc/MarlinConfigPre.h" -extern int bilinear_grid_spacing[2], bilinear_start[2]; -extern float bilinear_grid_factor[2], - z_values[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y]; -float bilinear_z_offset(const float raw[XYZ]); +extern xy_int_t bilinear_grid_spacing, bilinear_start; +extern xy_float_t bilinear_grid_factor; +extern bed_mesh_t z_values; +float bilinear_z_offset(const xy_pos_t &raw); void extrapolate_unprobed_bed_level(); void print_bilinear_leveling_grid(); @@ -40,6 +40,6 @@ void refresh_bed_level(); void bilinear_line_to_destination(const feedRate_t &scaled_fr_mm_s, uint16_t x_splits=0xFFFF, uint16_t y_splits=0xFFFF); #endif -#define _GET_MESH_X(I) (bilinear_start[X_AXIS] + (I) * bilinear_grid_spacing[X_AXIS]) -#define _GET_MESH_Y(J) (bilinear_start[Y_AXIS] + (J) * bilinear_grid_spacing[Y_AXIS]) +#define _GET_MESH_X(I) float(bilinear_start.x + (I) * bilinear_grid_spacing.x) +#define _GET_MESH_Y(J) float(bilinear_start.y + (J) * bilinear_grid_spacing.y) #define Z_VALUES_ARR z_values diff --git a/Marlin/src/feature/bedlevel/bedlevel.cpp b/Marlin/src/feature/bedlevel/bedlevel.cpp index f4a17b003..d92f903a9 100644 --- a/Marlin/src/feature/bedlevel/bedlevel.cpp +++ b/Marlin/src/feature/bedlevel/bedlevel.cpp @@ -51,7 +51,7 @@ bool leveling_is_valid() { #if ENABLED(MESH_BED_LEVELING) mbl.has_mesh() #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) - !!bilinear_grid_spacing[X_AXIS] + !!bilinear_grid_spacing.x #elif ENABLED(AUTO_BED_LEVELING_UBL) ubl.mesh_is_valid() #else // 3POINT, LINEAR @@ -81,13 +81,13 @@ void set_bed_leveling_enabled(const bool enable/*=true*/) { #if ENABLED(AUTO_BED_LEVELING_BILINEAR) // Force bilinear_z_offset to re-calculate next time - const float reset[XYZ] = { -9999.999, -9999.999, 0 }; + const xyz_pos_t reset { -9999.999, -9999.999, 0 }; (void)bilinear_z_offset(reset); #endif if (planner.leveling_active) { // leveling from on to off // change unleveled current_position to physical current_position without moving steppers. - planner.apply_leveling(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS]); + planner.apply_leveling(current_position); planner.leveling_active = false; // disable only AFTER calling apply_leveling } else { // leveling from off to on @@ -116,9 +116,9 @@ TemporaryBedLevelingState::TemporaryBedLevelingState(const bool enable) : saved( planner.set_z_fade_height(zfh); if (leveling_was_active) { - const float oldpos[] = { current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS] }; + const xyz_pos_t oldpos = current_position; set_bed_leveling_enabled(true); - if (do_report && memcmp(oldpos, current_position, sizeof(oldpos))) + if (do_report && oldpos != current_position) report_current_position(); } } @@ -137,8 +137,8 @@ void reset_bed_level() { #if ENABLED(MESH_BED_LEVELING) mbl.reset(); #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) - bilinear_start[X_AXIS] = bilinear_start[Y_AXIS] = - bilinear_grid_spacing[X_AXIS] = bilinear_grid_spacing[Y_AXIS] = 0; + bilinear_start.reset(); + bilinear_grid_spacing.reset(); for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) { z_values[x][y] = NAN; @@ -223,25 +223,25 @@ void reset_bed_level() { #if EITHER(MESH_BED_LEVELING, PROBE_MANUALLY) - void _manual_goto_xy(const float &rx, const float &ry) { + void _manual_goto_xy(const xy_pos_t &pos) { #ifdef MANUAL_PROBE_START_Z + constexpr float startz = _MAX(0, MANUAL_PROBE_START_Z); #if MANUAL_PROBE_HEIGHT > 0 - do_blocking_move_to(rx, ry, MANUAL_PROBE_HEIGHT); - do_blocking_move_to_z(_MAX(0,MANUAL_PROBE_START_Z)); + do_blocking_move_to(pos, MANUAL_PROBE_HEIGHT); + do_blocking_move_to_z(startz); #else - do_blocking_move_to(rx, ry, _MAX(0,MANUAL_PROBE_START_Z)); + do_blocking_move_to(pos, startz); #endif #elif MANUAL_PROBE_HEIGHT > 0 - const float prev_z = current_position[Z_AXIS]; - do_blocking_move_to(rx, ry, MANUAL_PROBE_HEIGHT); + const float prev_z = current_position.z; + do_blocking_move_to(pos, MANUAL_PROBE_HEIGHT); do_blocking_move_to_z(prev_z); #else - do_blocking_move_to_xy(rx, ry); + do_blocking_move_to_xy(pos); #endif - current_position[X_AXIS] = rx; - current_position[Y_AXIS] = ry; + current_position = pos; #if ENABLED(LCD_BED_LEVELING) ui.wait_for_bl_move = false; diff --git a/Marlin/src/feature/bedlevel/bedlevel.h b/Marlin/src/feature/bedlevel/bedlevel.h index d01751407..6ba094888 100644 --- a/Marlin/src/feature/bedlevel/bedlevel.h +++ b/Marlin/src/feature/bedlevel/bedlevel.h @@ -38,7 +38,7 @@ void reset_bed_level(); #endif #if EITHER(MESH_BED_LEVELING, PROBE_MANUALLY) - void _manual_goto_xy(const float &x, const float &y); + void _manual_goto_xy(const xy_pos_t &pos); #endif /** @@ -57,11 +57,6 @@ class TemporaryBedLevelingState { typedef float bed_mesh_t[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y]; - typedef struct { - int8_t x_index, y_index; - float distance; // When populated, the distance from the search location - } mesh_index_pair; - #if ENABLED(AUTO_BED_LEVELING_BILINEAR) #include "abl/abl.h" #elif ENABLED(AUTO_BED_LEVELING_UBL) @@ -71,6 +66,7 @@ class TemporaryBedLevelingState { #endif #define Z_VALUES(X,Y) Z_VALUES_ARR[X][Y] + #define _GET_MESH_POS(M) { _GET_MESH_X(M.a), _GET_MESH_Y(M.b) } #if EITHER(AUTO_BED_LEVELING_BILINEAR, MESH_BED_LEVELING) @@ -85,4 +81,18 @@ class TemporaryBedLevelingState { #endif + struct mesh_index_pair { + xy_int8_t pos; + float distance; // When populated, the distance from the search location + void invalidate() { pos = -1; } + bool valid() const { return pos.x >= 0 && pos.y >= 0; } + #if ENABLED(AUTO_BED_LEVELING_UBL) + xy_pos_t meshpos() { + return { ubl.mesh_index_to_xpos(pos.x), ubl.mesh_index_to_ypos(pos.y) }; + } + #endif + operator xy_int8_t&() { return pos; } + operator const xy_int8_t&() const { return pos; } + }; + #endif diff --git a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp index b3a1a1352..af9c671d6 100644 --- a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp +++ b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.cpp @@ -24,10 +24,9 @@ #if ENABLED(MESH_BED_LEVELING) - #include "mesh_bed_leveling.h" + #include "../bedlevel.h" #include "../../../module/motion.h" - #include "../../../feature/bedlevel/bedlevel.h" #if ENABLED(EXTENSIBLE_UI) #include "../../../lcd/extensible_ui/ui_api.h" @@ -66,62 +65,60 @@ */ 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 - int cx1 = cell_index_x(current_position[X_AXIS]), - cy1 = cell_index_y(current_position[Y_AXIS]), - cx2 = cell_index_x(destination[X_AXIS]), - cy2 = cell_index_y(destination[Y_AXIS]); - NOMORE(cx1, GRID_MAX_POINTS_X - 2); - NOMORE(cy1, GRID_MAX_POINTS_Y - 2); - NOMORE(cx2, GRID_MAX_POINTS_X - 2); - NOMORE(cy2, GRID_MAX_POINTS_Y - 2); + xy_int8_t scel = cell_indexes(current_position), ecel = cell_indexes(destination); + NOMORE(scel.x, GRID_MAX_POINTS_X - 2); + NOMORE(scel.y, GRID_MAX_POINTS_Y - 2); + NOMORE(ecel.x, GRID_MAX_POINTS_X - 2); + NOMORE(ecel.y, GRID_MAX_POINTS_Y - 2); // Start and end in the same cell? No split needed. - if (cx1 == cx2 && cy1 == cy2) { + if (scel == ecel) { line_to_destination(scaled_fr_mm_s); - set_current_from_destination(); + current_position = destination; return; } - #define MBL_SEGMENT_END(A) (current_position[_AXIS(A)] + (destination[_AXIS(A)] - current_position[_AXIS(A)]) * normalized_dist) + #define MBL_SEGMENT_END(A) (current_position.A + (destination.A - current_position.A) * normalized_dist) - float normalized_dist, end[XYZE]; - const int8_t gcx = _MAX(cx1, cx2), gcy = _MAX(cy1, cy2); + float normalized_dist; + xyze_pos_t dest; + const int8_t gcx = _MAX(scel.x, ecel.x), gcy = _MAX(scel.y, ecel.y); // Crosses on the X and not already split on this X? // The x_splits flags are insurance against rounding errors. - if (cx2 != cx1 && TEST(x_splits, gcx)) { + if (ecel.x != scel.x && TEST(x_splits, gcx)) { // Split on the X grid line CBI(x_splits, gcx); - COPY(end, destination); - destination[X_AXIS] = index_to_xpos[gcx]; - normalized_dist = (destination[X_AXIS] - current_position[X_AXIS]) / (end[X_AXIS] - current_position[X_AXIS]); - destination[Y_AXIS] = MBL_SEGMENT_END(Y); + dest = destination; + destination.x = index_to_xpos[gcx]; + normalized_dist = (destination.x - current_position.x) / (dest.x - current_position.x); + destination.y = MBL_SEGMENT_END(y); } // Crosses on the Y and not already split on this Y? - else if (cy2 != cy1 && TEST(y_splits, gcy)) { + else if (ecel.y != scel.y && TEST(y_splits, gcy)) { // Split on the Y grid line CBI(y_splits, gcy); - COPY(end, destination); - destination[Y_AXIS] = index_to_ypos[gcy]; - normalized_dist = (destination[Y_AXIS] - current_position[Y_AXIS]) / (end[Y_AXIS] - current_position[Y_AXIS]); - destination[X_AXIS] = MBL_SEGMENT_END(X); + dest = destination; + destination.y = index_to_ypos[gcy]; + normalized_dist = (destination.y - current_position.y) / (dest.y - current_position.y); + destination.x = MBL_SEGMENT_END(x); } else { // Must already have been split on these border(s) // This should be a rare case. line_to_destination(scaled_fr_mm_s); - set_current_from_destination(); + current_position = destination; return; } - destination[Z_AXIS] = MBL_SEGMENT_END(Z); - destination[E_AXIS] = MBL_SEGMENT_END(E); + destination.z = MBL_SEGMENT_END(z); + destination.e = MBL_SEGMENT_END(e); // Do the split and look for more borders line_to_destination(scaled_fr_mm_s, x_splits, y_splits); // Restore destination from stack - COPY(destination, end); + destination = dest; line_to_destination(scaled_fr_mm_s, x_splits, y_splits); } diff --git a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h index def380399..3009f4aea 100644 --- a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h +++ b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h @@ -76,21 +76,27 @@ public: int8_t cx = (x - (MESH_MIN_X)) * RECIPROCAL(MESH_X_DIST); return constrain(cx, 0, (GRID_MAX_POINTS_X) - 2); } - static int8_t cell_index_y(const float &y) { int8_t cy = (y - (MESH_MIN_Y)) * RECIPROCAL(MESH_Y_DIST); return constrain(cy, 0, (GRID_MAX_POINTS_Y) - 2); } + static inline xy_int8_t cell_indexes(const float &x, const float &y) { + return { cell_index_x(x), cell_index_y(y) }; + } + static inline xy_int8_t cell_indexes(const xy_pos_t &xy) { return cell_indexes(xy.x, xy.y); } 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 &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 inline xy_int8_t probe_indexes(const float &x, const float &y) { + return { probe_index_x(x), probe_index_y(y) }; + } + static inline xy_int8_t probe_indexes(const xy_pos_t &xy) { return probe_indexes(xy.x, xy.y); } 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), @@ -98,21 +104,21 @@ public: return z1 + delta_a * delta_z; } - static float get_z(const float &x0, const float &y0 + static float get_z(const xy_pos_t &pos #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - , const float &factor + , const float &factor=1.0f #endif ) { - const int8_t cx = cell_index_x(x0), cy = cell_index_y(y0); - const float z1 = calc_z0(x0, index_to_xpos[cx], z_values[cx][cy], index_to_xpos[cx + 1], z_values[cx + 1][cy]), - z2 = calc_z0(x0, index_to_xpos[cx], z_values[cx][cy + 1], index_to_xpos[cx + 1], z_values[cx + 1][cy + 1]), - z0 = calc_z0(y0, index_to_ypos[cy], z1, index_to_ypos[cy + 1], z2); - - return z_offset + z0 - #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - * factor - #endif - ; + #if DISABLED(ENABLE_LEVELING_FADE_HEIGHT) + constexpr float factor = 1.0f; + #endif + const xy_int8_t ind = cell_indexes(pos); + const float x1 = index_to_xpos[ind.x], x2 = index_to_xpos[ind.x+1], + y1 = index_to_xpos[ind.y], y2 = index_to_xpos[ind.y+1], + z1 = calc_z0(pos.x, x1, z_values[ind.x][ind.y ], x2, z_values[ind.x+1][ind.y ]), + z2 = calc_z0(pos.x, x1, z_values[ind.x][ind.y+1], x2, z_values[ind.x+1][ind.y+1]); + + return z_offset + calc_z0(pos.y, y1, z1, y2, z2) * factor; } #if IS_CARTESIAN && DISABLED(SEGMENT_LEVELED_MOVES) diff --git a/Marlin/src/feature/bedlevel/ubl/ubl.cpp b/Marlin/src/feature/bedlevel/ubl/ubl.cpp index 4cdc4721b..259ee1096 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl.cpp @@ -176,8 +176,7 @@ // Add XY probe offset from extruder because probe_at_point() subtracts them when // moving to the XY position to be measured. This ensures better agreement between // the current Z position after G28 and the mesh values. - const float current_xi = find_closest_x_index(current_position[X_AXIS] + probe_offset[X_AXIS]), - current_yi = find_closest_y_index(current_position[Y_AXIS] + probe_offset[Y_AXIS]); + const xy_int8_t curr = closest_indexes(xy_pos_t(current_position) + xy_pos_t(probe_offset)); if (!lcd) SERIAL_EOL(); for (int8_t j = GRID_MAX_POINTS_Y - 1; j >= 0; j--) { @@ -193,7 +192,7 @@ for (uint8_t i = 0; i < GRID_MAX_POINTS_X; i++) { // Opening Brace or Space - const bool is_current = i == current_xi && j == current_yi; + const bool is_current = i == curr.x && j == curr.y; if (human) SERIAL_CHAR(is_current ? '[' : ' '); // Z Value at current I, J diff --git a/Marlin/src/feature/bedlevel/ubl/ubl.h b/Marlin/src/feature/bedlevel/ubl/ubl.h index 6897217c3..2202bb652 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl.h +++ b/Marlin/src/feature/bedlevel/ubl/ubl.h @@ -32,15 +32,12 @@ #define UBL_OK false #define UBL_ERR true -#define USE_NOZZLE_AS_REFERENCE 0 -#define USE_PROBE_AS_REFERENCE 1 - -// ubl_G29.cpp - enum MeshPointType : char { INVALID, REAL, SET_IN_BITMAP }; // External references +struct mesh_index_pair; + #define MESH_X_DIST (float(MESH_MAX_X - (MESH_MIN_X)) / float(GRID_MAX_POINTS_X - 1)) #define MESH_Y_DIST (float(MESH_MAX_Y - (MESH_MIN_Y)) / float(GRID_MAX_POINTS_Y - 1)) @@ -52,10 +49,11 @@ class unified_bed_leveling { g29_repetition_cnt, g29_storage_slot, g29_map_type; - static bool g29_c_flag, g29_x_flag, g29_y_flag; - static float g29_x_pos, g29_y_pos, - g29_card_thickness, + static bool g29_c_flag; + static float g29_card_thickness, g29_constant; + static xy_pos_t g29_pos; + static xy_bool_t xy_seen; #if HAS_BED_PROBE static int g29_grid_size; @@ -65,16 +63,19 @@ class unified_bed_leveling { static void move_z_with_encoder(const float &multiplier); static float measure_point_with_encoder(); static float measure_business_card_thickness(float in_height); - static void manually_probe_remaining_mesh(const float&, const float&, const float&, const float&, const bool) _O0; - static void fine_tune_mesh(const float &rx, const float &ry, const bool do_ubl_mesh_map) _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_parameter_parsing() _O0; static void shift_mesh_height(); - static void probe_entire_mesh(const float &rx, const float &ry, const bool do_ubl_mesh_map, const bool stow_probe, const bool do_furthest) _O0; + 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_3pts(const float &z1, const float &z2, const float &z3); 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); + static inline bool smart_fill_one(const xy_uint8_t &pos, const xy_uint8_t &dir) { + return smart_fill_one(pos.x, pos.y, dir.x, dir.y); + } static void smart_fill_mesh(); #if ENABLED(UBL_DEVEL_DEBUGGING) @@ -91,7 +92,7 @@ class unified_bed_leveling { static void save_ubl_active_state_and_disable(); static void restore_ubl_active_state_and_leave(); static void display_map(const int) _O0; - static mesh_index_pair find_closest_mesh_point_of_type(const MeshPointType, const float&, const float&, const bool, uint16_t[16]) _O0; + static mesh_index_pair find_closest_mesh_point_of_type(const MeshPointType, const xy_pos_t&, const bool=false, MeshFlags *done_flags=nullptr) _O0; static mesh_index_pair find_furthest_invalid_mesh_point() _O0; static void reset(); static void invalidate(); @@ -118,14 +119,14 @@ class unified_bed_leveling { 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 get_cell_index_x(const float &x) { + static int8_t cell_index_x(const float &x) { const int8_t cx = (x - (MESH_MIN_X)) * RECIPROCAL(MESH_X_DIST); return constrain(cx, 0, (GRID_MAX_POINTS_X) - 1); // -1 is appropriate if we want all movement to the X_MAX } // position. But with this defined this way, it is possible // to extrapolate off of this point even further out. Probably // that is OK because something else should be keeping that from // happening and should not be worried about at this level. - static int8_t get_cell_index_y(const float &y) { + static int8_t cell_index_y(const float &y) { const int8_t cy = (y - (MESH_MIN_Y)) * RECIPROCAL(MESH_Y_DIST); return constrain(cy, 0, (GRID_MAX_POINTS_Y) - 1); // -1 is appropriate if we want all movement to the Y_MAX } // position. But with this defined this way, it is possible @@ -133,15 +134,22 @@ class unified_bed_leveling { // that is OK because something else should be keeping that from // happening and should not be worried about at this level. - static int8_t find_closest_x_index(const float &x) { + static inline xy_int8_t cell_indexes(const float &x, const float &y) { + return { cell_index_x(x), cell_index_y(y) }; + } + static inline xy_int8_t cell_indexes(const xy_pos_t &xy) { return cell_indexes(xy.x, xy.y); } + + 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 find_closest_y_index(const float &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; } + static inline xy_int8_t closest_indexes(const xy_pos_t &xy) { + return { closest_x_index(xy.x), closest_y_index(xy.y) }; + } /** * z2 --| @@ -228,8 +236,7 @@ class unified_bed_leveling { * on the Y position within the cell. */ static float get_z_correction(const float &rx0, const float &ry0) { - const int8_t cx = get_cell_index_x(rx0), - cy = get_cell_index_y(ry0); // return values are clamped + const int8_t cx = cell_index_x(rx0), cy = cell_index_y(ry0); // return values are clamped /** * Check if the requested location is off the mesh. If so, and @@ -275,11 +282,11 @@ class unified_bed_leveling { } return z0; } + static inline float get_z_correction(const xy_pos_t &pos) { return get_z_correction(pos.x, pos.y); } static inline float mesh_index_to_xpos(const uint8_t i) { return i < GRID_MAX_POINTS_X ? pgm_read_float(&_mesh_index_to_xpos[i]) : MESH_MIN_X + i * (MESH_X_DIST); } - static inline float mesh_index_to_ypos(const uint8_t i) { return i < GRID_MAX_POINTS_Y ? pgm_read_float(&_mesh_index_to_ypos[i]) : MESH_MIN_Y + i * (MESH_Y_DIST); } diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index 54c7666ba..6005e9881 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -53,8 +53,6 @@ #define UBL_G29_P31 - extern float destination[XYZE], current_position[XYZE]; - #if HAS_LCD_MENU void _lcd_ubl_output_map_lcd(); #endif @@ -67,13 +65,11 @@ unified_bed_leveling::g29_repetition_cnt, unified_bed_leveling::g29_storage_slot = 0, unified_bed_leveling::g29_map_type; - bool unified_bed_leveling::g29_c_flag, - unified_bed_leveling::g29_x_flag, - unified_bed_leveling::g29_y_flag; - float unified_bed_leveling::g29_x_pos, - unified_bed_leveling::g29_y_pos, - unified_bed_leveling::g29_card_thickness = 0, + bool unified_bed_leveling::g29_c_flag; + float unified_bed_leveling::g29_card_thickness = 0, unified_bed_leveling::g29_constant = 0; + xy_bool_t unified_bed_leveling::xy_seen; + xy_pos_t unified_bed_leveling::g29_pos; #if HAS_BED_PROBE int unified_bed_leveling::g29_grid_size; @@ -330,18 +326,19 @@ else { while (g29_repetition_cnt--) { if (cnt > 20) { cnt = 0; idle(); } - const mesh_index_pair location = find_closest_mesh_point_of_type(REAL, g29_x_pos, g29_y_pos, USE_NOZZLE_AS_REFERENCE, nullptr); - if (location.x_index < 0) { - // No more REACHABLE mesh points to invalidate, so we ASSUME the user + const mesh_index_pair closest = find_closest_mesh_point_of_type(REAL, g29_pos); + const xy_int8_t &cpos = closest.pos; + if (cpos.x < 0) { + // No more REAL mesh points to invalidate, so we ASSUME the user // meant to invalidate the ENTIRE mesh, which cannot be done with - // find_closest_mesh_point loop which only returns REACHABLE points. + // find_closest_mesh_point loop which only returns REAL points. set_all_mesh_points_to_value(NAN); SERIAL_ECHOLNPGM("Entire Mesh invalidated.\n"); break; // No more invalid Mesh Points to populate } - z_values[location.x_index][location.y_index] = NAN; + z_values[cpos.x][cpos.y] = NAN; #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(location.x_index, location.y_index, 0); + ExtUI::onMeshUpdate(closest, 0); #endif cnt++; } @@ -448,13 +445,13 @@ SERIAL_ECHOLNPGM("Mesh invalidated. Probing mesh."); } if (g29_verbose_level > 1) { - SERIAL_ECHOPAIR("Probing around (", g29_x_pos); + SERIAL_ECHOPAIR("Probing around (", g29_pos.x); SERIAL_CHAR(','); - SERIAL_ECHO(g29_y_pos); + SERIAL_ECHO(g29_pos.y); SERIAL_ECHOLNPGM(").\n"); } - probe_entire_mesh(g29_x_pos + probe_offset[X_AXIS], g29_y_pos + probe_offset[Y_AXIS], - parser.seen('T'), parser.seen('E'), parser.seen('U')); + const xy_pos_t near = g29_pos + probe_offset; + probe_entire_mesh(near, parser.seen('T'), parser.seen('E'), parser.seen('U')); report_current_position(); probe_deployed = true; @@ -470,7 +467,7 @@ SERIAL_ECHOLNPGM("Manually probing unreachable mesh locations."); do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); - if (parser.seen('C') && !g29_x_flag && !g29_y_flag) { + if (parser.seen('C') && !xy_seen) { /** * Use a good default location for the path. * The flipped > and < operators in these comparisons is intentional. @@ -478,13 +475,14 @@ * It may make sense to have Delta printers default to the center of the bed. * Until that is decided, this can be forced with the X and Y parameters. */ - #if IS_KINEMATIC - g29_x_pos = X_HOME_POS; - g29_y_pos = Y_HOME_POS; - #else // cartesian - g29_x_pos = probe_offset[X_AXIS] > 0 ? X_BED_SIZE : 0; - g29_y_pos = probe_offset[Y_AXIS] < 0 ? Y_BED_SIZE : 0; - #endif + g29_pos.set( + #if IS_KINEMATIC + X_HOME_POS, Y_HOME_POS + #else + probe_offset.x > 0 ? X_BED_SIZE : 0, + probe_offset.y < 0 ? Y_BED_SIZE : 0 + #endif + ); } if (parser.seen('B')) { @@ -496,13 +494,13 @@ probe_deployed = true; } - if (!position_is_reachable(g29_x_pos, g29_y_pos)) { + if (!position_is_reachable(g29_pos)) { SERIAL_ECHOLNPGM("XY outside printable radius."); return; } const float height = parser.floatval('H', Z_CLEARANCE_BETWEEN_PROBES); - manually_probe_remaining_mesh(g29_x_pos, g29_y_pos, height, g29_card_thickness, parser.seen('T')); + manually_probe_remaining_mesh(g29_pos, height, g29_card_thickness, parser.seen('T')); SERIAL_ECHOLNPGM("G29 P2 finished."); @@ -530,20 +528,22 @@ } else { while (g29_repetition_cnt--) { // this only populates reachable mesh points near - const mesh_index_pair location = find_closest_mesh_point_of_type(INVALID, g29_x_pos, g29_y_pos, USE_NOZZLE_AS_REFERENCE, nullptr); - if (location.x_index < 0) { - // No more REACHABLE INVALID mesh points to populate, so we ASSUME + const mesh_index_pair closest = find_closest_mesh_point_of_type(INVALID, g29_pos); + const xy_int8_t &cpos = closest.pos; + if (cpos.x < 0) { + // No more REAL INVALID mesh points to populate, so we ASSUME // user meant to populate ALL INVALID mesh points to value for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) - if (isnan(z_values[x][y])) - z_values[x][y] = g29_constant; + if (isnan(z_values[x][y])) z_values[x][y] = g29_constant; break; // No more invalid Mesh Points to populate } - z_values[location.x_index][location.y_index] = g29_constant; - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(location.x_index, location.y_index, z_values[location.x_index][location.y_index]); - #endif + else { + z_values[cpos.x][cpos.y] = g29_constant; + #if ENABLED(EXTENSIBLE_UI) + ExtUI::onMeshUpdate(closest, g29_constant); + #endif + } } } } @@ -576,7 +576,7 @@ case 4: // Fine Tune (i.e., Edit) the Mesh #if HAS_LCD_MENU - fine_tune_mesh(g29_x_pos, g29_y_pos, parser.seen('T')); + fine_tune_mesh(g29_pos, parser.seen('T')); #else SERIAL_ECHOLNPGM("?P4 is only available when an LCD is present."); return; @@ -740,9 +740,7 @@ * Probe all invalidated locations of the mesh that can be reached by the probe. * This attempts to fill in locations closest to the nozzle's start location first. */ - void unified_bed_leveling::probe_entire_mesh(const float &rx, const float &ry, const bool do_ubl_mesh_map, const bool stow_probe, const bool do_furthest) { - mesh_index_pair location; - + void unified_bed_leveling::probe_entire_mesh(const xy_pos_t &near, const bool do_ubl_mesh_map, const bool stow_probe, const bool do_furthest) { #if HAS_LCD_MENU ui.capture(); #endif @@ -752,6 +750,7 @@ uint8_t count = GRID_MAX_POINTS; + mesh_index_pair best; do { if (do_ubl_mesh_map) display_map(g29_map_type); @@ -773,23 +772,23 @@ } #endif - if (do_furthest) - location = find_furthest_invalid_mesh_point(); - else - location = find_closest_mesh_point_of_type(INVALID, rx, ry, USE_PROBE_AS_REFERENCE, nullptr); + best = do_furthest + ? find_furthest_invalid_mesh_point() + : find_closest_mesh_point_of_type(INVALID, near, true); - if (location.x_index >= 0) { // mesh point found and is reachable by probe - const float rawx = mesh_index_to_xpos(location.x_index), - rawy = mesh_index_to_ypos(location.y_index), - measured_z = probe_at_point(rawx, rawy, stow_probe ? PROBE_PT_STOW : PROBE_PT_RAISE, g29_verbose_level); // TODO: Needs error handling - z_values[location.x_index][location.y_index] = measured_z; + if (best.pos.x >= 0) { // mesh point found and is reachable by probe + const float measured_z = probe_at_point( + best.meshpos(), + stow_probe ? PROBE_PT_STOW : PROBE_PT_RAISE, g29_verbose_level + ); + z_values[best.pos.x][best.pos.y] = measured_z; #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(location.x_index, location.y_index, measured_z); + ExtUI::onMeshUpdate(best, measured_z); #endif } SERIAL_FLUSH(); // Prevent host M105 buffer overrun. - } while (location.x_index >= 0 && --count); + } while (best.pos.x >= 0 && --count); STOW_PROBE(); @@ -800,8 +799,8 @@ restore_ubl_active_state_and_leave(); do_blocking_move_to_xy( - constrain(rx - probe_offset[X_AXIS], MESH_MIN_X, MESH_MAX_X), - constrain(ry - probe_offset[Y_AXIS], MESH_MIN_Y, MESH_MAX_Y) + constrain(near.x - probe_offset.x, MESH_MIN_X, MESH_MAX_X), + constrain(near.y - probe_offset.y, MESH_MIN_Y, MESH_MAX_Y) ); } @@ -835,7 +834,7 @@ idle(); gcode.reset_stepper_timeout(); // Keep steppers powered if (encoder_diff) { - do_blocking_move_to_z(current_position[Z_AXIS] + float(encoder_diff) * multiplier); + do_blocking_move_to_z(current_position.z + float(encoder_diff) * multiplier); encoder_diff = 0; } } @@ -844,7 +843,7 @@ float unified_bed_leveling::measure_point_with_encoder() { KEEPALIVE_STATE(PAUSED_FOR_USER); move_z_with_encoder(0.01f); - return current_position[Z_AXIS]; + return current_position.z; } static void echo_and_take_a_measurement() { SERIAL_ECHOLNPGM(" and take a measurement."); } @@ -863,7 +862,7 @@ echo_and_take_a_measurement(); const float z1 = measure_point_with_encoder(); - do_blocking_move_to_z(current_position[Z_AXIS] + SIZE_OF_LITTLE_RAISE); + do_blocking_move_to_z(current_position.z + SIZE_OF_LITTLE_RAISE); planner.synchronize(); SERIAL_ECHOPGM("Remove shim"); @@ -872,7 +871,7 @@ const float z2 = measure_point_with_encoder(); - do_blocking_move_to_z(current_position[Z_AXIS] + Z_CLEARANCE_BETWEEN_PROBES); + do_blocking_move_to_z(current_position.z + Z_CLEARANCE_BETWEEN_PROBES); const float thickness = ABS(z1 - z2); @@ -888,29 +887,33 @@ return thickness; } - void unified_bed_leveling::manually_probe_remaining_mesh(const float &rx, const float &ry, const float &z_clearance, const float &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(); save_ubl_active_state_and_disable(); // No bed level correction so only raw data is obtained - do_blocking_move_to(current_position[X_AXIS], current_position[Y_AXIS], z_clearance); + do_blocking_move_to(current_position.x, current_position.y, z_clearance); ui.return_to_status(); mesh_index_pair location; + xy_int8_t &lpos = location.pos; do { - location = find_closest_mesh_point_of_type(INVALID, rx, ry, USE_NOZZLE_AS_REFERENCE, nullptr); + location = find_closest_mesh_point_of_type(INVALID, pos); // It doesn't matter if the probe can't reach the NAN location. This is a manual probe. - if (location.x_index < 0 && location.y_index < 0) continue; + if (!location.valid()) continue; - const float xProbe = mesh_index_to_xpos(location.x_index), - yProbe = mesh_index_to_ypos(location.y_index); + const xyz_pos_t ppos = { + mesh_index_to_xpos(lpos.x), + mesh_index_to_ypos(lpos.y), + Z_CLEARANCE_BETWEEN_PROBES + }; - if (!position_is_reachable(xProbe, yProbe)) break; // SHOULD NOT OCCUR (find_closest_mesh_point only returns reachable points) + if (!position_is_reachable(ppos)) break; // SHOULD NOT OCCUR (find_closest_mesh_point only returns reachable points) LCD_MESSAGEPGM(MSG_UBL_MOVING_TO_NEXT); - do_blocking_move_to(xProbe, yProbe, Z_CLEARANCE_BETWEEN_PROBES); + do_blocking_move_to(ppos); do_blocking_move_to_z(z_clearance); KEEPALIVE_STATE(PAUSED_FOR_USER); @@ -932,20 +935,20 @@ return restore_ubl_active_state_and_leave(); } - z_values[location.x_index][location.y_index] = current_position[Z_AXIS] - thick; + z_values[lpos.x][lpos.y] = current_position.z - thick; #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(location.x_index, location.y_index, z_values[location.x_index][location.y_index]); + ExtUI::onMeshUpdate(location, z_values[lpos.x][lpos.y]); #endif if (g29_verbose_level > 2) - SERIAL_ECHOLNPAIR_F("Mesh Point Measured at: ", z_values[location.x_index][location.y_index], 6); + SERIAL_ECHOLNPAIR_F("Mesh Point Measured at: ", z_values[lpos.x][lpos.y], 6); SERIAL_FLUSH(); // Prevent host M105 buffer overrun. - } while (location.x_index >= 0 && location.y_index >= 0); + } while (location.valid()); if (do_ubl_mesh_map) display_map(g29_map_type); // show user where we're probing restore_ubl_active_state_and_leave(); - do_blocking_move_to(rx, ry, Z_CLEARANCE_DEPLOY_PROBE); + do_blocking_move_to(pos, Z_CLEARANCE_DEPLOY_PROBE); } inline void set_message_with_feedback(PGM_P const msg_P) { @@ -959,8 +962,8 @@ set_message_with_feedback(PSTR(MSG_EDITING_STOPPED)); } - void unified_bed_leveling::fine_tune_mesh(const float &rx, const float &ry, const bool do_ubl_mesh_map) { - if (!parser.seen('R')) // fine_tune_mesh() is special. If no repetition count flag is specified + void unified_bed_leveling::fine_tune_mesh(const xy_pos_t &pos, const bool do_ubl_mesh_map) { + if (!parser.seen('R')) // fine_tune_mesh() is special. If no repetition count flag is specified g29_repetition_cnt = 1; // do exactly one mesh location. Otherwise use what the parser decided. #if ENABLED(UBL_MESH_EDIT_MOVES_Z) @@ -973,7 +976,7 @@ mesh_index_pair location; - if (!position_is_reachable(rx, ry)) { + if (!position_is_reachable(pos)) { SERIAL_ECHOLNPGM("(X,Y) outside printable radius."); return; } @@ -981,76 +984,78 @@ save_ubl_active_state_and_disable(); LCD_MESSAGEPGM(MSG_UBL_FINE_TUNE_MESH); - ui.capture(); // Take over control of the LCD encoder + ui.capture(); // Take over control of the LCD encoder - do_blocking_move_to(rx, ry, Z_CLEARANCE_BETWEEN_PROBES); // Move to the given XY with probe clearance + do_blocking_move_to(pos, Z_CLEARANCE_BETWEEN_PROBES); // Move to the given XY with probe clearance #if ENABLED(UBL_MESH_EDIT_MOVES_Z) - do_blocking_move_to_z(h_offset); // Move Z to the given 'H' offset + do_blocking_move_to_z(h_offset); // Move Z to the given 'H' offset #endif - uint16_t not_done[16]; - memset(not_done, 0xFF, sizeof(not_done)); + MeshFlags done_flags{0}; + xy_int8_t &lpos = location.pos; do { - location = find_closest_mesh_point_of_type(SET_IN_BITMAP, rx, ry, USE_NOZZLE_AS_REFERENCE, not_done); - - if (location.x_index < 0) break; // Stop when there are no more reachable points + location = find_closest_mesh_point_of_type(SET_IN_BITMAP, pos, false, &done_flags); - bitmap_clear(not_done, location.x_index, location.y_index); // Mark this location as 'adjusted' so a new - // location is used on the next loop + if (lpos.x < 0) break; // Stop when there are no more reachable points - const float rawx = mesh_index_to_xpos(location.x_index), - rawy = mesh_index_to_ypos(location.y_index); + done_flags.mark(lpos); // Mark this location as 'adjusted' so a new + // location is used on the next loop + const xyz_pos_t raw = { + mesh_index_to_xpos(lpos.x), + mesh_index_to_ypos(lpos.y), + Z_CLEARANCE_BETWEEN_PROBES + }; - if (!position_is_reachable(rawx, rawy)) break; // SHOULD NOT OCCUR because find_closest_mesh_point_of_type will only return reachable + if (!position_is_reachable(raw)) break; // SHOULD NOT OCCUR (find_closest_mesh_point_of_type only returns reachable) - do_blocking_move_to(rawx, rawy, Z_CLEARANCE_BETWEEN_PROBES); // Move the nozzle to the edit point with probe clearance + do_blocking_move_to(raw); // Move the nozzle to the edit point with probe clearance #if ENABLED(UBL_MESH_EDIT_MOVES_Z) - do_blocking_move_to_z(h_offset); // Move Z to the given 'H' offset before editing + do_blocking_move_to_z(h_offset); // Move Z to the given 'H' offset before editing #endif KEEPALIVE_STATE(PAUSED_FOR_USER); - if (do_ubl_mesh_map) display_map(g29_map_type); // Display the current point + if (do_ubl_mesh_map) display_map(g29_map_type); // Display the current point ui.refresh(); - float new_z = z_values[location.x_index][location.y_index]; - if (isnan(new_z)) new_z = 0; // Invalid points begin at 0 - new_z = FLOOR(new_z * 1000) * 0.001f; // Chop off digits after the 1000ths place + float new_z = z_values[lpos.x][lpos.y]; + if (isnan(new_z)) new_z = 0; // Invalid points begin at 0 + new_z = FLOOR(new_z * 1000) * 0.001f; // Chop off digits after the 1000ths place lcd_mesh_edit_setup(new_z); do { new_z = lcd_mesh_edit(); #if ENABLED(UBL_MESH_EDIT_MOVES_Z) - do_blocking_move_to_z(h_offset + new_z); // Move the nozzle as the point is edited + do_blocking_move_to_z(h_offset + new_z); // Move the nozzle as the point is edited #endif idle(); - SERIAL_FLUSH(); // Prevent host M105 buffer overrun. + SERIAL_FLUSH(); // Prevent host M105 buffer overrun. } while (!ui.button_pressed()); - if (!lcd_map_control) ui.return_to_status(); // Just editing a single point? Return to status + if (!lcd_map_control) ui.return_to_status(); // Just editing a single point? Return to status - if (click_and_hold(abort_fine_tune)) break; // Button held down? Abort editing + if (click_and_hold(abort_fine_tune)) break; // Button held down? Abort editing - z_values[location.x_index][location.y_index] = new_z; // Save the updated Z value + z_values[lpos.x][lpos.y] = new_z; // Save the updated Z value #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(location.x_index, location.y_index, new_z); + ExtUI::onMeshUpdate(location, new_z); #endif - serial_delay(20); // No switch noise + serial_delay(20); // No switch noise ui.refresh(); - } while (location.x_index >= 0 && --g29_repetition_cnt > 0); + } while (lpos.x >= 0 && --g29_repetition_cnt > 0); ui.release(); if (do_ubl_mesh_map) display_map(g29_map_type); restore_ubl_active_state_and_leave(); - do_blocking_move_to(rx, ry, Z_CLEARANCE_BETWEEN_PROBES); + do_blocking_move_to(pos, Z_CLEARANCE_BETWEEN_PROBES); LCD_MESSAGEPGM(MSG_UBL_DONE_EDITING_MESH); SERIAL_ECHOLNPGM("Done Editing Mesh"); @@ -1073,11 +1078,6 @@ g29_constant = 0; g29_repetition_cnt = 0; - g29_x_flag = parser.seenval('X'); - g29_x_pos = g29_x_flag ? parser.value_float() : current_position[X_AXIS]; - g29_y_flag = parser.seenval('Y'); - g29_y_pos = g29_y_flag ? parser.value_float() : current_position[Y_AXIS]; - if (parser.seen('R')) { g29_repetition_cnt = parser.has_value() ? parser.value_int() : GRID_MAX_POINTS; NOMORE(g29_repetition_cnt, GRID_MAX_POINTS); @@ -1124,17 +1124,24 @@ #endif } - if (g29_x_flag != g29_y_flag) { + xy_seen.x = parser.seenval('X'); + float sx = xy_seen.x ? parser.value_float() : current_position.x; + xy_seen.y = parser.seenval('Y'); + float sy = xy_seen.y ? parser.value_float() : current_position.y; + + if (xy_seen.x != xy_seen.y) { SERIAL_ECHOLNPGM("Both X & Y locations must be specified.\n"); err_flag = true; } // If X or Y are not valid, use center of the bed values - if (!WITHIN(g29_x_pos, X_MIN_BED, X_MAX_BED)) g29_x_pos = X_CENTER; - if (!WITHIN(g29_y_pos, Y_MIN_BED, Y_MAX_BED)) g29_y_pos = Y_CENTER; + if (!WITHIN(sx, X_MIN_BED, X_MAX_BED)) sx = X_CENTER; + if (!WITHIN(sy, Y_MIN_BED, Y_MAX_BED)) sy = Y_CENTER; if (err_flag) return UBL_ERR; + g29_pos.set(sx, sy); + /** * Activate or deactivate UBL * Note: UBL's G29 restores the state set here when done. @@ -1213,26 +1220,22 @@ mesh_index_pair unified_bed_leveling::find_furthest_invalid_mesh_point() { - bool found_a_NAN = false, found_a_real = false; + bool found_a_NAN = false, found_a_real = false; - mesh_index_pair out_mesh; - out_mesh.x_index = out_mesh.y_index = -1; - out_mesh.distance = -99999.99f; + mesh_index_pair farthest { -1, -1, -99999.99 }; for (int8_t i = 0; i < GRID_MAX_POINTS_X; i++) { for (int8_t j = 0; j < GRID_MAX_POINTS_Y; j++) { - if (isnan(z_values[i][j])) { // Check to see if this location holds an invalid mesh point - - const float mx = mesh_index_to_xpos(i), - my = mesh_index_to_ypos(j); + if (isnan(z_values[i][j])) { // Invalid mesh point? - if (!position_is_reachable_by_probe(mx, my)) // make sure the probe can get to the mesh point + // Skip points the probe can't reach + if (!position_is_reachable_by_probe(mesh_index_to_xpos(i), mesh_index_to_ypos(j))) continue; found_a_NAN = true; - int8_t closest_x = -1, closest_y = -1; + xy_int8_t near { -1, -1 }; float d1, d2 = 99999.9f; for (int8_t k = 0; k < GRID_MAX_POINTS_X; k++) { for (int8_t l = 0; l < GRID_MAX_POINTS_Y; l++) { @@ -1245,84 +1248,75 @@ d1 = HYPOT(i - k, j - l) + (1.0f / ((millis() % 47) + 13)); - if (d1 < d2) { // found a closer distance from invalid mesh point at (i,j) to defined mesh point at (k,l) - d2 = d1; // found a closer location with - closest_x = i; // an assigned mesh point value - closest_y = j; + if (d1 < d2) { // Invalid mesh point (i,j) is closer to the defined point (k,l) + d2 = d1; + near.set(i, j); } } } } // - // At this point d2 should have the closest defined mesh point to invalid mesh point (i,j) + // At this point d2 should have the near defined mesh point to invalid mesh point (i,j) // - if (found_a_real && (closest_x >= 0) && (d2 > out_mesh.distance)) { - out_mesh.distance = d2; // found an invalid location with a greater distance - out_mesh.x_index = closest_x; // to a defined mesh point - out_mesh.y_index = closest_y; + if (found_a_real && near.x >= 0 && d2 > farthest.distance) { + farthest.pos = near; // Found an invalid location farther from the defined mesh point + farthest.distance = d2; } } } // for j } // for i if (!found_a_real && found_a_NAN) { // if the mesh is totally unpopulated, start the probing - out_mesh.x_index = GRID_MAX_POINTS_X / 2; - out_mesh.y_index = GRID_MAX_POINTS_Y / 2; - out_mesh.distance = 1; + farthest.pos.set(GRID_MAX_POINTS_X / 2, GRID_MAX_POINTS_Y / 2); + farthest.distance = 1; } - return out_mesh; + return farthest; } - mesh_index_pair unified_bed_leveling::find_closest_mesh_point_of_type(const MeshPointType type, const float &rx, const float &ry, const bool probe_as_reference, uint16_t bits[16]) { - mesh_index_pair out_mesh; - out_mesh.x_index = out_mesh.y_index = -1; - out_mesh.distance = -99999.9f; + mesh_index_pair unified_bed_leveling::find_closest_mesh_point_of_type(const MeshPointType type, const xy_pos_t &pos, const bool probe_relative/*=false*/, MeshFlags *done_flags/*=nullptr*/) { + mesh_index_pair closest; + closest.invalidate(); + closest.distance = -99999.9f; - // Get our reference position. Either the nozzle or probe location. - const float px = rx + (probe_as_reference == USE_PROBE_AS_REFERENCE ? probe_offset[X_AXIS] : 0), - py = ry + (probe_as_reference == USE_PROBE_AS_REFERENCE ? probe_offset[Y_AXIS] : 0); + // Get the reference position, either nozzle or probe + const xy_pos_t ref = probe_relative ? pos + probe_offset : pos; float best_so_far = 99999.99f; for (int8_t i = 0; i < GRID_MAX_POINTS_X; i++) { for (int8_t j = 0; j < GRID_MAX_POINTS_Y; j++) { - - if ( (type == INVALID && isnan(z_values[i][j])) // Check to see if this location holds the right thing - || (type == REAL && !isnan(z_values[i][j])) - || (type == SET_IN_BITMAP && is_bitmap_set(bits, i, j)) + if ( (type == (isnan(z_values[i][j]) ? INVALID : REAL)) + || (type == SET_IN_BITMAP && !done_flags->marked(i, j)) ) { - // We only get here if we found a Mesh Point of the specified type - - const float mx = mesh_index_to_xpos(i), - my = mesh_index_to_ypos(j); + // Found a Mesh Point of the specified type! + const xy_pos_t mpos = { mesh_index_to_xpos(i), mesh_index_to_ypos(j) }; // If using the probe as the reference there are some unreachable locations. // Also for round beds, there are grid points outside the bed the nozzle can't reach. // Prune them from the list and ignore them till the next Phase (manual nozzle probing). - if (probe_as_reference ? !position_is_reachable_by_probe(mx, my) : !position_is_reachable(mx, my)) + if (probe_relative ? !position_is_reachable_by_probe(mpos) : !position_is_reachable(mpos)) continue; // Reachable. Check if it's the best_so_far location to the nozzle. - float distance = HYPOT(px - mx, py - my); + const xy_pos_t diff = current_position - mpos; + const float distance = (ref - mpos).magnitude() + diff.magnitude() * 0.1f; // factor in the distance from the current location for the normal case // so the nozzle isn't running all over the bed. - distance += HYPOT(current_position[X_AXIS] - mx, current_position[Y_AXIS] - my) * 0.1f; if (distance < best_so_far) { - best_so_far = distance; // We found a closer location with - out_mesh.x_index = i; // the specified type of mesh value. - out_mesh.y_index = j; - out_mesh.distance = best_so_far; + best_so_far = distance; // Found a closer location with the desired value type. + closest.pos.set(i, j); + closest.distance = best_so_far; } } } // for j } // for i - return out_mesh; + return closest; } /** @@ -1332,20 +1326,20 @@ */ bool unified_bed_leveling::smart_fill_one(const uint8_t x, const uint8_t y, const int8_t xdir, const int8_t ydir) { - const int8_t x1 = x + xdir, x2 = x1 + xdir, - y1 = y + ydir, y2 = y1 + ydir; - // A NAN next to a pair of real values? - if (isnan(z_values[x][y]) && !isnan(z_values[x1][y1]) && !isnan(z_values[x2][y2])) { - if (z_values[x1][y1] < z_values[x2][y2]) // Angled downward? - z_values[x][y] = z_values[x1][y1]; // Use nearest (maybe a little too high.) - else - z_values[x][y] = 2.0f * z_values[x1][y1] - z_values[x2][y2]; // Angled upward... - - #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(x, y, z_values[x][y]); - #endif - - return true; + const float v = z_values[x][y]; + if (isnan(v)) { // A NAN... + const int8_t dx = x + xdir, dy = y + ydir; + const float v1 = z_values[dx][dy]; + if (!isnan(v1)) { // ...next to a pair of real values? + const float v2 = z_values[dx + xdir][dy + ydir]; + if (!isnan(v2)) { + z_values[x][y] = v1 < v2 ? v1 : v1 + v1 - v2; + #if ENABLED(EXTENSIBLE_UI) + ExtUI::onMeshUpdate(x, y, z_values[pos.x][pos.y]); + #endif + return true; + } + } } return false; } @@ -1391,15 +1385,15 @@ dx = (x_max - x_min) / (g29_grid_size - 1), dy = (y_max - y_min) / (g29_grid_size - 1); - vector_3 points[3] = { + const vector_3 points[3] = { #if ENABLED(HAS_FIXED_3POINT) - vector_3(PROBE_PT_1_X, PROBE_PT_1_Y, 0), - vector_3(PROBE_PT_2_X, PROBE_PT_2_Y, 0), - vector_3(PROBE_PT_3_X, PROBE_PT_3_Y, 0) + { PROBE_PT_1_X, PROBE_PT_1_Y, 0 }, + { PROBE_PT_2_X, PROBE_PT_2_Y, 0 }, + { PROBE_PT_3_X, PROBE_PT_3_Y, 0 } #else - vector_3(x_min, y_min, 0), - vector_3(x_max, y_min, 0), - vector_3((x_max - x_min) / 2, y_max, 0) + { x_min, y_min, 0 }, + { x_max, y_min, 0 }, + { (x_max - x_min) / 2, y_max, 0 } #endif }; @@ -1419,11 +1413,11 @@ ui.status_printf_P(0, PSTR(MSG_LCD_TILTING_MESH " 1/3")); #endif - measured_z = probe_at_point(points[0].x, points[0].y, PROBE_PT_RAISE, g29_verbose_level); + measured_z = probe_at_point(points[0], PROBE_PT_RAISE, g29_verbose_level); if (isnan(measured_z)) abort_flag = true; else { - measured_z -= get_z_correction(points[0].x, points[0].y); + measured_z -= get_z_correction(points[0]); #ifdef VALIDATE_MESH_TILT z1 = measured_z; #endif @@ -1431,7 +1425,7 @@ serial_spaces(16); SERIAL_ECHOLNPAIR("Corrected_Z=", measured_z); } - incremental_LSF(&lsf_results, points[0].x, points[0].y, measured_z); + incremental_LSF(&lsf_results, points[0], measured_z); } if (!abort_flag) { @@ -1440,19 +1434,19 @@ ui.status_printf_P(0, PSTR(MSG_LCD_TILTING_MESH " 2/3")); #endif - measured_z = probe_at_point(points[1].x, points[1].y, PROBE_PT_RAISE, g29_verbose_level); + measured_z = probe_at_point(points[1], PROBE_PT_RAISE, g29_verbose_level); #ifdef VALIDATE_MESH_TILT z2 = measured_z; #endif if (isnan(measured_z)) abort_flag = true; else { - measured_z -= get_z_correction(points[1].x, points[1].y); + measured_z -= get_z_correction(points[1]); if (g29_verbose_level > 3) { serial_spaces(16); SERIAL_ECHOLNPAIR("Corrected_Z=", measured_z); } - incremental_LSF(&lsf_results, points[1].x, points[1].y, measured_z); + incremental_LSF(&lsf_results, points[1], measured_z); } } @@ -1462,19 +1456,19 @@ ui.status_printf_P(0, PSTR(MSG_LCD_TILTING_MESH " 3/3")); #endif - measured_z = probe_at_point(points[2].x, points[2].y, PROBE_PT_STOW, g29_verbose_level); + measured_z = probe_at_point(points[2], PROBE_PT_STOW, g29_verbose_level); #ifdef VALIDATE_MESH_TILT z3 = measured_z; #endif if (isnan(measured_z)) abort_flag = true; else { - measured_z -= get_z_correction(points[2].x, points[2].y); + measured_z -= get_z_correction(points[2]); if (g29_verbose_level > 3) { serial_spaces(16); SERIAL_ECHOLNPAIR("Corrected_Z=", measured_z); } - incremental_LSF(&lsf_results, points[2].x, points[2].y, measured_z); + incremental_LSF(&lsf_results, points[2], measured_z); } } @@ -1494,10 +1488,11 @@ uint16_t total_points = g29_grid_size * g29_grid_size, point_num = 1; + xy_pos_t rpos; for (uint8_t ix = 0; ix < g29_grid_size; ix++) { - const float rx = x_min + ix * dx; + rpos.x = x_min + ix * dx; for (int8_t iy = 0; iy < g29_grid_size; iy++) { - const float ry = y_min + dy * (zig_zag ? g29_grid_size - 1 - iy : iy); + rpos.y = y_min + dy * (zig_zag ? g29_grid_size - 1 - iy : iy); if (!abort_flag) { SERIAL_ECHOLNPAIR("Tilting mesh point ", point_num, "/", total_points, "\n"); @@ -1505,24 +1500,24 @@ ui.status_printf_P(0, PSTR(MSG_LCD_TILTING_MESH " %i/%i"), point_num, total_points); #endif - measured_z = probe_at_point(rx, ry, parser.seen('E') ? PROBE_PT_STOW : PROBE_PT_RAISE, g29_verbose_level); // TODO: Needs error handling + measured_z = probe_at_point(rpos, parser.seen('E') ? PROBE_PT_STOW : PROBE_PT_RAISE, g29_verbose_level); // TODO: Needs error handling abort_flag = isnan(measured_z); if (DEBUGGING(LEVELING)) { + const xy_pos_t lpos = rpos.asLogical(); DEBUG_CHAR('('); - DEBUG_ECHO_F(rx, 7); + DEBUG_ECHO_F(rpos.x, 7); DEBUG_CHAR(','); - DEBUG_ECHO_F(ry, 7); - DEBUG_ECHOPGM(") logical: ("); - DEBUG_ECHO_F(LOGICAL_X_POSITION(rx), 7); + DEBUG_ECHO_F(rpos.y, 7); + DEBUG_ECHOPAIR_F(") logical: (", lpos.x, 7); DEBUG_CHAR(','); - DEBUG_ECHO_F(LOGICAL_Y_POSITION(ry), 7); + DEBUG_ECHO_F(lpos.y, 7); DEBUG_ECHOPAIR_F(") measured: ", measured_z, 7); - DEBUG_ECHOPAIR_F(" correction: ", get_z_correction(rx, ry), 7); + DEBUG_ECHOPAIR_F(" correction: ", get_z_correction(rpos), 7); } - measured_z -= get_z_correction(rx, ry) /* + probe_offset[Z_AXIS] */ ; + measured_z -= get_z_correction(rpos) /* + probe_offset.z */ ; if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR_F(" final >>>---> ", measured_z, 7); @@ -1530,7 +1525,7 @@ serial_spaces(16); SERIAL_ECHOLNPAIR("Corrected_Z=", measured_z); } - incremental_LSF(&lsf_results, rx, ry, measured_z); + incremental_LSF(&lsf_results, rpos, measured_z); } point_num++; @@ -1564,33 +1559,33 @@ for (uint8_t i = 0; i < GRID_MAX_POINTS_X; i++) { for (uint8_t j = 0; j < GRID_MAX_POINTS_Y; j++) { - float x_tmp = mesh_index_to_xpos(i), - y_tmp = mesh_index_to_ypos(j), - z_tmp = z_values[i][j]; + float mx = mesh_index_to_xpos(i), + my = mesh_index_to_ypos(j), + mz = z_values[i][j]; if (DEBUGGING(LEVELING)) { - DEBUG_ECHOPAIR_F("before rotation = [", x_tmp, 7); + DEBUG_ECHOPAIR_F("before rotation = [", mx, 7); DEBUG_CHAR(','); - DEBUG_ECHO_F(y_tmp, 7); + DEBUG_ECHO_F(my, 7); DEBUG_CHAR(','); - DEBUG_ECHO_F(z_tmp, 7); + DEBUG_ECHO_F(mz, 7); DEBUG_ECHOPGM("] ---> "); DEBUG_DELAY(20); } - apply_rotation_xyz(rotation, x_tmp, y_tmp, z_tmp); + apply_rotation_xyz(rotation, mx, my, mz); if (DEBUGGING(LEVELING)) { - DEBUG_ECHOPAIR_F("after rotation = [", x_tmp, 7); + DEBUG_ECHOPAIR_F("after rotation = [", mx, 7); DEBUG_CHAR(','); - DEBUG_ECHO_F(y_tmp, 7); + DEBUG_ECHO_F(my, 7); DEBUG_CHAR(','); - DEBUG_ECHO_F(z_tmp, 7); + DEBUG_ECHO_F(mz, 7); DEBUG_ECHOLNPGM("]"); - DEBUG_DELAY(55); + DEBUG_DELAY(20); } - z_values[i][j] = z_tmp - lsf_results.D; + z_values[i][j] = mz - lsf_results.D; #if ENABLED(EXTENSIBLE_UI) ExtUI::onMeshUpdate(i, j, z_values[i][j]); #endif @@ -1613,41 +1608,32 @@ DEBUG_EOL(); /** - * The following code can be used to check the validity of the mesh tilting algorithm. - * When a 3-Point Mesh Tilt is done, the same algorithm is used as the grid based tilting. - * The only difference is just 3 points are used in the calculations. That fact guarantees - * each probed point should have an exact match when a get_z_correction() for that location - * is calculated. The Z error between the probed point locations and the get_z_correction() + * Use the code below to check the validity of the mesh tilting algorithm. + * 3-Point Mesh Tilt uses the same algorithm as grid-based tilting, but only + * three points are used in the calculation. This guarantees that each probed point + * has an exact match when get_z_correction() for that location is calculated. + * The Z error between the probed point locations and the get_z_correction() * numbers for those locations should be 0. */ #ifdef VALIDATE_MESH_TILT - float t, t1, d; - t = normal.x * x_min + normal.y * y_min; - d = t + normal.z * z1; - DEBUG_ECHOPAIR_F("D from 1st point: ", d, 6); - DEBUG_ECHOLNPAIR_F(" Z error: ", normal.z * z1 - get_z_correction(x_min, y_min), 6); - - t = normal.x * x_max + normal.y * y_min; - d = t + normal.z * z2; - DEBUG_EOL(); - DEBUG_ECHOPAIR_F("D from 2nd point: ", d, 6); - DEBUG_ECHOLNPAIR_F(" Z error: ", normal.z * z2 - get_z_correction(x_max, y_min), 6); - - t = normal.x * ((x_max - x_min) / 2) + normal.y * (y_min); - d = t + normal.z * z3; - DEBUG_ECHOPAIR_F("D from 3rd point: ", d, 6); - DEBUG_ECHOLNPAIR_F(" Z error: ", normal.z * z3 - get_z_correction((x_max - x_min) / 2, y_max), 6); - - t = normal.x * (Z_SAFE_HOMING_X_POINT) + normal.y * (Z_SAFE_HOMING_Y_POINT); - d = t + normal.z * 0; - DEBUG_ECHOLNPAIR_F("D from home location with Z=0 : ", d, 6); - - t = normal.x * (Z_SAFE_HOMING_X_POINT) + normal.y * (Z_SAFE_HOMING_Y_POINT); - d = t + get_z_correction(Z_SAFE_HOMING_X_POINT, Z_SAFE_HOMING_Y_POINT); // normal.z * 0; - DEBUG_ECHOPAIR_F("D from home location using mesh value for Z: ", d, 6); - + auto d_from = []() { DEBUG_ECHOPGM("D from "); }; + auto normed = [&](const xy_pos_t &pos, const float &zadd) { + return normal.x * pos.x + normal.y * pos.y + zadd; + }; + auto debug_pt = [](PGM_P const pre, const xy_pos_t &pos, const float &zadd) { + d_from(); serialprintPGM(pre); + DEBUG_ECHO_F(normed(pos, zadd), 6); + DEBUG_ECHOLNPAIR_F(" Z error: ", zadd - get_z_correction(pos), 6); + }; + debug_pt(PSTR("1st point: "), probe_pt[0], normal.z * z1); + debug_pt(PSTR("2nd point: "), probe_pt[1], normal.z * z2); + debug_pt(PSTR("3rd point: "), probe_pt[2], normal.z * z3); + d_from(); DEBUG_ECHOPGM("safe home with Z="); + DEBUG_ECHOLNPAIR_F("0 : ", normed(safe_homing_xy, 0), 6); + d_from(); DEBUG_ECHOPGM("safe home with Z="); + DEBUG_ECHOLNPAIR_F("mesh value ", normed(safe_homing_xy, get_z_correction(safe_homing_xy)), 6); DEBUG_ECHOPAIR(" Z error: (", Z_SAFE_HOMING_X_POINT, ",", Z_SAFE_HOMING_Y_POINT); - DEBUG_ECHOLNPAIR_F(") = ", get_z_correction(Z_SAFE_HOMING_X_POINT, Z_SAFE_HOMING_Y_POINT), 6); + DEBUG_ECHOLNPAIR_F(") = ", get_z_correction(safe_homing_xy), 6); #endif } // DEBUGGING(LEVELING) @@ -1676,21 +1662,23 @@ if (!isnan(z_values[jx][jy])) SBI(bitmap[jx], jy); + xy_pos_t ppos; for (uint8_t ix = 0; ix < GRID_MAX_POINTS_X; ix++) { - const float px = mesh_index_to_xpos(ix); + ppos.x = mesh_index_to_xpos(ix); for (uint8_t iy = 0; iy < GRID_MAX_POINTS_Y; iy++) { - const float py = mesh_index_to_ypos(iy); + ppos.y = mesh_index_to_ypos(iy); if (isnan(z_values[ix][iy])) { - // undefined mesh point at (px,py), compute weighted LSF from original valid mesh points. + // undefined mesh point at (ppos.x,ppos.y), compute weighted LSF from original valid mesh points. incremental_LSF_reset(&lsf_results); + xy_pos_t rpos; for (uint8_t jx = 0; jx < GRID_MAX_POINTS_X; jx++) { - const float rx = mesh_index_to_xpos(jx); + rpos.x = mesh_index_to_xpos(jx); for (uint8_t jy = 0; jy < GRID_MAX_POINTS_Y; jy++) { if (TEST(bitmap[jx], jy)) { - const float ry = mesh_index_to_ypos(jy), - rz = z_values[jx][jy], - w = 1 + weight_scaled / HYPOT((rx - px), (ry - py)); - incremental_WLSF(&lsf_results, rx, ry, rz, w); + rpos.y = mesh_index_to_ypos(jy); + const float rz = z_values[jx][jy], + w = 1.0f + weight_scaled / (rpos - ppos).magnitude(); + incremental_WLSF(&lsf_results, rpos, rz, w); } } } @@ -1698,12 +1686,12 @@ SERIAL_ECHOLNPGM("Insufficient data"); return; } - const float ez = -lsf_results.D - lsf_results.A * px - lsf_results.B * py; + const float ez = -lsf_results.D - lsf_results.A * ppos.x - lsf_results.B * ppos.y; z_values[ix][iy] = ez; #if ENABLED(EXTENSIBLE_UI) ExtUI::onMeshUpdate(ix, iy, z_values[ix][iy]); #endif - idle(); // housekeeping + idle(); // housekeeping } } } @@ -1734,7 +1722,7 @@ adjust_mesh_to_mean(g29_c_flag, g29_constant); #if HAS_BED_PROBE - SERIAL_ECHOLNPAIR_F("Probe Offset M851 Z", probe_offset[Z_AXIS], 7); + SERIAL_ECHOLNPAIR_F("Probe Offset M851 Z", probe_offset.z, 7); #endif SERIAL_ECHOLNPAIR("MESH_MIN_X " STRINGIFY(MESH_MIN_X) "=", MESH_MIN_X); serial_delay(50); diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp index fcce41169..a0d5518c4 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp @@ -35,12 +35,6 @@ #include "../../../Marlin.h" #include -#if AVR_AT90USB1286_FAMILY // Teensyduino & Printrboard IDE extensions have compile errors without this - inline void set_current_from_destination() { COPY(current_position, destination); } -#else - extern void set_current_from_destination(); -#endif - #if !UBL_SEGMENTED void unified_bed_leveling::line_to_destination_cartesian(const feedRate_t &scaled_fr_mm_s, const uint8_t extruder) { @@ -50,60 +44,57 @@ * just do the required Z-Height correction, call the Planner's buffer_line() routine, and leave */ #if HAS_POSITION_MODIFIERS - float start[XYZE] = { current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS] }, - end[XYZE] = { destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS] }; + xyze_pos_t start = current_position, end = destination; planner.apply_modifiers(start); planner.apply_modifiers(end); #else - const float (&start)[XYZE] = current_position, - (&end)[XYZE] = destination; + const xyze_pos_t &start = current_position, &end = destination; #endif - const int cell_start_xi = get_cell_index_x(start[X_AXIS]), - cell_start_yi = get_cell_index_y(start[Y_AXIS]), - cell_dest_xi = get_cell_index_x(end[X_AXIS]), - cell_dest_yi = get_cell_index_y(end[Y_AXIS]); + const xy_int8_t istart = cell_indexes(start), iend = cell_indexes(end); // A move within the same cell needs no splitting - if (cell_start_xi == cell_dest_xi && cell_start_yi == cell_dest_yi) { + if (istart == iend) { // For a move off the bed, use a constant Z raise - if (!WITHIN(cell_dest_xi, 0, GRID_MAX_POINTS_X - 1) || !WITHIN(cell_dest_yi, 0, GRID_MAX_POINTS_Y - 1)) { + if (!WITHIN(iend.x, 0, GRID_MAX_POINTS_X - 1) || !WITHIN(iend.y, 0, GRID_MAX_POINTS_Y - 1)) { // Note: There is no Z Correction in this case. We are off the grid and don't know what // a reasonable correction would be. If the user has specified a UBL_Z_RAISE_WHEN_OFF_MESH // value, that will be used instead of a calculated (Bi-Linear interpolation) correction. - const float z_raise = 0.0 - #ifdef UBL_Z_RAISE_WHEN_OFF_MESH - + UBL_Z_RAISE_WHEN_OFF_MESH - #endif - ; - planner.buffer_segment(end[X_AXIS], end[Y_AXIS], end[Z_AXIS] + z_raise, end[E_AXIS], scaled_fr_mm_s, extruder); - set_current_from_destination(); + #ifdef UBL_Z_RAISE_WHEN_OFF_MESH + end.z += UBL_Z_RAISE_WHEN_OFF_MESH; + #endif + planner.buffer_segment(end, scaled_fr_mm_s, extruder); + current_position = destination; return; } FINAL_MOVE: // The distance is always MESH_X_DIST so multiply by the constant reciprocal. - const float xratio = (end[X_AXIS] - mesh_index_to_xpos(cell_dest_xi)) * RECIPROCAL(MESH_X_DIST); + const float xratio = (end.x - mesh_index_to_xpos(iend.x)) * RECIPROCAL(MESH_X_DIST); - float z1 = z_values[cell_dest_xi ][cell_dest_yi ] + xratio * - (z_values[cell_dest_xi + 1][cell_dest_yi ] - z_values[cell_dest_xi][cell_dest_yi ]), - z2 = z_values[cell_dest_xi ][cell_dest_yi + 1] + xratio * - (z_values[cell_dest_xi + 1][cell_dest_yi + 1] - z_values[cell_dest_xi][cell_dest_yi + 1]); - - if (cell_dest_xi >= GRID_MAX_POINTS_X - 1) z1 = z2 = 0.0; + float z1, z2; + if (iend.x >= GRID_MAX_POINTS_X - 1) + z1 = z2 = 0.0; + else { + z1 = z_values[iend.x ][iend.y ] + xratio * + (z_values[iend.x + 1][iend.y ] - z_values[iend.x][iend.y ]), + z2 = z_values[iend.x ][iend.y + 1] + xratio * + (z_values[iend.x + 1][iend.y + 1] - z_values[iend.x][iend.y + 1]); + } // X cell-fraction done. Interpolate the two Z offsets with the Y fraction for the final Z offset. - const float yratio = (end[Y_AXIS] - mesh_index_to_ypos(cell_dest_yi)) * RECIPROCAL(MESH_Y_DIST), - z0 = cell_dest_yi < GRID_MAX_POINTS_Y - 1 ? (z1 + (z2 - z1) * yratio) * planner.fade_scaling_factor_for_z(end[Z_AXIS]) : 0.0; + const float yratio = (end.y - mesh_index_to_ypos(iend.y)) * RECIPROCAL(MESH_Y_DIST), + z0 = iend.y < GRID_MAX_POINTS_Y - 1 ? (z1 + (z2 - z1) * yratio) * planner.fade_scaling_factor_for_z(end.z) : 0.0; // Undefined parts of the Mesh in z_values[][] are NAN. // Replace NAN corrections with 0.0 to prevent NAN propagation. - planner.buffer_segment(end[X_AXIS], end[Y_AXIS], end[Z_AXIS] + (isnan(z0) ? 0.0 : z0), end[E_AXIS], scaled_fr_mm_s, extruder); - set_current_from_destination(); + if (!isnan(z0)) end.z += z0; + planner.buffer_segment(end, scaled_fr_mm_s, extruder); + current_position = destination; return; } @@ -112,17 +103,11 @@ * case - crossing only one X or Y line - after details are worked out to reduce computation. */ - const float dx = end[X_AXIS] - start[X_AXIS], - dy = end[Y_AXIS] - start[Y_AXIS]; - - const int left_flag = dx < 0.0 ? 1 : 0, - down_flag = dy < 0.0 ? 1 : 0; - - const float adx = left_flag ? -dx : dx, - ady = down_flag ? -dy : dy; - - const int dxi = cell_start_xi == cell_dest_xi ? 0 : left_flag ? -1 : 1, - dyi = cell_start_yi == cell_dest_yi ? 0 : down_flag ? -1 : 1; + const xy_float_t dist = end - start; + const xy_bool_t neg { dist.x < 0, dist.y < 0 }; + const xy_int8_t ineg { int8_t(neg.x), int8_t(neg.y) }; + const xy_float_t sign { neg.x ? -1.0f : 1.0f, neg.y ? -1.0f : 1.0f }; + const xy_int8_t iadd { int8_t(iend.x == istart.x ? 0 : sign.x), int8_t(iend.y == istart.y ? 0 : sign.y) }; /** * Compute the extruder scaling factor for each partial move, checking for @@ -132,64 +117,64 @@ * components. The larger of the two is used to preserve precision. */ - const bool use_x_dist = adx > ady; + const xy_float_t ad = sign * dist; + const bool use_x_dist = ad.x > ad.y; - float on_axis_distance = use_x_dist ? dx : dy, - e_position = end[E_AXIS] - start[E_AXIS], - z_position = end[Z_AXIS] - start[Z_AXIS]; + float on_axis_distance = use_x_dist ? dist.x : dist.y, + e_position = end.e - start.e, + z_position = end.z - start.z; - const float e_normalized_dist = e_position / on_axis_distance, + const float e_normalized_dist = e_position / on_axis_distance, // Allow divide by zero z_normalized_dist = z_position / on_axis_distance; - int current_xi = cell_start_xi, - current_yi = cell_start_yi; + xy_int8_t icell = istart; - const float m = dy / dx, - c = start[Y_AXIS] - m * start[X_AXIS]; + const float ratio = dist.y / dist.x, // Allow divide by zero + c = start.y - ratio * start.x; - const bool inf_normalized_flag = (isinf(e_normalized_dist) != 0), - inf_m_flag = (isinf(m) != 0); + const bool inf_normalized_flag = isinf(e_normalized_dist), + inf_ratio_flag = isinf(ratio); /** * Handle vertical lines that stay within one column. * These need not be perfectly vertical. */ - if (dxi == 0) { // Vertical line? - current_yi += down_flag; // Line going down? Just go to the bottom. - while (current_yi != cell_dest_yi + down_flag) { - current_yi += dyi; - const float next_mesh_line_y = mesh_index_to_ypos(current_yi); + if (iadd.x == 0) { // Vertical line? + icell.y += ineg.y; // Line going down? Just go to the bottom. + while (icell.y != iend.y + ineg.y) { + icell.y += iadd.y; + const float next_mesh_line_y = mesh_index_to_ypos(icell.y); /** * Skip the calculations for an infinite slope. * For others the next X is the same so this can continue. * Calculate X at the next Y mesh line. */ - const float rx = inf_m_flag ? start[X_AXIS] : (next_mesh_line_y - c) / m; + const float rx = inf_ratio_flag ? start.x : (next_mesh_line_y - c) / ratio; - float z0 = z_correction_for_x_on_horizontal_mesh_line(rx, current_xi, current_yi) - * planner.fade_scaling_factor_for_z(end[Z_AXIS]); + float z0 = z_correction_for_x_on_horizontal_mesh_line(rx, icell.x, icell.y) + * planner.fade_scaling_factor_for_z(end.z); // Undefined parts of the Mesh in z_values[][] are NAN. // Replace NAN corrections with 0.0 to prevent NAN propagation. if (isnan(z0)) z0 = 0.0; - const float ry = mesh_index_to_ypos(current_yi); + const float ry = mesh_index_to_ypos(icell.y); /** * Without this check, it's possible to generate a zero length move, as in the case where * the line is heading down, starting exactly on a mesh line boundary. Since this is rare * it might be fine to remove this check and let planner.buffer_segment() filter it out. */ - if (ry != start[Y_AXIS]) { - if (!inf_normalized_flag) { - on_axis_distance = use_x_dist ? rx - start[X_AXIS] : ry - start[Y_AXIS]; - e_position = start[E_AXIS] + on_axis_distance * e_normalized_dist; - z_position = start[Z_AXIS] + on_axis_distance * z_normalized_dist; + if (ry != start.y) { + if (!inf_normalized_flag) { // fall-through faster than branch + on_axis_distance = use_x_dist ? rx - start.x : ry - start.y; + e_position = start.e + on_axis_distance * e_normalized_dist; + z_position = start.z + on_axis_distance * z_normalized_dist; } else { - e_position = end[E_AXIS]; - z_position = end[Z_AXIS]; + e_position = end.e; + z_position = end.z; } planner.buffer_segment(rx, ry, z_position + z0, e_position, scaled_fr_mm_s, extruder); @@ -197,10 +182,10 @@ } // At the final destination? Usually not, but when on a Y Mesh Line it's completed. - if (current_position[X_AXIS] != end[X_AXIS] || current_position[Y_AXIS] != end[Y_AXIS]) + if (xy_pos_t(current_position) != xy_pos_t(end)) goto FINAL_MOVE; - set_current_from_destination(); + current_position = destination; return; } @@ -208,36 +193,34 @@ * Handle horizontal lines that stay within one row. * These need not be perfectly horizontal. */ - if (dyi == 0) { // Horizontal line? - current_xi += left_flag; // Heading left? Just go to the left edge of the cell for the first move. - while (current_xi != cell_dest_xi + left_flag) { - current_xi += dxi; - const float next_mesh_line_x = mesh_index_to_xpos(current_xi), - ry = m * next_mesh_line_x + c; // Calculate Y at the next X mesh line + if (iadd.y == 0) { // Horizontal line? + icell.x += ineg.x; // Heading left? Just go to the left edge of the cell for the first move. + while (icell.x != iend.x + ineg.x) { + icell.x += iadd.x; + const float rx = mesh_index_to_xpos(icell.x); + const float ry = ratio * rx + c; // Calculate Y at the next X mesh line - float z0 = z_correction_for_y_on_vertical_mesh_line(ry, current_xi, current_yi) - * planner.fade_scaling_factor_for_z(end[Z_AXIS]); + float z0 = z_correction_for_y_on_vertical_mesh_line(ry, icell.x, icell.y) + * planner.fade_scaling_factor_for_z(end.z); // Undefined parts of the Mesh in z_values[][] are NAN. // Replace NAN corrections with 0.0 to prevent NAN propagation. if (isnan(z0)) z0 = 0.0; - const float rx = mesh_index_to_xpos(current_xi); - /** * Without this check, it's possible to generate a zero length move, as in the case where * the line is heading left, starting exactly on a mesh line boundary. Since this is rare * it might be fine to remove this check and let planner.buffer_segment() filter it out. */ - if (rx != start[X_AXIS]) { + if (rx != start.x) { if (!inf_normalized_flag) { - on_axis_distance = use_x_dist ? rx - start[X_AXIS] : ry - start[Y_AXIS]; - e_position = start[E_AXIS] + on_axis_distance * e_normalized_dist; // is based on X or Y because this is a horizontal move - z_position = start[Z_AXIS] + on_axis_distance * z_normalized_dist; + on_axis_distance = use_x_dist ? rx - start.x : ry - start.y; + e_position = start.e + on_axis_distance * e_normalized_dist; // is based on X or Y because this is a horizontal move + z_position = start.z + on_axis_distance * z_normalized_dist; } else { - e_position = end[E_AXIS]; - z_position = end[Z_AXIS]; + e_position = end.e; + z_position = end.z; } if (!planner.buffer_segment(rx, ry, z_position + z0, e_position, scaled_fr_mm_s, extruder)) @@ -245,93 +228,88 @@ } //else printf("FIRST MOVE PRUNED "); } - if (current_position[X_AXIS] != end[X_AXIS] || current_position[Y_AXIS] != end[Y_AXIS]) + if (xy_pos_t(current_position) != xy_pos_t(end)) goto FINAL_MOVE; - set_current_from_destination(); + current_position = destination; return; } /** * - * Handle the generic case of a line crossing both X and Y Mesh lines. + * Generic case of a line crossing both X and Y Mesh lines. * */ - int xi_cnt = cell_start_xi - cell_dest_xi, - yi_cnt = cell_start_yi - cell_dest_yi; - - if (xi_cnt < 0) xi_cnt = -xi_cnt; - if (yi_cnt < 0) yi_cnt = -yi_cnt; + xy_int8_t cnt = (istart - iend).ABS(); - current_xi += left_flag; - current_yi += down_flag; + icell += ineg; - while (xi_cnt || yi_cnt) { + while (cnt) { - const float next_mesh_line_x = mesh_index_to_xpos(current_xi + dxi), - next_mesh_line_y = mesh_index_to_ypos(current_yi + dyi), - ry = m * next_mesh_line_x + c, // Calculate Y at the next X mesh line - rx = (next_mesh_line_y - c) / m; // Calculate X at the next Y mesh line - // (No need to worry about m being zero. - // If that was the case, it was already detected - // as a vertical line move above.) + const float next_mesh_line_x = mesh_index_to_xpos(icell.x + iadd.x), + next_mesh_line_y = mesh_index_to_ypos(icell.y + iadd.y), + ry = ratio * next_mesh_line_x + c, // Calculate Y at the next X mesh line + rx = (next_mesh_line_y - c) / ratio; // Calculate X at the next Y mesh line + // (No need to worry about ratio == 0. + // In that case, it was already detected + // as a vertical line move above.) - if (left_flag == (rx > next_mesh_line_x)) { // Check if we hit the Y line first + if (neg.x == (rx > next_mesh_line_x)) { // Check if we hit the Y line first // Yes! Crossing a Y Mesh Line next - float z0 = z_correction_for_x_on_horizontal_mesh_line(rx, current_xi - left_flag, current_yi + dyi) - * planner.fade_scaling_factor_for_z(end[Z_AXIS]); + float z0 = z_correction_for_x_on_horizontal_mesh_line(rx, icell.x - ineg.x, icell.y + iadd.y) + * planner.fade_scaling_factor_for_z(end.z); // Undefined parts of the Mesh in z_values[][] are NAN. // Replace NAN corrections with 0.0 to prevent NAN propagation. if (isnan(z0)) z0 = 0.0; if (!inf_normalized_flag) { - on_axis_distance = use_x_dist ? rx - start[X_AXIS] : next_mesh_line_y - start[Y_AXIS]; - e_position = start[E_AXIS] + on_axis_distance * e_normalized_dist; - z_position = start[Z_AXIS] + on_axis_distance * z_normalized_dist; + on_axis_distance = use_x_dist ? rx - start.x : next_mesh_line_y - start.y; + e_position = start.e + on_axis_distance * e_normalized_dist; + z_position = start.z + on_axis_distance * z_normalized_dist; } else { - e_position = end[E_AXIS]; - z_position = end[Z_AXIS]; + e_position = end.e; + z_position = end.z; } if (!planner.buffer_segment(rx, next_mesh_line_y, z_position + z0, e_position, scaled_fr_mm_s, extruder)) break; - current_yi += dyi; - yi_cnt--; + icell.y += iadd.y; + cnt.y--; } else { // Yes! Crossing a X Mesh Line next - float z0 = z_correction_for_y_on_vertical_mesh_line(ry, current_xi + dxi, current_yi - down_flag) - * planner.fade_scaling_factor_for_z(end[Z_AXIS]); + float z0 = z_correction_for_y_on_vertical_mesh_line(ry, icell.x + iadd.x, icell.y - ineg.y) + * planner.fade_scaling_factor_for_z(end.z); // Undefined parts of the Mesh in z_values[][] are NAN. // Replace NAN corrections with 0.0 to prevent NAN propagation. if (isnan(z0)) z0 = 0.0; if (!inf_normalized_flag) { - on_axis_distance = use_x_dist ? next_mesh_line_x - start[X_AXIS] : ry - start[Y_AXIS]; - e_position = start[E_AXIS] + on_axis_distance * e_normalized_dist; - z_position = start[Z_AXIS] + on_axis_distance * z_normalized_dist; + on_axis_distance = use_x_dist ? next_mesh_line_x - start.x : ry - start.y; + e_position = start.e + on_axis_distance * e_normalized_dist; + z_position = start.z + on_axis_distance * z_normalized_dist; } else { - e_position = end[E_AXIS]; - z_position = end[Z_AXIS]; + e_position = end.e; + z_position = end.z; } if (!planner.buffer_segment(next_mesh_line_x, ry, z_position + z0, e_position, scaled_fr_mm_s, extruder)) break; - current_xi += dxi; - xi_cnt--; + icell.x += iadd.x; + cnt.x--; } - if (xi_cnt < 0 || yi_cnt < 0) break; // Too far! Exit the loop and go to FINAL_MOVE + if (cnt.x < 0 || cnt.y < 0) break; // Too far! Exit the loop and go to FINAL_MOVE } - if (current_position[X_AXIS] != end[X_AXIS] || current_position[Y_AXIS] != end[Y_AXIS]) + if (xy_pos_t(current_position) != xy_pos_t(end)) goto FINAL_MOVE; - set_current_from_destination(); + current_position = destination; } #else // UBL_SEGMENTED @@ -356,56 +334,42 @@ bool _O2 unified_bed_leveling::line_to_destination_segmented(const feedRate_t &scaled_fr_mm_s) { - if (!position_is_reachable(destination[X_AXIS], destination[Y_AXIS])) // fail if moving outside reachable boundary - return true; // did not move, so current_position still accurate + if (!position_is_reachable(destination)) // fail if moving outside reachable boundary + return true; // did not move, so current_position still accurate - const float total[XYZE] = { - destination[X_AXIS] - current_position[X_AXIS], - destination[Y_AXIS] - current_position[Y_AXIS], - destination[Z_AXIS] - current_position[Z_AXIS], - destination[E_AXIS] - current_position[E_AXIS] - }; + const xyze_pos_t total = destination - current_position; - const float cartesian_xy_mm = HYPOT(total[X_AXIS], total[Y_AXIS]); // total horizontal xy distance + const float cart_xy_mm_2 = HYPOT2(total.x, total.y), + cart_xy_mm = SQRT(cart_xy_mm_2); // Total XY distance #if IS_KINEMATIC - const float seconds = cartesian_xy_mm / scaled_fr_mm_s; // Duration of XY move at requested rate - uint16_t segments = LROUND(delta_segments_per_second * seconds), // Preferred number of segments for distance @ feedrate - seglimit = LROUND(cartesian_xy_mm * RECIPROCAL(DELTA_SEGMENT_MIN_LENGTH)); // Number of segments at minimum segment length - NOMORE(segments, seglimit); // Limit to minimum segment length (fewer segments) + const float seconds = cart_xy_mm / scaled_fr_mm_s; // Duration of XY move at requested rate + uint16_t segments = LROUND(delta_segments_per_second * seconds), // Preferred number of segments for distance @ feedrate + seglimit = LROUND(cart_xy_mm * RECIPROCAL(DELTA_SEGMENT_MIN_LENGTH)); // Number of segments at minimum segment length + NOMORE(segments, seglimit); // Limit to minimum segment length (fewer segments) #else - uint16_t segments = LROUND(cartesian_xy_mm * RECIPROCAL(DELTA_SEGMENT_MIN_LENGTH)); // cartesian fixed segment length + uint16_t segments = LROUND(cart_xy_mm * RECIPROCAL(DELTA_SEGMENT_MIN_LENGTH)); // Cartesian fixed segment length #endif - NOLESS(segments, 1U); // must have at least one segment - const float inv_segments = 1.0f / segments; // divide once, multiply thereafter + NOLESS(segments, 1U); // Must have at least one segment + const float inv_segments = 1.0f / segments, // Reciprocal to save calculation + segment_xyz_mm = SQRT(cart_xy_mm_2 + sq(total.z)) * inv_segments; // Length of each segment - const float segment_xyz_mm = HYPOT(cartesian_xy_mm, total[Z_AXIS]) * inv_segments; // length of each segment #if ENABLED(SCARA_FEEDRATE_SCALING) const float inv_duration = scaled_fr_mm_s / segment_xyz_mm; #endif - const float diff[XYZE] = { - total[X_AXIS] * inv_segments, - total[Y_AXIS] * inv_segments, - total[Z_AXIS] * inv_segments, - total[E_AXIS] * inv_segments - }; + xyze_float_t diff = total * inv_segments; // Note that E segment distance could vary slightly as z mesh height // changes for each segment, but small enough to ignore. - float raw[XYZE] = { - current_position[X_AXIS], - current_position[Y_AXIS], - current_position[Z_AXIS], - current_position[E_AXIS] - }; + xyze_pos_t raw = current_position; // Just do plain segmentation if UBL is inactive or the target is above the fade height - if (!planner.leveling_active || !planner.leveling_active_at_z(destination[Z_AXIS])) { + if (!planner.leveling_active || !planner.leveling_active_at_z(destination.z)) { while (--segments) { - LOOP_XYZE(i) raw[i] += diff[i]; + raw += diff; planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, segment_xyz_mm #if ENABLED(SCARA_FEEDRATE_SCALING) , inv_duration @@ -417,17 +381,17 @@ , inv_duration #endif ); - return false; // moved but did not set_current_from_destination(); + return false; // Did not set current from destination } // Otherwise perform per-segment leveling #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - const float fade_scaling_factor = planner.fade_scaling_factor_for_z(destination[Z_AXIS]); + const float fade_scaling_factor = planner.fade_scaling_factor_for_z(destination.z); #endif - // increment to first segment destination - LOOP_XYZE(i) raw[i] += diff[i]; + // Move to first segment destination + raw += diff; for (;;) { // for each mesh cell encountered during the move @@ -438,75 +402,68 @@ // in top of loop and again re-find same adjacent cell and use it, just less efficient // for mesh inset area. - int8_t cell_xi = (raw[X_AXIS] - (MESH_MIN_X)) * RECIPROCAL(MESH_X_DIST), - cell_yi = (raw[Y_AXIS] - (MESH_MIN_Y)) * RECIPROCAL(MESH_Y_DIST); + xy_int8_t icell = { + int8_t((raw.x - (MESH_MIN_X)) * RECIPROCAL(MESH_X_DIST)), + int8_t((raw.y - (MESH_MIN_Y)) * RECIPROCAL(MESH_Y_DIST)) + }; + LIMIT(icell.x, 0, (GRID_MAX_POINTS_X) - 1); + LIMIT(icell.y, 0, (GRID_MAX_POINTS_Y) - 1); - LIMIT(cell_xi, 0, (GRID_MAX_POINTS_X) - 1); - LIMIT(cell_yi, 0, (GRID_MAX_POINTS_Y) - 1); - - const float x0 = mesh_index_to_xpos(cell_xi), // 64 byte table lookup avoids mul+add - y0 = mesh_index_to_ypos(cell_yi); - - float z_x0y0 = z_values[cell_xi ][cell_yi ], // z at lower left corner - z_x1y0 = z_values[cell_xi+1][cell_yi ], // z at upper left corner - z_x0y1 = z_values[cell_xi ][cell_yi+1], // z at lower right corner - z_x1y1 = z_values[cell_xi+1][cell_yi+1]; // z at upper right corner + float z_x0y0 = z_values[icell.x ][icell.y ], // z at lower left corner + z_x1y0 = z_values[icell.x+1][icell.y ], // z at upper left corner + z_x0y1 = z_values[icell.x ][icell.y+1], // z at lower right corner + z_x1y1 = z_values[icell.x+1][icell.y+1]; // z at upper right corner if (isnan(z_x0y0)) z_x0y0 = 0; // ideally activating planner.leveling_active (G29 A) if (isnan(z_x1y0)) z_x1y0 = 0; // should refuse if any invalid mesh points if (isnan(z_x0y1)) z_x0y1 = 0; // in order to avoid isnan tests per cell, if (isnan(z_x1y1)) z_x1y1 = 0; // thus guessing zero for undefined points - float cx = raw[X_AXIS] - x0, // cell-relative x and y - cy = raw[Y_AXIS] - y0; + const xy_pos_t pos = { mesh_index_to_xpos(icell.x), mesh_index_to_ypos(icell.y) }; + xy_pos_t cell = raw - pos; const float z_xmy0 = (z_x1y0 - z_x0y0) * RECIPROCAL(MESH_X_DIST), // z slope per x along y0 (lower left to lower right) z_xmy1 = (z_x1y1 - z_x0y1) * RECIPROCAL(MESH_X_DIST); // z slope per x along y1 (upper left to upper right) - float z_cxy0 = z_x0y0 + z_xmy0 * cx; // z height along y0 at cx (changes for each cx in cell) + float z_cxy0 = z_x0y0 + z_xmy0 * cell.x; // z height along y0 at cell.x (changes for each cell.x in cell) - const float z_cxy1 = z_x0y1 + z_xmy1 * cx, // z height along y1 at cx - z_cxyd = z_cxy1 - z_cxy0; // z height difference along cx from y0 to y1 + const float z_cxy1 = z_x0y1 + z_xmy1 * cell.x, // z height along y1 at cell.x + z_cxyd = z_cxy1 - z_cxy0; // z height difference along cell.x from y0 to y1 - float z_cxym = z_cxyd * RECIPROCAL(MESH_Y_DIST); // z slope per y along cx from y0 to y1 (changes for each cx in cell) + float z_cxym = z_cxyd * RECIPROCAL(MESH_Y_DIST); // z slope per y along cell.x from pos.y to y1 (changes for each cell.x in cell) - // float z_cxcy = z_cxy0 + z_cxym * cy; // interpolated mesh z height along cx at cy (do inside the segment loop) + // float z_cxcy = z_cxy0 + z_cxym * cell.y; // interpolated mesh z height along cell.x at cell.y (do inside the segment loop) // As subsequent segments step through this cell, the z_cxy0 intercept will change - // and the z_cxym slope will change, both as a function of cx within the cell, and + // and the z_cxym slope will change, both as a function of cell.x within the cell, and // each change by a constant for fixed segment lengths. - const float z_sxy0 = z_xmy0 * diff[X_AXIS], // per-segment adjustment to z_cxy0 - z_sxym = (z_xmy1 - z_xmy0) * RECIPROCAL(MESH_Y_DIST) * diff[X_AXIS]; // per-segment adjustment to z_cxym + const float z_sxy0 = z_xmy0 * diff.x, // per-segment adjustment to z_cxy0 + z_sxym = (z_xmy1 - z_xmy0) * RECIPROCAL(MESH_Y_DIST) * diff.x; // per-segment adjustment to z_cxym for (;;) { // for all segments within this mesh cell - if (--segments == 0) COPY(raw, destination); // if this is last segment, use destination for exact + if (--segments == 0) raw = destination; // if this is last segment, use destination for exact - const float z_cxcy = (z_cxy0 + z_cxym * cy) // interpolated mesh z height along cx at cy + const float z_cxcy = (z_cxy0 + z_cxym * cell.y) // interpolated mesh z height along cell.x at cell.y #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) * fade_scaling_factor // apply fade factor to interpolated mesh height #endif ; - const float z = raw[Z_AXIS]; - raw[Z_AXIS] += z_cxcy; - planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, segment_xyz_mm + planner.buffer_line(raw.x, raw.y, raw.z + z_cxcy, raw.e, scaled_fr_mm_s, active_extruder, segment_xyz_mm #if ENABLED(SCARA_FEEDRATE_SCALING) , inv_duration #endif ); - raw[Z_AXIS] = z; if (segments == 0) // done with last segment - return false; // did not set_current_from_destination() - - LOOP_XYZE(i) raw[i] += diff[i]; + return false; // didn't set current from destination - cx += diff[X_AXIS]; - cy += diff[Y_AXIS]; + raw += diff; + cell += diff; - if (!WITHIN(cx, 0, MESH_X_DIST) || !WITHIN(cy, 0, MESH_Y_DIST)) // done within this cell, break to next + if (!WITHIN(cell.x, 0, MESH_X_DIST) || !WITHIN(cell.y, 0, MESH_Y_DIST)) // done within this cell, break to next break; // Next segment still within same mesh cell, adjust the per-segment diff --git a/Marlin/src/feature/dac/dac_mcp4728.cpp b/Marlin/src/feature/dac/dac_mcp4728.cpp index cfe36dd39..19f8d5f64 100644 --- a/Marlin/src/feature/dac/dac_mcp4728.cpp +++ b/Marlin/src/feature/dac/dac_mcp4728.cpp @@ -36,7 +36,7 @@ #include "dac_mcp4728.h" -uint16_t mcp4728_values[XYZE]; +xyze_uint_t mcp4728_values; /** * Begin I2C, get current values (input register and eeprom) of mcp4728 @@ -121,8 +121,8 @@ uint8_t mcp4728_getDrvPct(const uint8_t channel) { return uint8_t(100.0 * mcp472 * Receives all Drive strengths as 0-100 percent values, updates * DAC Values array and calls fastwrite to update the DAC. */ -void mcp4728_setDrvPct(uint8_t pct[XYZE]) { - LOOP_XYZE(i) mcp4728_values[i] = 0.01 * pct[i] * (DAC_STEPPER_MAX); +void mcp4728_setDrvPct(xyze_uint8_t &pct) { + mcp4728_values *= 0.01 * pct * (DAC_STEPPER_MAX); mcp4728_fastWrite(); } diff --git a/Marlin/src/feature/dac/dac_mcp4728.h b/Marlin/src/feature/dac/dac_mcp4728.h index c81482945..92e28ffb2 100644 --- a/Marlin/src/feature/dac/dac_mcp4728.h +++ b/Marlin/src/feature/dac/dac_mcp4728.h @@ -25,6 +25,8 @@ * Arduino library for MicroChip MCP4728 I2C D/A converter. */ +#include "../../core/types.h" + #include #define defaultVDD DAC_STEPPER_MAX //was 5000 but differs with internal Vref @@ -54,4 +56,4 @@ uint16_t mcp4728_getValue(const uint8_t channel); uint8_t mcp4728_fastWrite(); uint8_t mcp4728_simpleCommand(const byte simpleCommand); uint8_t mcp4728_getDrvPct(const uint8_t channel); -void mcp4728_setDrvPct(uint8_t pct[XYZE]); +void mcp4728_setDrvPct(xyze_uint8_t &pct); diff --git a/Marlin/src/feature/dac/stepper_dac.cpp b/Marlin/src/feature/dac/stepper_dac.cpp index d1e101bd5..565b62a39 100644 --- a/Marlin/src/feature/dac/stepper_dac.cpp +++ b/Marlin/src/feature/dac/stepper_dac.cpp @@ -31,8 +31,8 @@ #include "stepper_dac.h" bool dac_present = false; -const uint8_t dac_order[NUM_AXIS] = DAC_STEPPER_ORDER; -uint8_t dac_channel_pct[XYZE] = DAC_MOTOR_CURRENT_DEFAULT; +constexpr xyze_uint8_t dac_order = DAC_STEPPER_ORDER; +xyze_uint8_t dac_channel_pct = DAC_MOTOR_CURRENT_DEFAULT; int dac_init() { #if PIN_EXISTS(DAC_DISABLE) @@ -77,8 +77,8 @@ void dac_current_raw(uint8_t channel, uint16_t val) { static float dac_perc(int8_t n) { return 100.0 * mcp4728_getValue(dac_order[n]) * RECIPROCAL(DAC_STEPPER_MAX); } static float dac_amps(int8_t n) { return mcp4728_getDrvPct(dac_order[n]) * (DAC_STEPPER_MAX) * 0.125 * RECIPROCAL(DAC_STEPPER_SENSE); } -uint8_t dac_current_get_percent(AxisEnum axis) { return mcp4728_getDrvPct(dac_order[axis]); } -void dac_current_set_percents(const uint8_t pct[XYZE]) { +uint8_t dac_current_get_percent(const AxisEnum axis) { return mcp4728_getDrvPct(dac_order[axis]); } +void dac_current_set_percents(xyze_uint8_t &pct) { LOOP_XYZE(i) dac_channel_pct[i] = pct[dac_order[i]]; mcp4728_setDrvPct(dac_channel_pct); } diff --git a/Marlin/src/feature/dac/stepper_dac.h b/Marlin/src/feature/dac/stepper_dac.h index 8ad51ee78..3496ebec4 100644 --- a/Marlin/src/feature/dac/stepper_dac.h +++ b/Marlin/src/feature/dac/stepper_dac.h @@ -33,4 +33,4 @@ void dac_current_raw(uint8_t channel, uint16_t val); void dac_print_values(); void dac_commit_eeprom(); uint8_t dac_current_get_percent(AxisEnum axis); -void dac_current_set_percents(const uint8_t pct[XYZE]); +void dac_current_set_percents(xyze_uint8_t &pct); diff --git a/Marlin/src/feature/fwretract.cpp b/Marlin/src/feature/fwretract.cpp index b4302cb17..896e60295 100644 --- a/Marlin/src/feature/fwretract.cpp +++ b/Marlin/src/feature/fwretract.cpp @@ -123,8 +123,8 @@ void FWRetract::retract(const bool retracting SERIAL_ECHOLNPAIR("retracted_swap[", i, "] ", retracted_swap[i]); #endif } - SERIAL_ECHOLNPAIR("current_position[z] ", current_position[Z_AXIS]); - SERIAL_ECHOLNPAIR("current_position[e] ", current_position[E_AXIS]); + SERIAL_ECHOLNPAIR("current_position.z ", current_position.z); + SERIAL_ECHOLNPAIR("current_position.e ", current_position.e); SERIAL_ECHOLNPAIR("current_hop ", current_hop); //*/ @@ -136,7 +136,7 @@ void FWRetract::retract(const bool retracting ); // The current position will be the destination for E and Z moves - set_destination_from_current(); + destination = current_position; #if ENABLED(RETRACT_SYNC_MIXING) const uint8_t old_mixing_tool = mixer.get_current_vtool(); @@ -147,7 +147,7 @@ void FWRetract::retract(const bool retracting if (retracting) { // Retract by moving from a faux E position back to the current E position current_retract[active_extruder] = base_retract; - prepare_internal_move_to_destination( // set_current_to_destination + prepare_internal_move_to_destination( // set current to destination settings.retract_feedrate_mm_s #if ENABLED(RETRACT_SYNC_MIXING) * (MIXING_STEPPERS) @@ -171,7 +171,7 @@ void FWRetract::retract(const bool retracting const float extra_recover = swapping ? settings.swap_retract_recover_extra : settings.retract_recover_extra; if (extra_recover) { - current_position[E_AXIS] -= extra_recover; // Adjust the current E position by the extra amount to recover + current_position.e -= extra_recover; // Adjust the current E position by the extra amount to recover sync_plan_position_e(); // Sync the planner position so the extra amount is recovered } @@ -207,8 +207,8 @@ void FWRetract::retract(const bool retracting SERIAL_ECHOLNPAIR("retracted_swap[", i, "] ", retracted_swap[i]); #endif } - SERIAL_ECHOLNPAIR("current_position[z] ", current_position[Z_AXIS]); - SERIAL_ECHOLNPAIR("current_position[e] ", current_position[E_AXIS]); + SERIAL_ECHOLNPAIR("current_position.z ", current_position.z); + SERIAL_ECHOLNPAIR("current_position.e ", current_position.e); SERIAL_ECHOLNPAIR("current_hop ", current_hop); //*/ } diff --git a/Marlin/src/feature/joystick.cpp b/Marlin/src/feature/joystick.cpp index bb54ff1d6..baa3142b6 100644 --- a/Marlin/src/feature/joystick.cpp +++ b/Marlin/src/feature/joystick.cpp @@ -71,35 +71,35 @@ Joystick joystick; #if HAS_JOY_ADC_X || HAS_JOY_ADC_Y || HAS_JOY_ADC_Z - void Joystick::calculate(float (&norm_jog)[XYZ]) { + void Joystick::calculate(xyz_float_t &norm_jog) { // Do nothing if enable pin (active-low) is not LOW #if HAS_JOY_ADC_EN if (READ(JOY_EN_PIN)) return; #endif - auto _normalize_joy = [](float &norm_jog, const int16_t raw, const int16_t (&joy_limits)[4]) { + auto _normalize_joy = [](float &axis_jog, const int16_t raw, const int16_t (&joy_limits)[4]) { if (WITHIN(raw, joy_limits[0], joy_limits[3])) { // within limits, check deadzone if (raw > joy_limits[2]) - norm_jog = (raw - joy_limits[2]) / float(joy_limits[3] - joy_limits[2]); + axis_jog = (raw - joy_limits[2]) / float(joy_limits[3] - joy_limits[2]); else if (raw < joy_limits[1]) - norm_jog = (raw - joy_limits[1]) / float(joy_limits[1] - joy_limits[0]); // negative value + axis_jog = (raw - joy_limits[1]) / float(joy_limits[1] - joy_limits[0]); // negative value // Map normal to jog value via quadratic relationship - norm_jog = SIGN(norm_jog) * sq(norm_jog); + axis_jog = SIGN(axis_jog) * sq(axis_jog); } }; #if HAS_JOY_ADC_X static constexpr int16_t joy_x_limits[4] = JOY_X_LIMITS; - _normalize_joy(norm_jog[X_AXIS], x.raw, joy_x_limits); + _normalize_joy(norm_jog.x, x.raw, joy_x_limits); #endif #if HAS_JOY_ADC_Y static constexpr int16_t joy_y_limits[4] = JOY_Y_LIMITS; - _normalize_joy(norm_jog[Y_AXIS], y.raw, joy_y_limits); + _normalize_joy(norm_jog.y, y.raw, joy_y_limits); #endif #if HAS_JOY_ADC_Z static constexpr int16_t joy_z_limits[4] = JOY_Z_LIMITS; - _normalize_joy(norm_jog[Z_AXIS], z.raw, joy_z_limits); + _normalize_joy(norm_jog.z, z.raw, joy_z_limits); #endif } @@ -129,7 +129,7 @@ Joystick joystick; // Normalized jog values are 0 for no movement and -1 or +1 for as max feedrate (nonlinear relationship) // Jog are initialized to zero and handling input can update values but doesn't have to // You could use a two-axis joystick and a one-axis keypad and they might work together - float norm_jog[XYZ] = { 0 }; + xyz_float_t norm_jog{0}; // Use ADC values and defined limits. The active zone is normalized: -1..0 (dead) 0..1 #if HAS_JOY_ADC_X || HAS_JOY_ADC_Y || HAS_JOY_ADC_Z @@ -143,16 +143,13 @@ Joystick joystick; ExtUI::_joystick_update(norm_jog); #endif - #if EITHER(ULTIPANEL, EXTENSIBLE_UI) - constexpr float manual_feedrate[XYZE] = MANUAL_FEEDRATE; - #endif - // norm_jog values of [-1 .. 1] maps linearly to [-feedrate .. feedrate] - float move_dist[XYZ] = { 0 }, hypot2 = 0; + xyz_float_t move_dist{0}; + float hypot2 = 0; LOOP_XYZ(i) if (norm_jog[i]) { move_dist[i] = seg_time * norm_jog[i] * #if EITHER(ULTIPANEL, EXTENSIBLE_UI) - MMM_TO_MMS(manual_feedrate[i]); + MMM_TO_MMS(manual_feedrate_mm_m[i]); #else planner.settings.max_feedrate_mm_s[i]; #endif @@ -160,7 +157,7 @@ Joystick joystick; } if (!UNEAR_ZERO(hypot2)) { - LOOP_XYZ(i) current_position[i] += move_dist[i]; + current_position += move_dist; const float length = sqrt(hypot2); injecting_now = true; planner.buffer_line(current_position, length / seg_time, active_extruder, length); diff --git a/Marlin/src/feature/joystick.h b/Marlin/src/feature/joystick.h index e96120517..50196374a 100644 --- a/Marlin/src/feature/joystick.h +++ b/Marlin/src/feature/joystick.h @@ -25,6 +25,8 @@ * joystick.h - joystick input / jogging */ +#include "../inc/MarlinConfigPre.h" +#include "../core/types.h" #include "../core/macros.h" #include "../module/temperature.h" @@ -46,7 +48,7 @@ class Joystick { #if ENABLED(JOYSTICK_DEBUG) static void report(); #endif - static void calculate(float (&norm_jog)[XYZ]); + static void calculate(xyz_float_t &norm_jog); static void inject_jog_moves(); }; diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index ff200d0af..ccb6f6323 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -64,7 +64,7 @@ // private: -static float resume_position[XYZE]; +static xyze_pos_t resume_position; PauseMode pause_mode = PAUSE_MODE_PAUSE_PRINT; @@ -126,8 +126,8 @@ void do_pause_e_move(const float &length, const feedRate_t &fr_mm_s) { #if HAS_FILAMENT_SENSOR runout.reset(); #endif - current_position[E_AXIS] += length / planner.e_factor[active_extruder]; - planner.buffer_line(current_position, fr_mm_s, active_extruder); + current_position.e += length / planner.e_factor[active_extruder]; + line_to_current_position(fr_mm_s); planner.synchronize(); } @@ -385,7 +385,7 @@ bool unload_filament(const float &unload_length, const bool show_lcd/*=false*/, */ uint8_t did_pause_print = 0; -bool pause_print(const float &retract, const point_t &park_point, const float &unload_length/*=0*/, const bool show_lcd/*=false*/ DXC_ARGS) { +bool pause_print(const float &retract, const xyz_pos_t &park_point, const float &unload_length/*=0*/, const bool show_lcd/*=false*/ DXC_ARGS) { #if !HAS_LCD_MENU UNUSED(show_lcd); @@ -432,7 +432,7 @@ bool pause_print(const float &retract, const point_t &park_point, const float &u print_job_timer.pause(); // Save current position - COPY(resume_position, current_position); + resume_position = current_position; // Wait for buffered blocks to complete planner.synchronize(); @@ -611,10 +611,10 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep * - Display "wait for print to resume" * - Re-prime the nozzle... * - FWRETRACT: Recover/prime from the prior G10. - * - !FWRETRACT: Retract by resume_position[E], if negative. + * - !FWRETRACT: Retract by resume_position.e, if negative. * Not sure how this logic comes into use. * - Move the nozzle back to resume_position - * - Sync the planner E to resume_position[E] + * - Sync the planner E to resume_position.e * - Send host action for resume, if configured * - Resume the current SD print job, if any */ @@ -652,13 +652,13 @@ void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_le #endif // If resume_position is negative - if (resume_position[E_AXIS] < 0) do_pause_e_move(resume_position[E_AXIS], feedRate_t(PAUSE_PARK_RETRACT_FEEDRATE)); + if (resume_position.e < 0) do_pause_e_move(resume_position.e, feedRate_t(PAUSE_PARK_RETRACT_FEEDRATE)); // Move XY to starting position, then Z - do_blocking_move_to_xy(resume_position[X_AXIS], resume_position[Y_AXIS], feedRate_t(NOZZLE_PARK_XY_FEEDRATE)); + do_blocking_move_to_xy(xy_pos_t(resume_position), feedRate_t(NOZZLE_PARK_XY_FEEDRATE)); // Move Z_AXIS to saved position - do_blocking_move_to_z(resume_position[Z_AXIS], feedRate_t(NOZZLE_PARK_Z_FEEDRATE)); + do_blocking_move_to_z(resume_position.z, feedRate_t(NOZZLE_PARK_Z_FEEDRATE)); #if ADVANCED_PAUSE_RESUME_PRIME != 0 do_pause_e_move(ADVANCED_PAUSE_RESUME_PRIME, feedRate_t(ADVANCED_PAUSE_PURGE_FEEDRATE)); @@ -666,7 +666,7 @@ void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_le // Now all extrusion positions are resumed and ready to be confirmed // Set extruder to saved position - planner.set_e_position_mm((destination[E_AXIS] = current_position[E_AXIS] = resume_position[E_AXIS])); + planner.set_e_position_mm((destination.e = current_position.e = resume_position.e)); #if HAS_LCD_MENU lcd_pause_show_message(PAUSE_MESSAGE_STATUS); diff --git a/Marlin/src/feature/pause.h b/Marlin/src/feature/pause.h index deb19f46a..cb6787d91 100644 --- a/Marlin/src/feature/pause.h +++ b/Marlin/src/feature/pause.h @@ -83,7 +83,7 @@ extern uint8_t did_pause_print; void do_pause_e_move(const float &length, const feedRate_t &fr_mm_s); -bool pause_print(const float &retract, const point_t &park_point, const float &unload_length=0, const bool show_lcd=false DXC_PARAMS); +bool pause_print(const float &retract, const xyz_pos_t &park_point, const float &unload_length=0, const bool show_lcd=false DXC_PARAMS); void wait_for_confirmation(const bool is_reload=false, const int8_t max_beep_count=0 DXC_PARAMS); diff --git a/Marlin/src/feature/power_loss_recovery.cpp b/Marlin/src/feature/power_loss_recovery.cpp index 3420f205f..bf13bb4b1 100644 --- a/Marlin/src/feature/power_loss_recovery.cpp +++ b/Marlin/src/feature/power_loss_recovery.cpp @@ -156,7 +156,7 @@ void PrintJobRecovery::save(const bool force/*=false*/, const bool save_queue/*= || ELAPSED(ms, next_save_ms) #endif // Save if Z is above the last-saved position by some minimum height - || current_position[Z_AXIS] > info.current_position[Z_AXIS] + POWER_LOSS_MIN_Z_CHANGE + || current_position.z > info.current_position.z + POWER_LOSS_MIN_Z_CHANGE #endif ) { @@ -170,12 +170,12 @@ void PrintJobRecovery::save(const bool force/*=false*/, const bool save_queue/*= info.valid_foot = info.valid_head; // Machine state - COPY(info.current_position, current_position); + info.current_position = current_position; #if HAS_HOME_OFFSET - COPY(info.home_offset, home_offset); + info.home_offset = home_offset; #endif #if HAS_POSITION_SHIFT - COPY(info.position_shift, position_shift); + info.position_shift = position_shift; #endif info.feedrate = uint16_t(feedrate_mm_s * 60.0f); @@ -361,13 +361,13 @@ void PrintJobRecovery::resume() { // Move back to the saved XY sprintf_P(cmd, PSTR("G1 X%s Y%s F3000"), - dtostrf(info.current_position[X_AXIS], 1, 3, str_1), - dtostrf(info.current_position[Y_AXIS], 1, 3, str_2) + dtostrf(info.current_position.x, 1, 3, str_1), + dtostrf(info.current_position.y, 1, 3, str_2) ); gcode.process_subcommands_now(cmd); // Move back to the saved Z - dtostrf(info.current_position[Z_AXIS], 1, 3, str_1); + dtostrf(info.current_position.z, 1, 3, str_1); #if Z_HOME_DIR > 0 sprintf_P(cmd, PSTR("G1 Z%s F200"), str_1); #else @@ -388,22 +388,20 @@ void PrintJobRecovery::resume() { gcode.process_subcommands_now(cmd); // Restore E position with G92.9 - sprintf_P(cmd, PSTR("G92.9 E%s"), dtostrf(info.current_position[E_AXIS], 1, 3, str_1)); + sprintf_P(cmd, PSTR("G92.9 E%s"), dtostrf(info.current_position.e, 1, 3, str_1)); gcode.process_subcommands_now(cmd); // Relative axis modes gcode.axis_relative = info.axis_relative; + #if HAS_HOME_OFFSET + home_offset = info.home_offset; + #endif + #if HAS_POSITION_SHIFT + position_shift = info.position_shift; + #endif #if HAS_HOME_OFFSET || HAS_POSITION_SHIFT - LOOP_XYZ(i) { - #if HAS_HOME_OFFSET - home_offset[i] = info.home_offset[i]; - #endif - #if HAS_POSITION_SHIFT - position_shift[i] = info.position_shift[i]; - #endif - update_workspace_offset((AxisEnum)i); - } + LOOP_XYZ(i) update_workspace_offset((AxisEnum)i); #endif // Resume the SD file from the last position diff --git a/Marlin/src/feature/power_loss_recovery.h b/Marlin/src/feature/power_loss_recovery.h index 58b6c1dc7..c02d5d34c 100644 --- a/Marlin/src/feature/power_loss_recovery.h +++ b/Marlin/src/feature/power_loss_recovery.h @@ -44,13 +44,13 @@ typedef struct { uint8_t valid_head; // Machine state - float current_position[NUM_AXIS]; + xyze_pos_t current_position; #if HAS_HOME_OFFSET - float home_offset[XYZ]; + xyz_pos_t home_offset; #endif #if HAS_POSITION_SHIFT - float position_shift[XYZ]; + xyz_pos_t position_shift; #endif uint16_t feedrate; diff --git a/Marlin/src/feature/prusa_MMU2/mmu2.cpp b/Marlin/src/feature/prusa_MMU2/mmu2.cpp index 8f5537ba9..dd0b2c681 100644 --- a/Marlin/src/feature/prusa_MMU2/mmu2.cpp +++ b/Marlin/src/feature/prusa_MMU2/mmu2.cpp @@ -550,10 +550,10 @@ bool MMU2::get_response() { */ void MMU2::manage_response(const bool move_axes, const bool turn_off_nozzle) { + constexpr xyz_pos_t park_point = NOZZLE_PARK_POINT; bool response = false; mmu_print_saved = false; - point_t park_point = NOZZLE_PARK_POINT; - float resume_position[XYZE]; + xyz_pos_t resume_position; int16_t resume_hotend_temp; KEEPALIVE_STATE(PAUSED_FOR_USER); @@ -572,7 +572,7 @@ void MMU2::manage_response(const bool move_axes, const bool turn_off_nozzle) { SERIAL_ECHOLNPGM("MMU not responding"); resume_hotend_temp = thermalManager.degTargetHotend(active_extruder); - COPY(resume_position, current_position); + resume_position = current_position; if (move_axes && all_axes_homed()) nozzle.park(2, park_point /*= NOZZLE_PARK_POINT*/); @@ -604,10 +604,10 @@ void MMU2::manage_response(const bool move_axes, const bool turn_off_nozzle) { BUZZ(200, 404); // Move XY to starting position, then Z - do_blocking_move_to_xy(resume_position[X_AXIS], resume_position[Y_AXIS], feedRate_t(NOZZLE_PARK_XY_FEEDRATE)); + do_blocking_move_to_xy(resume_position, feedRate_t(NOZZLE_PARK_XY_FEEDRATE)); // Move Z_AXIS to saved position - do_blocking_move_to_z(resume_position[Z_AXIS], feedRate_t(NOZZLE_PARK_Z_FEEDRATE)); + do_blocking_move_to_z(resume_position.z, feedRate_t(NOZZLE_PARK_Z_FEEDRATE)); } else { BUZZ(200, 404); @@ -698,8 +698,8 @@ void MMU2::filament_runout() { LCD_MESSAGEPGM(MSG_MMU2_EJECTING_FILAMENT); enable_E0(); - current_position[E_AXIS] -= MMU2_FILAMENTCHANGE_EJECT_FEED; - planner.buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 2500 / 60, active_extruder); + current_position.e -= MMU2_FILAMENTCHANGE_EJECT_FEED; + line_to_current_position(2500 / 60); planner.synchronize(); command(MMU_CMD_E0 + index); manage_response(false, false); @@ -787,7 +787,7 @@ void MMU2::filament_runout() { DEBUG_ECHO_START(); DEBUG_ECHOLNPAIR("E step ", es, "/", fr_mm_m); - current_position[E_AXIS] += es; + current_position.e += es; line_to_current_position(MMM_TO_MMS(fr_mm_m)); planner.synchronize(); diff --git a/Marlin/src/feature/runout.h b/Marlin/src/feature/runout.h index ab92c1f7c..0ce2c9af7 100644 --- a/Marlin/src/feature/runout.h +++ b/Marlin/src/feature/runout.h @@ -327,14 +327,14 @@ class FilamentSensorBase { } static inline void block_completed(const block_t* const b) { - if (b->steps[X_AXIS] || b->steps[Y_AXIS] || b->steps[Z_AXIS] + if (b->steps.x || b->steps.y || b->steps.z #if ENABLED(ADVANCED_PAUSE_FEATURE) || did_pause_print // Allow pause purge move to re-trigger runout state #endif ) { // Only trigger on extrusion with XYZ movement to allow filament change and retract/recover. const uint8_t e = b->extruder; - const int32_t steps = b->steps[E_AXIS]; + const int32_t steps = b->steps.e; runout_mm_countdown[e] -= (TEST(b->direction_bits, E_AXIS) ? -steps : steps) * planner.steps_to_mm[E_AXIS_N(e)]; } } diff --git a/Marlin/src/feature/tmc_util.h b/Marlin/src/feature/tmc_util.h index b5b45089b..bea5e14e9 100644 --- a/Marlin/src/feature/tmc_util.h +++ b/Marlin/src/feature/tmc_util.h @@ -367,9 +367,9 @@ void test_tmc_connection(const bool test_x, const bool test_y, const bool test_z constexpr uint16_t default_sg_guard_duration = 400; struct slow_homing_t { - struct { uint32_t x, y; } acceleration; + xy_ulong_t acceleration; #if HAS_CLASSIC_JERK - struct { float x, y; } jerk; + xy_float_t jerk_xy; #endif }; #endif diff --git a/Marlin/src/gcode/bedlevel/G26.cpp b/Marlin/src/gcode/bedlevel/G26.cpp index f98ffc88c..2356f0428 100644 --- a/Marlin/src/gcode/bedlevel/G26.cpp +++ b/Marlin/src/gcode/bedlevel/G26.cpp @@ -62,7 +62,7 @@ #define G26_ERR true #if ENABLED(ARC_SUPPORT) - void plan_arc(const float (&cart)[XYZE], const float (&offset)[2], const uint8_t clockwise); + void plan_arc(const xyze_pos_t &cart, const ab_float_t &offset, const uint8_t clockwise); #endif /** @@ -142,7 +142,7 @@ // Private functions -static uint16_t circle_flags[16], horizontal_mesh_line_flags[16], vertical_mesh_line_flags[16]; +static MeshFlags circle_flags, horizontal_mesh_line_flags, vertical_mesh_line_flags; float g26_e_axis_feedrate = 0.025, random_deviation = 0.0; @@ -154,7 +154,7 @@ float g26_extrusion_multiplier, g26_layer_height, g26_prime_length; -float g26_x_pos = 0, g26_y_pos = 0; +xy_pos_t g26_pos; // = { 0, 0 } int16_t g26_bed_temp, g26_hotend_temp; @@ -178,85 +178,85 @@ int8_t g26_prime_flag; #endif -mesh_index_pair find_closest_circle_to_print(const float &X, const float &Y) { +mesh_index_pair find_closest_circle_to_print(const xy_pos_t &pos) { float closest = 99999.99; - mesh_index_pair return_val; + mesh_index_pair out_point; - return_val.x_index = return_val.y_index = -1; + out_point.pos = -1; for (uint8_t i = 0; i < GRID_MAX_POINTS_X; i++) { for (uint8_t j = 0; j < GRID_MAX_POINTS_Y; j++) { - if (!is_bitmap_set(circle_flags, i, j)) { - const float mx = _GET_MESH_X(i), // We found a circle that needs to be printed - my = _GET_MESH_Y(j); + if (!circle_flags.marked(i, j)) { + // We found a circle that needs to be printed + const xy_pos_t m = { _GET_MESH_X(i), _GET_MESH_Y(j) }; // Get the distance to this intersection - float f = HYPOT(X - mx, Y - my); + float f = (pos - m).magnitude(); // It is possible that we are being called with the values // to let us find the closest circle to the start position. // But if this is not the case, add a small weighting to the // distance calculation to help it choose a better place to continue. - f += HYPOT(g26_x_pos - mx, g26_y_pos - my) / 15.0; + f += (g26_pos - m).magnitude() / 15.0f; - // Add in the specified amount of Random Noise to our search - if (random_deviation > 1.0) - f += random(0.0, random_deviation); + // Add the specified amount of Random Noise to our search + if (random_deviation > 1.0) f += random(0.0, random_deviation); if (f < closest) { - closest = f; // We found a closer location that is still - return_val.x_index = i; // un-printed --- save the data for it - return_val.y_index = j; - return_val.distance = closest; + closest = f; // Found a closer un-printed location + out_point.pos.set(i, j); // Save its data + out_point.distance = closest; } } } } - bitmap_set(circle_flags, return_val.x_index, return_val.y_index); // Mark this location as done. - return return_val; + circle_flags.mark(out_point); // Mark this location as done. + return out_point; } void move_to(const float &rx, const float &ry, const float &z, const float &e_delta) { static float last_z = -999.99; - bool has_xy_component = (rx != current_position[X_AXIS] || ry != current_position[Y_AXIS]); // Check if X or Y is involved in the movement. + const xy_pos_t dest = { rx, ry }; - if (z != last_z) { - last_z = z; - const feedRate_t feed_value = planner.settings.max_feedrate_mm_s[Z_AXIS] * 0.5f; // Use half of the Z_AXIS max feed rate + const bool has_xy_component = dest != current_position; // Check if X or Y is involved in the movement. - destination[X_AXIS] = current_position[X_AXIS]; - destination[Y_AXIS] = current_position[Y_AXIS]; - destination[Z_AXIS] = z; // We know the last_z!=z or we wouldn't be in this block of code. - destination[E_AXIS] = current_position[E_AXIS]; + destination = current_position; + if (z != last_z) { + last_z = destination.z = z; + const feedRate_t feed_value = planner.settings.max_feedrate_mm_s[Z_AXIS] * 0.5f; // Use half of the Z_AXIS max feed rate prepare_internal_move_to_destination(feed_value); - set_destination_from_current(); + destination = current_position; } // If X or Y is involved do a 'normal' move. Otherwise retract/recover/hop. + destination = dest; + destination.e += e_delta; const feedRate_t feed_value = has_xy_component ? feedRate_t(G26_XY_FEEDRATE) : planner.settings.max_feedrate_mm_s[E_AXIS] * 0.666f; - - destination[X_AXIS] = rx; - destination[Y_AXIS] = ry; - destination[E_AXIS] += e_delta; - prepare_internal_move_to_destination(feed_value); - set_destination_from_current(); + destination = current_position; } -FORCE_INLINE void move_to(const float (&where)[XYZE], const float &de) { move_to(where[X_AXIS], where[Y_AXIS], where[Z_AXIS], de); } +FORCE_INLINE void move_to(const xyz_pos_t &where, const float &de) { move_to(where.x, where.y, where.z, de); } -void retract_filament(const float (&where)[XYZE]) { +void retract_filament(const xyz_pos_t &where) { if (!g26_retracted) { // Only retract if we are not already retracted! g26_retracted = true; - move_to(where, -1.0 * g26_retraction_multiplier); + move_to(where, -1.0f * g26_retraction_multiplier); } } -void recover_filament(const float (&where)[XYZE]) { +// TODO: Parameterize the Z lift with a define +void retract_lift_move(const xyz_pos_t &s) { + retract_filament(destination); + move_to(current_position.x, current_position.y, current_position.z + 0.5f, 0.0); // Z lift to minimize scraping + move_to(s.x, s.y, s.z + 0.5f, 0.0); // Get to the starting point with no extrusion while lifted +} + +void recover_filament(const xyz_pos_t &where) { if (g26_retracted) { // Only un-retract if we are retracted. - move_to(where, 1.2 * g26_retraction_multiplier); + move_to(where, 1.2f * g26_retraction_multiplier); g26_retracted = false; } } @@ -276,41 +276,34 @@ void recover_filament(const float (&where)[XYZE]) { * segment of a 'circle'. The time this requires is very short and is easily saved by the other * cases where the optimization comes into play. */ -void print_line_from_here_to_there(const float &sx, const float &sy, const float &sz, const float &ex, const float &ey, const float &ez) { - const float dx_s = current_position[X_AXIS] - sx, // find our distance from the start of the actual line segment - dy_s = current_position[Y_AXIS] - sy, - dist_start = HYPOT2(dx_s, dy_s), // We don't need to do a sqrt(), we can compare the distance^2 - // to save computation time - dx_e = current_position[X_AXIS] - ex, // find our distance from the end of the actual line segment - dy_e = current_position[Y_AXIS] - ey, - dist_end = HYPOT2(dx_e, dy_e), +void print_line_from_here_to_there(const xyz_pos_t &s, const xyz_pos_t &e) { - line_length = HYPOT(ex - sx, ey - sy); + // Distances to the start / end of the line + xy_float_t svec = current_position - s, evec = current_position - e; + + const float dist_start = HYPOT2(svec.x, svec.y), + dist_end = HYPOT2(evec.x, evec.y), + line_length = HYPOT(e.x - s.x, e.y - s.y); // If the end point of the line is closer to the nozzle, flip the direction, // moving from the end to the start. On very small lines the optimization isn't worth it. if (dist_end < dist_start && (INTERSECTION_CIRCLE_RADIUS) < ABS(line_length)) - return print_line_from_here_to_there(ex, ey, ez, sx, sy, sz); + return print_line_from_here_to_there(e, s); - // Decide whether to retract & bump + // Decide whether to retract & lift + if (dist_start > 2.0) retract_lift_move(s); - if (dist_start > 2.0) { - retract_filament(destination); - //todo: parameterize the bump height with a define - move_to(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS] + 0.500, 0.0); // Z bump to minimize scraping - move_to(sx, sy, sz + 0.500, 0.0); // Get to the starting point with no extrusion while bumped - } - - move_to(sx, sy, sz, 0.0); // Get to the starting point with no extrusion / un-Z bump + move_to(s, 0.0); // Get to the starting point with no extrusion / un-Z lift const float e_pos_delta = line_length * g26_e_axis_feedrate * g26_extrusion_multiplier; recover_filament(destination); - move_to(ex, ey, ez, e_pos_delta); // Get to the ending point with an appropriate amount of extrusion + move_to(e, e_pos_delta); // Get to the ending point with an appropriate amount of extrusion } inline bool look_for_lines_to_connect() { - float sx, sy, ex, ey; + xyz_pos_t s, e; + s.z = e.z = g26_layer_height; for (uint8_t i = 0; i < GRID_MAX_POINTS_X; i++) { for (uint8_t j = 0; j < GRID_MAX_POINTS_Y; j++) { @@ -319,43 +312,43 @@ inline bool look_for_lines_to_connect() { if (user_canceled()) return true; #endif - if (i < GRID_MAX_POINTS_X) { // Can't connect to anything to the right than GRID_MAX_POINTS_X. - // Already a half circle at the edge of the bed. + if (i < GRID_MAX_POINTS_X) { // Can't connect to anything farther to the right than GRID_MAX_POINTS_X. + // Already a half circle at the edge of the bed. - if (is_bitmap_set(circle_flags, i, j) && is_bitmap_set(circle_flags, i + 1, j)) { // check if we can do a line to the left - if (!is_bitmap_set(horizontal_mesh_line_flags, i, j)) { + if (circle_flags.marked(i, j) && circle_flags.marked(i + 1, j)) { // Test whether a leftward line can be done + if (!horizontal_mesh_line_flags.marked(i, j)) { // Two circles need a horizontal line to connect them - sx = _GET_MESH_X( i ) + (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // right edge - ex = _GET_MESH_X(i + 1) - (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // left edge + s.x = _GET_MESH_X( i ) + (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // right edge + e.x = _GET_MESH_X(i + 1) - (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // left edge - LIMIT(sx, X_MIN_POS + 1, X_MAX_POS - 1); - sy = ey = constrain(_GET_MESH_Y(j), Y_MIN_POS + 1, Y_MAX_POS - 1); - LIMIT(ex, X_MIN_POS + 1, X_MAX_POS - 1); + LIMIT(s.x, X_MIN_POS + 1, X_MAX_POS - 1); + s.y = e.y = constrain(_GET_MESH_Y(j), Y_MIN_POS + 1, Y_MAX_POS - 1); + LIMIT(e.x, X_MIN_POS + 1, X_MAX_POS - 1); - if (position_is_reachable(sx, sy) && position_is_reachable(ex, ey)) - print_line_from_here_to_there(sx, sy, g26_layer_height, ex, ey, g26_layer_height); + if (position_is_reachable(s.x, s.y) && position_is_reachable(e.x, e.y)) + print_line_from_here_to_there(s, e); - bitmap_set(horizontal_mesh_line_flags, i, j); // Mark done, even if skipped + horizontal_mesh_line_flags.mark(i, j); // Mark done, even if skipped } } if (j < GRID_MAX_POINTS_Y) { // Can't connect to anything further back than GRID_MAX_POINTS_Y. // Already a half circle at the edge of the bed. - if (is_bitmap_set(circle_flags, i, j) && is_bitmap_set(circle_flags, i, j + 1)) { // check if we can do a line straight down - if (!is_bitmap_set( vertical_mesh_line_flags, i, j)) { + if (circle_flags.marked(i, j) && circle_flags.marked(i, j + 1)) { // Test whether a downward line can be done + if (!vertical_mesh_line_flags.marked(i, j)) { // Two circles that need a vertical line to connect them - sy = _GET_MESH_Y( j ) + (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // top edge - ey = _GET_MESH_Y(j + 1) - (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // bottom edge + s.y = _GET_MESH_Y( j ) + (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // top edge + e.y = _GET_MESH_Y(j + 1) - (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // bottom edge - sx = ex = constrain(_GET_MESH_X(i), X_MIN_POS + 1, X_MAX_POS - 1); - LIMIT(sy, Y_MIN_POS + 1, Y_MAX_POS - 1); - LIMIT(ey, Y_MIN_POS + 1, Y_MAX_POS - 1); + s.x = e.x = constrain(_GET_MESH_X(i), X_MIN_POS + 1, X_MAX_POS - 1); + LIMIT(s.y, Y_MIN_POS + 1, Y_MAX_POS - 1); + LIMIT(e.y, Y_MIN_POS + 1, Y_MAX_POS - 1); - if (position_is_reachable(sx, sy) && position_is_reachable(ex, ey)) - print_line_from_here_to_there(sx, sy, g26_layer_height, ex, ey, g26_layer_height); + if (position_is_reachable(s.x, s.y) && position_is_reachable(e.x, e.y)) + print_line_from_here_to_there(s, e); - bitmap_set(vertical_mesh_line_flags, i, j); // Mark done, even if skipped + vertical_mesh_line_flags.mark(i, j); // Mark done, even if skipped } } } @@ -436,19 +429,19 @@ inline bool prime_nozzle() { ui.set_status_P(PSTR(MSG_G26_MANUAL_PRIME), 99); ui.chirp(); - set_destination_from_current(); + destination = current_position; recover_filament(destination); // Make sure G26 doesn't think the filament is retracted(). while (!ui.button_pressed()) { ui.chirp(); - destination[E_AXIS] += 0.25; + destination.e += 0.25; #if ENABLED(PREVENT_LENGTHY_EXTRUDE) Total_Prime += 0.25; if (Total_Prime >= EXTRUDE_MAXLENGTH) return G26_ERR; #endif prepare_internal_move_to_destination(fr_slow_e); - set_destination_from_current(); + destination = current_position; planner.synchronize(); // Without this synchronize, the purge is more consistent, // but because the planner has a buffer, we won't be able // to stop as quickly. So we put up with the less smooth @@ -468,10 +461,10 @@ inline bool prime_nozzle() { ui.set_status_P(PSTR(MSG_G26_FIXED_LENGTH), 99); ui.quick_feedback(); #endif - set_destination_from_current(); - destination[E_AXIS] += g26_prime_length; + destination = current_position; + destination.e += g26_prime_length; prepare_internal_move_to_destination(fr_slow_e); - set_destination_from_current(); + destination.e -= g26_prime_length; retract_filament(destination); } @@ -630,9 +623,9 @@ void GcodeSuite::G26() { return; } - g26_x_pos = parser.seenval('X') ? RAW_X_POSITION(parser.value_linear_units()) : current_position[X_AXIS]; - g26_y_pos = parser.seenval('Y') ? RAW_Y_POSITION(parser.value_linear_units()) : current_position[Y_AXIS]; - if (!position_is_reachable(g26_x_pos, g26_y_pos)) { + g26_pos.set(parser.seenval('X') ? RAW_X_POSITION(parser.value_linear_units()) : current_position.x, + parser.seenval('Y') ? RAW_Y_POSITION(parser.value_linear_units()) : current_position.y); + if (!position_is_reachable(g26_pos.x, g26_pos.y)) { SERIAL_ECHOLNPGM("?Specified X,Y coordinate out of bounds."); return; } @@ -642,9 +635,9 @@ void GcodeSuite::G26() { */ set_bed_leveling_enabled(!parser.seen('D')); - if (current_position[Z_AXIS] < Z_CLEARANCE_BETWEEN_PROBES) { + if (current_position.z < Z_CLEARANCE_BETWEEN_PROBES) { do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); - set_current_from_destination(); + current_position = destination; } #if DISABLED(NO_VOLUMETRICS) @@ -655,7 +648,7 @@ void GcodeSuite::G26() { if (turn_on_heaters() != G26_OK) goto LEAVE; - current_position[E_AXIS] = 0.0; + current_position.e = 0.0; sync_plan_position_e(); if (g26_prime_flag && prime_nozzle() != G26_OK) goto LEAVE; @@ -670,13 +663,13 @@ void GcodeSuite::G26() { * It's "Show Time" !!! */ - ZERO(circle_flags); - ZERO(horizontal_mesh_line_flags); - ZERO(vertical_mesh_line_flags); + circle_flags.reset(); + horizontal_mesh_line_flags.reset(); + vertical_mesh_line_flags.reset(); // Move nozzle to the specified height for the first layer - set_destination_from_current(); - destination[Z_AXIS] = g26_layer_height; + destination = current_position; + destination.z = g26_layer_height; move_to(destination, 0.0); move_to(destination, g26_ooze_amount); @@ -706,71 +699,68 @@ void GcodeSuite::G26() { mesh_index_pair location; do { - location = g26_continue_with_closest - ? find_closest_circle_to_print(current_position[X_AXIS], current_position[Y_AXIS]) - : find_closest_circle_to_print(g26_x_pos, g26_y_pos); // Find the closest Mesh Intersection to where we are now. + // Find the nearest confluence + location = find_closest_circle_to_print(g26_continue_with_closest ? xy_pos_t(current_position) : g26_pos); - if (location.x_index >= 0 && location.y_index >= 0) { - const float circle_x = _GET_MESH_X(location.x_index), - circle_y = _GET_MESH_Y(location.y_index); + if (location.valid()) { + const xy_pos_t circle = _GET_MESH_POS(location.pos); // If this mesh location is outside the printable_radius, skip it. - if (!position_is_reachable(circle_x, circle_y)) continue; + if (!position_is_reachable(circle)) continue; // Determine where to start and end the circle, // which is always drawn counter-clockwise. - const uint8_t xi = location.x_index, yi = location.y_index; - const bool f = yi == 0, r = xi >= GRID_MAX_POINTS_X - 1, b = yi >= GRID_MAX_POINTS_Y - 1; + const xy_int8_t st = location; + const bool f = st.y == 0, + r = st.x >= GRID_MAX_POINTS_X - 1, + b = st.y >= GRID_MAX_POINTS_Y - 1; #if ENABLED(ARC_SUPPORT) #define ARC_LENGTH(quarters) (INTERSECTION_CIRCLE_RADIUS * M_PI * (quarters) / 2) #define INTERSECTION_CIRCLE_DIAM ((INTERSECTION_CIRCLE_RADIUS) * 2) - float sx = circle_x + INTERSECTION_CIRCLE_RADIUS, // default to full circle - ex = circle_x + INTERSECTION_CIRCLE_RADIUS, - sy = circle_y, ey = circle_y, - arc_length = ARC_LENGTH(4); + + xy_float_t e = { circle.x + INTERSECTION_CIRCLE_RADIUS, circle.y }; + xyz_float_t s = e; // Figure out where to start and end the arc - we always print counterclockwise - if (xi == 0) { // left edge - if (!f) { sx = circle_x; sy -= INTERSECTION_CIRCLE_RADIUS; } - if (!b) { ex = circle_x; ey += INTERSECTION_CIRCLE_RADIUS; } + float arc_length = ARC_LENGTH(4); + if (st.x == 0) { // left edge + if (!f) { s.x = circle.x; s.y -= INTERSECTION_CIRCLE_RADIUS; } + if (!b) { e.x = circle.x; e.y += INTERSECTION_CIRCLE_RADIUS; } arc_length = (f || b) ? ARC_LENGTH(1) : ARC_LENGTH(2); } else if (r) { // right edge - sx = b ? circle_x - (INTERSECTION_CIRCLE_RADIUS) : circle_x; - ex = f ? circle_x - (INTERSECTION_CIRCLE_RADIUS) : circle_x; - sy = b ? circle_y : circle_y + INTERSECTION_CIRCLE_RADIUS; - ey = f ? circle_y : circle_y - (INTERSECTION_CIRCLE_RADIUS); + if (b) s.set(circle.x - (INTERSECTION_CIRCLE_RADIUS), circle.y); + else s.set(circle.x, circle.y + INTERSECTION_CIRCLE_RADIUS); + if (f) e.set(circle.x - (INTERSECTION_CIRCLE_RADIUS), circle.y); + else e.set(circle.x, circle.y - (INTERSECTION_CIRCLE_RADIUS)); arc_length = (f || b) ? ARC_LENGTH(1) : ARC_LENGTH(2); } else if (f) { - ex -= INTERSECTION_CIRCLE_DIAM; + e.x -= INTERSECTION_CIRCLE_DIAM; arc_length = ARC_LENGTH(2); } else if (b) { - sx -= INTERSECTION_CIRCLE_DIAM; + s.x -= INTERSECTION_CIRCLE_DIAM; arc_length = ARC_LENGTH(2); } - const float arc_offset[2] = { circle_x - sx, circle_y - sy }, - dx_s = current_position[X_AXIS] - sx, // find our distance from the start of the actual circle - dy_s = current_position[Y_AXIS] - sy, - dist_start = HYPOT2(dx_s, dy_s), - endpoint[XYZE] = { - ex, ey, - g26_layer_height, - current_position[E_AXIS] + (arc_length * g26_e_axis_feedrate * g26_extrusion_multiplier) - }; + const ab_float_t arc_offset = circle - s; + const xy_float_t dist = current_position - s; // Distance from the start of the actual circle + const float dist_start = HYPOT2(dist.x, dist.y); + const xyze_pos_t endpoint = { + e.x, e.y, g26_layer_height, + current_position.e + (arc_length * g26_e_axis_feedrate * g26_extrusion_multiplier) + }; if (dist_start > 2.0) { - retract_filament(destination); - //todo: parameterize the bump height with a define - move_to(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS] + 0.500, 0.0); // Z bump to minimize scraping - move_to(sx, sy, g26_layer_height + 0.500, 0.0); // Get to the starting point with no extrusion while bumped + s.z = g26_layer_height + 0.5f; + retract_lift_move(s); } - move_to(sx, sy, g26_layer_height, 0.0); // Get to the starting point with no extrusion / un-Z bump + s.z = g26_layer_height; + move_to(s, 0.0); // Get to the starting point with no extrusion / un-Z lift recover_filament(destination); @@ -778,7 +768,7 @@ void GcodeSuite::G26() { feedrate_mm_s = PLANNER_XY_FEEDRATE() * 0.1f; plan_arc(endpoint, arc_offset, false); // Draw a counter-clockwise arc feedrate_mm_s = old_feedrate; - set_destination_from_current(); + destination = current_position; #if HAS_LCD_MENU if (user_canceled()) goto LEAVE; // Check if the user wants to stop the Mesh Validation @@ -787,7 +777,7 @@ void GcodeSuite::G26() { #else // !ARC_SUPPORT int8_t start_ind = -2, end_ind = 9; // Assume a full circle (from 5:00 to 5:00) - if (xi == 0) { // Left edge? Just right half. + if (st.x == 0) { // Left edge? Just right half. start_ind = f ? 0 : -3; // 03:00 to 12:00 for front-left end_ind = b ? 0 : 2; // 06:00 to 03:00 for back-left } @@ -810,23 +800,21 @@ void GcodeSuite::G26() { if (user_canceled()) goto LEAVE; // Check if the user wants to stop the Mesh Validation #endif - float rx = circle_x + _COS(ind), // For speed, these are now a lookup table entry - ry = circle_y + _SIN(ind), - xe = circle_x + _COS(ind + 1), - ye = circle_y + _SIN(ind + 1); + xy_float_t p = { circle.x + _COS(ind ), circle.y + _SIN(ind ), g26_layer_height }, + q = { circle.x + _COS(ind + 1), circle.y + _SIN(ind + 1), g26_layer_height }; #if IS_KINEMATIC // Check to make sure this segment is entirely on the bed, skip if not. - if (!position_is_reachable(rx, ry) || !position_is_reachable(xe, ye)) continue; - #else // not, we need to skip - LIMIT(rx, X_MIN_POS + 1, X_MAX_POS - 1); // This keeps us from bumping the endstops - LIMIT(ry, Y_MIN_POS + 1, Y_MAX_POS - 1); - LIMIT(xe, X_MIN_POS + 1, X_MAX_POS - 1); - LIMIT(ye, Y_MIN_POS + 1, Y_MAX_POS - 1); + if (!position_is_reachable(p) || !position_is_reachable(q)) continue; + #else + LIMIT(p.x, X_MIN_POS + 1, X_MAX_POS - 1); // Prevent hitting the endstops + LIMIT(p.y, Y_MIN_POS + 1, Y_MAX_POS - 1); + LIMIT(q.x, X_MIN_POS + 1, X_MAX_POS - 1); + LIMIT(q.y, Y_MIN_POS + 1, Y_MAX_POS - 1); #endif - print_line_from_here_to_there(rx, ry, g26_layer_height, xe, ye, g26_layer_height); - SERIAL_FLUSH(); // Prevent host M105 buffer overrun. + print_line_from_here_to_there(p, q); + SERIAL_FLUSH(); // Prevent host M105 buffer overrun. } #endif // !ARC_SUPPORT @@ -836,19 +824,18 @@ void GcodeSuite::G26() { SERIAL_FLUSH(); // Prevent host M105 buffer overrun. - } while (--g26_repeats && location.x_index >= 0 && location.y_index >= 0); + } while (--g26_repeats && location.valid()); LEAVE: ui.set_status_P(PSTR(MSG_G26_LEAVING), -1); retract_filament(destination); - destination[Z_AXIS] = Z_CLEARANCE_BETWEEN_PROBES; + destination.z = Z_CLEARANCE_BETWEEN_PROBES; move_to(destination, 0); // Raise the nozzle - destination[X_AXIS] = g26_x_pos; // Move back to the starting position - destination[Y_AXIS] = g26_y_pos; - //destination[Z_AXIS] = Z_CLEARANCE_BETWEEN_PROBES; // Keep the nozzle where it is + destination.set(g26_pos.x, g26_pos.y); // Move back to the starting position + //destination.z = Z_CLEARANCE_BETWEEN_PROBES; // Keep the nozzle where it is move_to(destination, 0); // Move back to the starting position diff --git a/Marlin/src/gcode/bedlevel/G42.cpp b/Marlin/src/gcode/bedlevel/G42.cpp index 55bc82317..424e5a699 100644 --- a/Marlin/src/gcode/bedlevel/G42.cpp +++ b/Marlin/src/gcode/bedlevel/G42.cpp @@ -27,6 +27,7 @@ #include "../gcode.h" #include "../../Marlin.h" // for IsRunning() #include "../../module/motion.h" +#include "../../module/probe.h" // for probe_offset #include "../../feature/bedlevel/bedlevel.h" /** @@ -44,15 +45,15 @@ void GcodeSuite::G42() { return; } - set_destination_from_current(); + destination = current_position; - if (hasI) destination[X_AXIS] = _GET_MESH_X(ix); - if (hasJ) destination[Y_AXIS] = _GET_MESH_Y(iy); + if (hasI) destination.x = _GET_MESH_X(ix); + if (hasJ) destination.y = _GET_MESH_Y(iy); #if HAS_BED_PROBE if (parser.boolval('P')) { - if (hasI) destination[X_AXIS] -= probe_offset[X_AXIS]; - if (hasJ) destination[Y_AXIS] -= probe_offset[Y_AXIS]; + if (hasI) destination.x -= probe_offset.x; + if (hasJ) destination.y -= probe_offset.y; } #endif diff --git a/Marlin/src/gcode/bedlevel/M420.cpp b/Marlin/src/gcode/bedlevel/M420.cpp index d3d94a99c..779490840 100644 --- a/Marlin/src/gcode/bedlevel/M420.cpp +++ b/Marlin/src/gcode/bedlevel/M420.cpp @@ -66,10 +66,9 @@ void GcodeSuite::M420() { #if ENABLED(AUTO_BED_LEVELING_BILINEAR) const float x_min = probe_min_x(), x_max = probe_max_x(), y_min = probe_min_y(), y_max = probe_max_y(); - bilinear_start[X_AXIS] = x_min; - bilinear_start[Y_AXIS] = y_min; - bilinear_grid_spacing[X_AXIS] = (x_max - x_min) / (GRID_MAX_POINTS_X - 1); - bilinear_grid_spacing[Y_AXIS] = (y_max - y_min) / (GRID_MAX_POINTS_Y - 1); + bilinear_start.set(x_min, y_min); + bilinear_grid_spacing.set((x_max - x_min) / (GRID_MAX_POINTS_X - 1), + (y_max - y_min) / (GRID_MAX_POINTS_Y - 1)); #endif for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) { @@ -91,7 +90,7 @@ void GcodeSuite::M420() { // (Don't disable for just M420 or M420 V) if (seen_S && !to_enable) set_bed_leveling_enabled(false); - const float oldpos[] = { current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS] }; + xyz_pos_t oldpos = current_position; #if ENABLED(AUTO_BED_LEVELING_UBL) @@ -251,7 +250,7 @@ void GcodeSuite::M420() { #endif // Report change in position - if (memcmp(oldpos, current_position, sizeof(oldpos))) + if (oldpos != current_position) report_current_position(); } diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index 45eec2805..5f1ef2e9a 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -61,15 +61,15 @@ #if ABL_GRID #if ENABLED(PROBE_Y_FIRST) - #define PR_OUTER_VAR xCount - #define PR_OUTER_END abl_grid_points_x - #define PR_INNER_VAR yCount - #define PR_INNER_END abl_grid_points_y + #define PR_OUTER_VAR meshCount.x + #define PR_OUTER_END abl_grid_points.x + #define PR_INNER_VAR meshCount.y + #define PR_INNER_END abl_grid_points.y #else - #define PR_OUTER_VAR yCount - #define PR_OUTER_END abl_grid_points_y - #define PR_INNER_VAR xCount - #define PR_INNER_END abl_grid_points_x + #define PR_OUTER_VAR meshCount.y + #define PR_OUTER_END abl_grid_points.y + #define PR_INNER_VAR meshCount.x + #define PR_INNER_END abl_grid_points.x #endif #endif @@ -210,7 +210,8 @@ G29_TYPE GcodeSuite::G29() { #endif ABL_VAR int verbose_level; - ABL_VAR float xProbe, yProbe, measured_z; + ABL_VAR xy_pos_t probePos; + ABL_VAR float measured_z; ABL_VAR bool dryrun, abl_should_enable; #if EITHER(PROBE_MANUALLY, AUTO_BED_LEVELING_LINEAR) @@ -224,20 +225,17 @@ G29_TYPE GcodeSuite::G29() { #if ABL_GRID #if ENABLED(PROBE_MANUALLY) - ABL_VAR uint8_t PR_OUTER_VAR; - ABL_VAR int8_t PR_INNER_VAR; + ABL_VAR xy_int8_t meshCount; #endif - ABL_VAR int left_probe_bed_position, right_probe_bed_position, front_probe_bed_position, back_probe_bed_position; - ABL_VAR float xGridSpacing = 0, yGridSpacing = 0; + ABL_VAR xy_int_t probe_position_lf, probe_position_rb; + ABL_VAR xy_float_t gridSpacing = { 0, 0 }; #if ENABLED(AUTO_BED_LEVELING_LINEAR) - ABL_VAR uint8_t abl_grid_points_x = GRID_MAX_POINTS_X, - abl_grid_points_y = GRID_MAX_POINTS_Y; ABL_VAR bool do_topography_map; + ABL_VAR xy_uint8_t abl_grid_points; #else // Bilinear - uint8_t constexpr abl_grid_points_x = GRID_MAX_POINTS_X, - abl_grid_points_y = GRID_MAX_POINTS_Y; + constexpr xy_uint8_t abl_grid_points = { GRID_MAX_POINTS_X, GRID_MAX_POINTS_Y }; #endif #if ENABLED(AUTO_BED_LEVELING_LINEAR) @@ -269,15 +267,15 @@ G29_TYPE GcodeSuite::G29() { const float x_min = probe_min_x(), x_max = probe_max_x(), y_min = probe_min_y(), y_max = probe_max_y(); ABL_VAR vector_3 points[3] = { - #if ENABLED(HAS_FIXED_3POINT) - vector_3(PROBE_PT_1_X, PROBE_PT_1_Y, 0), - vector_3(PROBE_PT_2_X, PROBE_PT_2_Y, 0), - vector_3(PROBE_PT_3_X, PROBE_PT_3_Y, 0) - #else - vector_3(x_min, y_min, 0), - vector_3(x_max, y_min, 0), - vector_3((x_max - x_min) / 2, y_max, 0) - #endif + #if ENABLED(HAS_FIXED_3POINT) + { PROBE_PT_1_X, PROBE_PT_1_Y, 0 }, + { PROBE_PT_2_X, PROBE_PT_2_Y, 0 }, + { PROBE_PT_3_X, PROBE_PT_3_Y, 0 } + #else + { x_min, y_min, 0 }, + { x_max, y_min, 0 }, + { (x_max - x_min) / 2, y_max, 0 } + #endif }; #endif // AUTO_BED_LEVELING_3POINT @@ -311,7 +309,7 @@ G29_TYPE GcodeSuite::G29() { G29_RETURN(false); } - const float rz = parser.seenval('Z') ? RAW_Z_POSITION(parser.value_linear_units()) : current_position[Z_AXIS]; + const float rz = parser.seenval('Z') ? RAW_Z_POSITION(parser.value_linear_units()) : current_position.z; if (!WITHIN(rz, -10, 10)) { SERIAL_ERROR_MSG("Bad Z value"); G29_RETURN(false); @@ -323,8 +321,8 @@ G29_TYPE GcodeSuite::G29() { if (!isnan(rx) && !isnan(ry)) { // Get nearest i / j from rx / ry - i = (rx - bilinear_start[X_AXIS] + 0.5 * xGridSpacing) / xGridSpacing; - j = (ry - bilinear_start[Y_AXIS] + 0.5 * yGridSpacing) / yGridSpacing; + i = (rx - bilinear_start.x + 0.5 * gridSpacing.x) / gridSpacing.x; + j = (ry - bilinear_start.y + 0.5 * gridSpacing.y) / gridSpacing.y; LIMIT(i, 0, GRID_MAX_POINTS_X - 1); LIMIT(j, 0, GRID_MAX_POINTS_Y - 1); } @@ -373,20 +371,22 @@ G29_TYPE GcodeSuite::G29() { // X and Y specify points in each direction, overriding the default // These values may be saved with the completed mesh - abl_grid_points_x = parser.intval('X', GRID_MAX_POINTS_X); - abl_grid_points_y = parser.intval('Y', GRID_MAX_POINTS_Y); - if (parser.seenval('P')) abl_grid_points_x = abl_grid_points_y = parser.value_int(); + abl_grid_points.set( + parser.byteval('X', GRID_MAX_POINTS_X), + parser.byteval('Y', GRID_MAX_POINTS_Y) + ); + if (parser.seenval('P')) abl_grid_points.x = abl_grid_points.y = parser.value_int(); - if (!WITHIN(abl_grid_points_x, 2, GRID_MAX_POINTS_X)) { + if (!WITHIN(abl_grid_points.x, 2, GRID_MAX_POINTS_X)) { SERIAL_ECHOLNPGM("?Probe points (X) implausible (2-" STRINGIFY(GRID_MAX_POINTS_X) ")."); G29_RETURN(false); } - if (!WITHIN(abl_grid_points_y, 2, GRID_MAX_POINTS_Y)) { + if (!WITHIN(abl_grid_points.y, 2, GRID_MAX_POINTS_Y)) { SERIAL_ECHOLNPGM("?Probe points (Y) implausible (2-" STRINGIFY(GRID_MAX_POINTS_Y) ")."); G29_RETURN(false); } - abl_points = abl_grid_points_x * abl_grid_points_y; + abl_points = abl_grid_points.x * abl_grid_points.y; mean = 0; #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) @@ -404,27 +404,35 @@ G29_TYPE GcodeSuite::G29() { if (parser.seen('H')) { const int16_t size = (int16_t)parser.value_linear_units(); - left_probe_bed_position = _MAX(X_CENTER - size / 2, x_min); - right_probe_bed_position = _MIN(left_probe_bed_position + size, x_max); - front_probe_bed_position = _MAX(Y_CENTER - size / 2, y_min); - back_probe_bed_position = _MIN(front_probe_bed_position + size, y_max); + probe_position_lf.set( + _MAX(X_CENTER - size / 2, x_min), + _MAX(Y_CENTER - size / 2, y_min) + ); + probe_position_rb.set( + _MIN(probe_position_lf.x + size, x_max), + _MIN(probe_position_lf.y + size, y_max) + ); } else { - left_probe_bed_position = parser.seenval('L') ? (int)RAW_X_POSITION(parser.value_linear_units()) : _MAX(X_CENTER - X_BED_SIZE / 2, x_min); - right_probe_bed_position = parser.seenval('R') ? (int)RAW_X_POSITION(parser.value_linear_units()) : _MIN(left_probe_bed_position + X_BED_SIZE, x_max); - front_probe_bed_position = parser.seenval('F') ? (int)RAW_Y_POSITION(parser.value_linear_units()) : _MAX(Y_CENTER - Y_BED_SIZE / 2, y_min); - back_probe_bed_position = parser.seenval('B') ? (int)RAW_Y_POSITION(parser.value_linear_units()) : _MIN(front_probe_bed_position + Y_BED_SIZE, y_max); + probe_position_lf.set( + parser.seenval('L') ? (int)RAW_X_POSITION(parser.value_linear_units()) : _MAX(X_CENTER - (X_BED_SIZE) / 2, x_min), + parser.seenval('F') ? (int)RAW_Y_POSITION(parser.value_linear_units()) : _MAX(Y_CENTER - (Y_BED_SIZE) / 2, y_min) + ); + probe_position_rb.set( + parser.seenval('R') ? (int)RAW_X_POSITION(parser.value_linear_units()) : _MIN(probe_position_lf.x + X_BED_SIZE, x_max), + parser.seenval('B') ? (int)RAW_Y_POSITION(parser.value_linear_units()) : _MIN(probe_position_lf.y + Y_BED_SIZE, y_max) + ); } if ( #if IS_SCARA || ENABLED(DELTA) - !position_is_reachable_by_probe(left_probe_bed_position, 0) - || !position_is_reachable_by_probe(right_probe_bed_position, 0) - || !position_is_reachable_by_probe(0, front_probe_bed_position) - || !position_is_reachable_by_probe(0, back_probe_bed_position) + !position_is_reachable_by_probe(probe_position_lf.x, 0) + || !position_is_reachable_by_probe(probe_position_rb.x, 0) + || !position_is_reachable_by_probe(0, probe_position_lf.y) + || !position_is_reachable_by_probe(0, probe_position_rb.y) #else - !position_is_reachable_by_probe(left_probe_bed_position, front_probe_bed_position) - || !position_is_reachable_by_probe(right_probe_bed_position, back_probe_bed_position) + !position_is_reachable_by_probe(probe_position_lf) + || !position_is_reachable_by_probe(probe_position_rb) #endif ) { SERIAL_ECHOLNPGM("? (L,R,F,B) out of bounds."); @@ -432,8 +440,8 @@ G29_TYPE GcodeSuite::G29() { } // probe at the points of a lattice grid - xGridSpacing = (right_probe_bed_position - left_probe_bed_position) / (abl_grid_points_x - 1); - yGridSpacing = (back_probe_bed_position - front_probe_bed_position) / (abl_grid_points_y - 1); + gridSpacing.set((probe_position_rb.x - probe_position_lf.x) / (abl_grid_points.x - 1), + (probe_position_rb.y - probe_position_lf.y) / (abl_grid_points.y - 1)); #endif // ABL_GRID @@ -464,19 +472,13 @@ G29_TYPE GcodeSuite::G29() { #if ENABLED(PROBE_MANUALLY) if (!no_action) #endif - if ( xGridSpacing != bilinear_grid_spacing[X_AXIS] - || yGridSpacing != bilinear_grid_spacing[Y_AXIS] - || left_probe_bed_position != bilinear_start[X_AXIS] - || front_probe_bed_position != bilinear_start[Y_AXIS] - ) { + if (gridSpacing != bilinear_grid_spacing || probe_position_lf != bilinear_start) { // Reset grid to 0.0 or "not probed". (Also disables ABL) reset_bed_level(); // Initialize a grid with the given dimensions - bilinear_grid_spacing[X_AXIS] = xGridSpacing; - bilinear_grid_spacing[Y_AXIS] = yGridSpacing; - bilinear_start[X_AXIS] = left_probe_bed_position; - bilinear_start[Y_AXIS] = front_probe_bed_position; + bilinear_grid_spacing = gridSpacing.asInt(); + bilinear_start = probe_position_lf; // Can't re-enable (on error) until the new grid is written abl_should_enable = false; @@ -546,17 +548,17 @@ G29_TYPE GcodeSuite::G29() { // For G29 after adjusting Z. // Save the previous Z before going to the next point - measured_z = current_position[Z_AXIS]; + measured_z = current_position.z; #if ENABLED(AUTO_BED_LEVELING_LINEAR) mean += measured_z; eqnBVector[index] = measured_z; - eqnAMatrix[index + 0 * abl_points] = xProbe; - eqnAMatrix[index + 1 * abl_points] = yProbe; + eqnAMatrix[index + 0 * abl_points] = probePos.x; + eqnAMatrix[index + 1 * abl_points] = probePos.y; eqnAMatrix[index + 2 * abl_points] = 1; - incremental_LSF(&lsf_results, xProbe, yProbe, measured_z); + incremental_LSF(&lsf_results, probePos, measured_z); #elif ENABLED(AUTO_BED_LEVELING_3POINT) @@ -564,12 +566,13 @@ G29_TYPE GcodeSuite::G29() { #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) - z_values[xCount][yCount] = measured_z + zoffset; + const float newz = measured_z + zoffset; + z_values[meshCount.x][meshCount.y] = newz; #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(xCount, yCount, z_values[xCount][yCount]); + ExtUI::onMeshUpdate(meshCount, newz); #endif - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Save X", xCount, " Y", yCount, " Z", measured_z + zoffset); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Save X", meshCount.x, " Y", meshCount.y, " Z", measured_z + zoffset); #endif } @@ -583,7 +586,7 @@ G29_TYPE GcodeSuite::G29() { // Skip any unreachable points while (abl_probe_index < abl_points) { - // Set xCount, yCount based on abl_probe_index, with zig-zag + // Set meshCount.x, meshCount.y based on abl_probe_index, with zig-zag PR_OUTER_VAR = abl_probe_index / PR_INNER_END; PR_INNER_VAR = abl_probe_index - (PR_OUTER_VAR * PR_INNER_END); @@ -592,24 +595,23 @@ G29_TYPE GcodeSuite::G29() { if (zig) PR_INNER_VAR = (PR_INNER_END - 1) - PR_INNER_VAR; - const float xBase = xCount * xGridSpacing + left_probe_bed_position, - yBase = yCount * yGridSpacing + front_probe_bed_position; + const xy_pos_t base = probe_position_lf.asFloat() + gridSpacing * meshCount.asFloat(); - xProbe = FLOOR(xBase + (xBase < 0 ? 0 : 0.5)); - yProbe = FLOOR(yBase + (yBase < 0 ? 0 : 0.5)); + probePos.set(FLOOR(base.x + (base.x < 0 ? 0 : 0.5)), + FLOOR(base.y + (base.y < 0 ? 0 : 0.5))); #if ENABLED(AUTO_BED_LEVELING_LINEAR) - indexIntoAB[xCount][yCount] = abl_probe_index; + indexIntoAB[meshCount.x][meshCount.y] = abl_probe_index; #endif // Keep looping till a reachable point is found - if (position_is_reachable(xProbe, yProbe)) break; + if (position_is_reachable(probePos)) break; ++abl_probe_index; } // Is there a next point to move to? if (abl_probe_index < abl_points) { - _manual_goto_xy(xProbe, yProbe); // Can be used here too! + _manual_goto_xy(probePos); // Can be used here too! #if HAS_SOFTWARE_ENDSTOPS // Disable software endstops to allow manual adjustment // If G29 is not completed, they will not be re-enabled @@ -633,9 +635,8 @@ G29_TYPE GcodeSuite::G29() { // Probe at 3 arbitrary points if (abl_probe_index < abl_points) { - xProbe = points[abl_probe_index].x; - yProbe = points[abl_probe_index].y; - _manual_goto_xy(xProbe, yProbe); + probePos = points[abl_probe_index]; + _manual_goto_xy(probePos); #if HAS_SOFTWARE_ENDSTOPS // Disable software endstops to allow manual adjustment // If G29 is not completed, they will not be re-enabled @@ -654,11 +655,7 @@ G29_TYPE GcodeSuite::G29() { if (!dryrun) { vector_3 planeNormal = vector_3::cross(points[0] - points[1], points[2] - points[1]).get_normal(); - if (planeNormal.z < 0) { - planeNormal.x *= -1; - planeNormal.y *= -1; - planeNormal.z *= -1; - } + if (planeNormal.z < 0) planeNormal *= -1; planner.bed_level_matrix = matrix_3x3::create_look_at(planeNormal); // Can't re-enable (on error) until the new grid is written @@ -681,8 +678,11 @@ G29_TYPE GcodeSuite::G29() { measured_z = 0; + xy_int8_t meshCount; + + // Outer loop is X with PROBE_Y_FIRST enabled // Outer loop is Y with PROBE_Y_FIRST disabled - for (uint8_t PR_OUTER_VAR = 0; PR_OUTER_VAR < PR_OUTER_END && !isnan(measured_z); PR_OUTER_VAR++) { + for (PR_OUTER_VAR = 0; PR_OUTER_VAR < PR_OUTER_END && !isnan(measured_z); PR_OUTER_VAR++) { int8_t inStart, inStop, inInc; @@ -703,21 +703,21 @@ G29_TYPE GcodeSuite::G29() { uint8_t pt_index = (PR_OUTER_VAR) * (PR_INNER_END) + 1; // Inner loop is Y with PROBE_Y_FIRST enabled - for (int8_t PR_INNER_VAR = inStart; PR_INNER_VAR != inStop; pt_index++, PR_INNER_VAR += inInc) { + // Inner loop is X with PROBE_Y_FIRST disabled + for (PR_INNER_VAR = inStart; PR_INNER_VAR != inStop; pt_index++, PR_INNER_VAR += inInc) { - const float xBase = left_probe_bed_position + xGridSpacing * xCount, - yBase = front_probe_bed_position + yGridSpacing * yCount; + const xy_pos_t base = probe_position_lf.asFloat() + gridSpacing * meshCount.asFloat(); - xProbe = FLOOR(xBase + (xBase < 0 ? 0 : 0.5)); - yProbe = FLOOR(yBase + (yBase < 0 ? 0 : 0.5)); + probePos.set(FLOOR(base.x + (base.x < 0 ? 0 : 0.5)), + FLOOR(base.y + (base.y < 0 ? 0 : 0.5))); #if ENABLED(AUTO_BED_LEVELING_LINEAR) - indexIntoAB[xCount][yCount] = ++abl_probe_index; // 0... + indexIntoAB[meshCount.x][meshCount.y] = ++abl_probe_index; // 0... #endif #if IS_KINEMATIC // Avoid probing outside the round or hexagonal area - if (!position_is_reachable_by_probe(xProbe, yProbe)) continue; + if (!position_is_reachable_by_probe(probePos)) continue; #endif if (verbose_level) SERIAL_ECHOLNPAIR("Probing mesh point ", int(pt_index), "/", int(GRID_MAX_POINTS), "."); @@ -725,7 +725,7 @@ G29_TYPE GcodeSuite::G29() { ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), PSTR(MSG_PROBING_MESH), int(pt_index), int(GRID_MAX_POINTS)); #endif - measured_z = faux ? 0.001 * random(-100, 101) : probe_at_point(xProbe, yProbe, raise_after, verbose_level); + measured_z = faux ? 0.001 * random(-100, 101) : probe_at_point(probePos, raise_after, verbose_level); if (isnan(measured_z)) { set_bed_leveling_enabled(abl_should_enable); @@ -736,17 +736,17 @@ G29_TYPE GcodeSuite::G29() { mean += measured_z; eqnBVector[abl_probe_index] = measured_z; - eqnAMatrix[abl_probe_index + 0 * abl_points] = xProbe; - eqnAMatrix[abl_probe_index + 1 * abl_points] = yProbe; + eqnAMatrix[abl_probe_index + 0 * abl_points] = probePos.x; + eqnAMatrix[abl_probe_index + 1 * abl_points] = probePos.y; eqnAMatrix[abl_probe_index + 2 * abl_points] = 1; - incremental_LSF(&lsf_results, xProbe, yProbe, measured_z); + incremental_LSF(&lsf_results, probePos, measured_z); #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) - z_values[xCount][yCount] = measured_z + zoffset; + z_values[meshCount.x][meshCount.y] = measured_z + zoffset; #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(xCount, yCount, z_values[xCount][yCount]); + ExtUI::onMeshUpdate(meshCount.x, meshCount.y, z_values[meshCount.x][meshCount.y]); #endif #endif @@ -768,9 +768,8 @@ G29_TYPE GcodeSuite::G29() { #endif // Retain the last probe position - xProbe = points[i].x; - yProbe = points[i].y; - measured_z = faux ? 0.001 * random(-100, 101) : probe_at_point(xProbe, yProbe, raise_after, verbose_level); + probePos = points[i]; + measured_z = faux ? 0.001 * random(-100, 101) : probe_at_point(probePos, raise_after, verbose_level); if (isnan(measured_z)) { set_bed_leveling_enabled(abl_should_enable); break; @@ -845,19 +844,19 @@ G29_TYPE GcodeSuite::G29() { * plane equation in the standard form, which is Vx*x+Vy*y+Vz*z+d = 0 * so Vx = -a Vy = -b Vz = 1 (we want the vector facing towards positive Z */ - float plane_equation_coefficients[3]; + struct { float a, b, d; } plane_equation_coefficients; finish_incremental_LSF(&lsf_results); - plane_equation_coefficients[0] = -lsf_results.A; // We should be able to eliminate the '-' on these three lines and down below - plane_equation_coefficients[1] = -lsf_results.B; // but that is not yet tested. - plane_equation_coefficients[2] = -lsf_results.D; + plane_equation_coefficients.a = -lsf_results.A; // We should be able to eliminate the '-' on these three lines and down below + plane_equation_coefficients.b = -lsf_results.B; // but that is not yet tested. + plane_equation_coefficients.d = -lsf_results.D; mean /= abl_points; if (verbose_level) { - SERIAL_ECHOPAIR_F("Eqn coefficients: a: ", plane_equation_coefficients[0], 8); - SERIAL_ECHOPAIR_F(" b: ", plane_equation_coefficients[1], 8); - SERIAL_ECHOPAIR_F(" d: ", plane_equation_coefficients[2], 8); + SERIAL_ECHOPAIR_F("Eqn coefficients: a: ", plane_equation_coefficients.a, 8); + SERIAL_ECHOPAIR_F(" b: ", plane_equation_coefficients.b, 8); + SERIAL_ECHOPAIR_F(" d: ", plane_equation_coefficients.d, 8); if (verbose_level > 2) SERIAL_ECHOPAIR_F("\nMean of sampled points: ", mean, 8); SERIAL_EOL(); @@ -866,13 +865,34 @@ G29_TYPE GcodeSuite::G29() { // Create the matrix but don't correct the position yet if (!dryrun) planner.bed_level_matrix = matrix_3x3::create_look_at( - vector_3(-plane_equation_coefficients[0], -plane_equation_coefficients[1], 1) // We can eliminate the '-' here and up above + vector_3(-plane_equation_coefficients.a, -plane_equation_coefficients.b, 1) // We can eliminate the '-' here and up above ); // Show the Topography map if enabled if (do_topography_map) { - SERIAL_ECHOLNPGM("\nBed Height Topography:\n" + float min_diff = 999; + + auto print_topo_map = [&](PGM_P const title, const bool get_min) { + serialprintPGM(title); + for (int8_t yy = abl_grid_points.y - 1; yy >= 0; yy--) { + for (uint8_t xx = 0; xx < abl_grid_points.x; xx++) { + const int ind = indexIntoAB[xx][yy]; + xyz_float_t tmp = { eqnAMatrix[ind + 0 * abl_points], + eqnAMatrix[ind + 1 * abl_points], 0 }; + apply_rotation_xyz(planner.bed_level_matrix, tmp); + if (get_min) NOMORE(min_diff, eqnBVector[ind] - tmp.z); + const float subval = get_min ? mean : tmp.z + min_diff, + diff = eqnBVector[ind] - subval; + SERIAL_CHAR(' '); if (diff >= 0.0) SERIAL_CHAR('+'); // Include + for column alignment + SERIAL_ECHO_F(diff, 5); + } // xx + SERIAL_EOL(); + } // yy + SERIAL_EOL(); + }; + + print_topo_map(PSTR("\nBed Height Topography:\n" " +--- BACK --+\n" " | |\n" " L | (+) | R\n" @@ -882,56 +902,10 @@ G29_TYPE GcodeSuite::G29() { " | (-) | T\n" " | |\n" " O-- FRONT --+\n" - " (0,0)"); + " (0,0)\n"), true); + if (verbose_level > 3) + print_topo_map(PSTR("\nCorrected Bed Height vs. Bed Topology:\n"), false); - float min_diff = 999; - - for (int8_t yy = abl_grid_points_y - 1; yy >= 0; yy--) { - for (uint8_t xx = 0; xx < abl_grid_points_x; xx++) { - int ind = indexIntoAB[xx][yy]; - float diff = eqnBVector[ind] - mean, - x_tmp = eqnAMatrix[ind + 0 * abl_points], - y_tmp = eqnAMatrix[ind + 1 * abl_points], - z_tmp = 0; - - apply_rotation_xyz(planner.bed_level_matrix, x_tmp, y_tmp, z_tmp); - - NOMORE(min_diff, eqnBVector[ind] - z_tmp); - - if (diff >= 0.0) - SERIAL_ECHOPGM(" +"); // Include + for column alignment - else - SERIAL_CHAR(' '); - SERIAL_ECHO_F(diff, 5); - } // xx - SERIAL_EOL(); - } // yy - SERIAL_EOL(); - - if (verbose_level > 3) { - SERIAL_ECHOLNPGM("\nCorrected Bed Height vs. Bed Topology:"); - - for (int8_t yy = abl_grid_points_y - 1; yy >= 0; yy--) { - for (uint8_t xx = 0; xx < abl_grid_points_x; xx++) { - int ind = indexIntoAB[xx][yy]; - float x_tmp = eqnAMatrix[ind + 0 * abl_points], - y_tmp = eqnAMatrix[ind + 1 * abl_points], - z_tmp = 0; - - apply_rotation_xyz(planner.bed_level_matrix, x_tmp, y_tmp, z_tmp); - - float diff = eqnBVector[ind] - z_tmp - min_diff; - if (diff >= 0.0) - SERIAL_ECHOPGM(" +"); - // Include + for column alignment - else - SERIAL_CHAR(' '); - SERIAL_ECHO_F(diff, 5); - } // xx - SERIAL_EOL(); - } // yy - SERIAL_EOL(); - } } //do_topography_map #endif // AUTO_BED_LEVELING_LINEAR @@ -950,24 +924,20 @@ G29_TYPE GcodeSuite::G29() { if (DEBUGGING(LEVELING)) DEBUG_POS("G29 uncorrected XYZ", current_position); - float converted[XYZ]; - COPY(converted, current_position); - - planner.leveling_active = true; - planner.unapply_leveling(converted); // use conversion machinery - planner.leveling_active = false; + xyze_pos_t converted = current_position; + planner.force_unapply_leveling(converted); // use conversion machinery // Use the last measured distance to the bed, if possible - if ( NEAR(current_position[X_AXIS], xProbe - probe_offset[X_AXIS]) - && NEAR(current_position[Y_AXIS], yProbe - probe_offset[Y_AXIS]) + if ( NEAR(current_position.x, probePos.x - probe_offset.x) + && NEAR(current_position.y, probePos.y - probe_offset.y) ) { - const float simple_z = current_position[Z_AXIS] - measured_z; - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Probed Z", simple_z, " Matrix Z", converted[Z_AXIS], " Discrepancy ", simple_z - converted[Z_AXIS]); - converted[Z_AXIS] = simple_z; + const float simple_z = current_position.z - measured_z; + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Probed Z", simple_z, " Matrix Z", converted.z, " Discrepancy ", simple_z - converted.z); + converted.z = simple_z; } // The rotated XY and corrected Z are now current_position - COPY(current_position, converted); + current_position = converted; if (DEBUGGING(LEVELING)) DEBUG_POS("G29 corrected XYZ", current_position); } @@ -975,13 +945,13 @@ G29_TYPE GcodeSuite::G29() { #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) if (!dryrun) { - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("G29 uncorrected Z:", current_position[Z_AXIS]); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("G29 uncorrected Z:", current_position.z); // Unapply the offset because it is going to be immediately applied // and cause compensation movement in Z - current_position[Z_AXIS] -= bilinear_z_offset(current_position); + current_position.z -= bilinear_z_offset(current_position); - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(" corrected Z:", current_position[Z_AXIS]); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(" corrected Z:", current_position.z); } #endif // ABL_PLANAR diff --git a/Marlin/src/gcode/bedlevel/mbl/G29.cpp b/Marlin/src/gcode/bedlevel/mbl/G29.cpp index eee542a6f..944e8d3a6 100644 --- a/Marlin/src/gcode/bedlevel/mbl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/mbl/G29.cpp @@ -110,7 +110,7 @@ void GcodeSuite::G29() { } else { // Save Z for the previous mesh position - mbl.set_zigzag_z(mbl_probe_index - 1, current_position[Z_AXIS]); + mbl.set_zigzag_z(mbl_probe_index - 1, current_position.z); #if HAS_SOFTWARE_ENDSTOPS soft_endstops_enabled = saved_soft_endstops_state; #endif @@ -124,11 +124,11 @@ void GcodeSuite::G29() { #endif mbl.zigzag(mbl_probe_index++, ix, iy); - _manual_goto_xy(mbl.index_to_xpos[ix], mbl.index_to_ypos[iy]); + _manual_goto_xy({ mbl.index_to_xpos[ix], mbl.index_to_ypos[iy] }); } else { // One last "return to the bed" (as originally coded) at completion - current_position[Z_AXIS] = MANUAL_PROBE_HEIGHT; + current_position.z = MANUAL_PROBE_HEIGHT; line_to_current_position(); planner.synchronize(); @@ -142,7 +142,7 @@ void GcodeSuite::G29() { set_bed_leveling_enabled(true); #if ENABLED(MESH_G28_REST_ORIGIN) - current_position[Z_AXIS] = 0; + current_position.z = 0; line_to_current_position(homing_feedrate(Z_AXIS)); planner.synchronize(); #endif diff --git a/Marlin/src/gcode/bedlevel/ubl/M421.cpp b/Marlin/src/gcode/bedlevel/ubl/M421.cpp index 34afe7862..153e6018a 100644 --- a/Marlin/src/gcode/bedlevel/ubl/M421.cpp +++ b/Marlin/src/gcode/bedlevel/ubl/M421.cpp @@ -46,28 +46,25 @@ * M421 C Q */ void GcodeSuite::M421() { - int8_t ix = parser.intval('I', -1), iy = parser.intval('J', -1); - const bool hasI = ix >= 0, - hasJ = iy >= 0, + xy_int8_t ij = { int8_t(parser.intval('I', -1)), int8_t(parser.intval('J', -1)) }; + const bool hasI = ij.x >= 0, + hasJ = ij.y >= 0, hasC = parser.seen('C'), hasN = parser.seen('N'), hasZ = parser.seen('Z'), hasQ = !hasZ && parser.seen('Q'); - if (hasC) { - const mesh_index_pair location = ubl.find_closest_mesh_point_of_type(REAL, current_position[X_AXIS], current_position[Y_AXIS], USE_NOZZLE_AS_REFERENCE, nullptr); - ix = location.x_index; - iy = location.y_index; - } + if (hasC) ij = ubl.find_closest_mesh_point_of_type(REAL, current_position); if (int(hasC) + int(hasI && hasJ) != 1 || !(hasZ || hasQ || hasN)) SERIAL_ERROR_MSG(MSG_ERR_M421_PARAMETERS); - else if (!WITHIN(ix, 0, GRID_MAX_POINTS_X - 1) || !WITHIN(iy, 0, GRID_MAX_POINTS_Y - 1)) + else if (!WITHIN(ij.x, 0, GRID_MAX_POINTS_X - 1) || !WITHIN(ij.y, 0, GRID_MAX_POINTS_Y - 1)) SERIAL_ERROR_MSG(MSG_ERR_MESH_XY); else { - ubl.z_values[ix][iy] = hasN ? NAN : parser.value_linear_units() + (hasQ ? ubl.z_values[ix][iy] : 0); + float &zval = ubl.z_values[ij.x][ij.y]; + zval = hasN ? NAN : parser.value_linear_units() + (hasQ ? zval : 0); #if ENABLED(EXTENSIBLE_UI) - ExtUI::onMeshUpdate(ix, iy, ubl.z_values[ix][iy]); + ExtUI::onMeshUpdate(ij.x, ij.y, zval); #endif } } diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index 514bb6589..6fda4e84d 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -59,7 +59,7 @@ static void quick_home_xy() { // Pretend the current position is 0,0 - current_position[X_AXIS] = current_position[Y_AXIS] = 0.0; + current_position.set(0.0, 0.0); sync_plan_position(); const int x_axis_home_dir = @@ -95,7 +95,7 @@ endstops.validate_homing_move(); - current_position[X_AXIS] = current_position[Y_AXIS] = 0.0; + current_position.set(0.0, 0.0); #if ENABLED(SENSORLESS_HOMING) tmc_disable_stallguard(stepperX, stealth_states.x); @@ -128,17 +128,15 @@ /** * Move the Z probe (or just the nozzle) to the safe homing point + * (Z is already at the right height) */ - destination[X_AXIS] = Z_SAFE_HOMING_X_POINT; - destination[Y_AXIS] = Z_SAFE_HOMING_Y_POINT; - destination[Z_AXIS] = current_position[Z_AXIS]; // Z is already at the right height + destination.set(safe_homing_xy, current_position.z); #if HOMING_Z_WITH_PROBE - destination[X_AXIS] -= probe_offset[X_AXIS]; - destination[Y_AXIS] -= probe_offset[Y_AXIS]; + destination -= probe_offset; #endif - if (position_is_reachable(destination[X_AXIS], destination[Y_AXIS])) { + if (position_is_reachable(destination)) { if (DEBUGGING(LEVELING)) DEBUG_POS("home_z_safely", destination); @@ -151,7 +149,7 @@ safe_delay(500); // Short delay needed to settle #endif - do_blocking_move_to_xy(destination[X_AXIS], destination[Y_AXIS]); + do_blocking_move_to_xy(destination); homeaxis(Z_AXIS); } else { @@ -232,16 +230,14 @@ void GcodeSuite::G28(const bool always_home_all) { #endif #if ENABLED(IMPROVE_HOMING_RELIABILITY) - slow_homing_t slow_homing { 0 }; - slow_homing.acceleration.x = planner.settings.max_acceleration_mm_per_s2[X_AXIS]; - slow_homing.acceleration.y = planner.settings.max_acceleration_mm_per_s2[Y_AXIS]; + slow_homing_t slow_homing{0}; + slow_homing.acceleration.set(planner.settings.max_acceleration_mm_per_s2[X_AXIS]; + planner.settings.max_acceleration_mm_per_s2[Y_AXIS]); planner.settings.max_acceleration_mm_per_s2[X_AXIS] = 100; planner.settings.max_acceleration_mm_per_s2[Y_AXIS] = 100; #if HAS_CLASSIC_JERK - slow_homing.jerk.x = planner.max_jerk[X_AXIS]; - slow_homing.jerk.y = planner.max_jerk[Y_AXIS]; - planner.max_jerk[X_AXIS] = 0; - planner.max_jerk[Y_AXIS] = 0; + slow_homing.jerk_xy = planner.max_jerk; + planner.max_jerk.set(0, 0); #endif planner.reset_acceleration_rates(); @@ -274,7 +270,7 @@ void GcodeSuite::G28(const bool always_home_all) { home_all = always_home_all || (homeX == homeY && homeX == homeZ), doX = home_all || homeX, doY = home_all || homeY, doZ = home_all || homeZ; - set_destination_from_current(); + destination = current_position; #if Z_HOME_DIR > 0 // If homing away from BED do Z first @@ -291,10 +287,10 @@ void GcodeSuite::G28(const bool always_home_all) { if (z_homing_height && (doX || doY)) { // Raise Z before homing any other axes and z is not already high enough (never lower z) - destination[Z_AXIS] = z_homing_height; - if (destination[Z_AXIS] > current_position[Z_AXIS]) { - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Raise Z (before homing) to ", destination[Z_AXIS]); - do_blocking_move_to_z(destination[Z_AXIS]); + destination.z = z_homing_height; + if (destination.z > current_position.z) { + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Raise Z (before homing) to ", destination.z); + do_blocking_move_to_z(destination.z); } } @@ -329,14 +325,14 @@ void GcodeSuite::G28(const bool always_home_all) { homeaxis(X_AXIS); // Remember this extruder's position for later tool change - inactive_extruder_x_pos = current_position[X_AXIS]; + inactive_extruder_x_pos = current_position.x; // Home the 1st (left) extruder active_extruder = 0; homeaxis(X_AXIS); // Consider the active extruder to be parked - COPY(raised_parked_position, current_position); + raised_parked_position = current_position; delayed_move_time = 0; active_extruder_parked = true; @@ -390,14 +386,14 @@ void GcodeSuite::G28(const bool always_home_all) { homeaxis(X_AXIS); // Remember this extruder's position for later tool change - inactive_extruder_x_pos = current_position[X_AXIS]; + inactive_extruder_x_pos = current_position.x; // Home the 1st (left) extruder active_extruder = 0; homeaxis(X_AXIS); // Consider the active extruder to be parked - COPY(raised_parked_position, current_position); + raised_parked_position = current_position; delayed_move_time = 0; active_extruder_parked = true; extruder_duplication_enabled = IDEX_saved_duplication_state; @@ -441,10 +437,8 @@ void GcodeSuite::G28(const bool always_home_all) { planner.settings.max_acceleration_mm_per_s2[X_AXIS] = slow_homing.acceleration.x; planner.settings.max_acceleration_mm_per_s2[Y_AXIS] = slow_homing.acceleration.y; #if HAS_CLASSIC_JERK - planner.max_jerk[X_AXIS] = slow_homing.jerk.x; - planner.max_jerk[Y_AXIS] = slow_homing.jerk.y; + planner.max_jerk = slow_homing.jerk_xy; #endif - planner.reset_acceleration_rates(); #endif diff --git a/Marlin/src/gcode/calibrate/G33.cpp b/Marlin/src/gcode/calibrate/G33.cpp index 1e3e84a1e..f961302fb 100644 --- a/Marlin/src/gcode/calibrate/G33.cpp +++ b/Marlin/src/gcode/calibrate/G33.cpp @@ -70,7 +70,7 @@ enum CalEnum : char { // the 7 main calibration points - #define AC_CLEANUP() ac_cleanup() #endif -float lcd_probe_pt(const float &rx, const float &ry); +float lcd_probe_pt(const xy_pos_t &xy); void ac_home() { endstops.enable(true); @@ -122,9 +122,9 @@ void print_signed_float(PGM_P const prefix, const float &f) { static void print_calibration_settings(const bool end_stops, const bool tower_angles) { SERIAL_ECHOPAIR(".Height:", delta_height); if (end_stops) { - print_signed_float(PSTR("Ex"), delta_endstop_adj[A_AXIS]); - print_signed_float(PSTR("Ey"), delta_endstop_adj[B_AXIS]); - print_signed_float(PSTR("Ez"), delta_endstop_adj[C_AXIS]); + print_signed_float(PSTR("Ex"), delta_endstop_adj.a); + print_signed_float(PSTR("Ey"), delta_endstop_adj.b); + print_signed_float(PSTR("Ez"), delta_endstop_adj.c); } if (end_stops && tower_angles) { SERIAL_ECHOPAIR(" Radius:", delta_radius); @@ -133,9 +133,9 @@ static void print_calibration_settings(const bool end_stops, const bool tower_an SERIAL_ECHO_SP(13); } if (tower_angles) { - print_signed_float(PSTR("Tx"), delta_tower_angle_trim[A_AXIS]); - print_signed_float(PSTR("Ty"), delta_tower_angle_trim[B_AXIS]); - print_signed_float(PSTR("Tz"), delta_tower_angle_trim[C_AXIS]); + print_signed_float(PSTR("Tx"), delta_tower_angle_trim.a); + print_signed_float(PSTR("Ty"), delta_tower_angle_trim.b); + print_signed_float(PSTR("Tz"), delta_tower_angle_trim.c); } if ((!end_stops && tower_angles) || (end_stops && !tower_angles)) { // XOR SERIAL_ECHOPAIR(" Radius:", delta_radius); @@ -188,12 +188,12 @@ static float std_dev_points(float z_pt[NPP + 1], const bool _0p_cal, const bool /** * - Probe a point */ -static float calibration_probe(const float &nx, const float &ny, const bool stow) { +static float calibration_probe(const xy_pos_t &xy, const bool stow) { #if HAS_BED_PROBE - return probe_at_point(nx, ny, stow ? PROBE_PT_STOW : PROBE_PT_RAISE, 0, false); + return probe_at_point(xy, stow ? PROBE_PT_STOW : PROBE_PT_RAISE, 0, false); #else UNUSED(stow); - return lcd_probe_pt(nx, ny); + return lcd_probe_pt(xy); #endif } @@ -223,7 +223,8 @@ static bool probe_calibration_points(float z_pt[NPP + 1], const int8_t probe_poi if (!_0p_calibration) { if (!_7p_no_intermediates && !_7p_4_intermediates && !_7p_11_intermediates) { // probe the center - z_pt[CEN] += calibration_probe(0, 0, stow_after_each); + const xy_pos_t center{0}; + z_pt[CEN] += calibration_probe(center, stow_after_each); if (isnan(z_pt[CEN])) return false; } @@ -233,7 +234,8 @@ static bool probe_calibration_points(float z_pt[NPP + 1], const int8_t probe_poi I_LOOP_CAL_PT(rad, start, steps) { const float a = RADIANS(210 + (360 / NPP) * (rad - 1)), r = delta_calibration_radius * 0.1; - z_pt[CEN] += calibration_probe(cos(a) * r, sin(a) * r, stow_after_each); + const xy_pos_t vec = { cos(a), sin(a) }; + z_pt[CEN] += calibration_probe(vec * r, stow_after_each); if (isnan(z_pt[CEN])) return false; } z_pt[CEN] /= float(_7p_2_intermediates ? 7 : probe_points); @@ -257,7 +259,8 @@ static bool probe_calibration_points(float z_pt[NPP + 1], const int8_t probe_poi const float a = RADIANS(210 + (360 / NPP) * (rad - 1)), r = delta_calibration_radius * (1 - 0.1 * (zig_zag ? offset - circle : circle)), interpol = FMOD(rad, 1); - const float z_temp = calibration_probe(cos(a) * r, sin(a) * r, stow_after_each); + const xy_pos_t vec = { cos(a), sin(a) }; + const float z_temp = calibration_probe(vec * r, stow_after_each); if (isnan(z_temp)) return false; // split probe point to neighbouring calibration points z_pt[uint8_t(LROUND(rad - interpol + NPP - 1)) % NPP + 1] += z_temp * sq(cos(RADIANS(interpol * 90))); @@ -281,80 +284,69 @@ static bool probe_calibration_points(float z_pt[NPP + 1], const int8_t probe_poi * - formulae for approximative forward kinematics in the end-stop displacement matrix * - definition of the matrix scaling parameters */ -static void reverse_kinematics_probe_points(float z_pt[NPP + 1], float mm_at_pt_axis[NPP + 1][ABC]) { - float pos[XYZ] = { 0.0 }; +static void reverse_kinematics_probe_points(float z_pt[NPP + 1], abc_float_t mm_at_pt_axis[NPP + 1]) { + xyz_pos_t pos{0}; LOOP_CAL_ALL(rad) { const float a = RADIANS(210 + (360 / NPP) * (rad - 1)), r = (rad == CEN ? 0.0f : delta_calibration_radius); - pos[X_AXIS] = cos(a) * r; - pos[Y_AXIS] = sin(a) * r; - pos[Z_AXIS] = z_pt[rad]; + pos.set(cos(a) * r, sin(a) * r, z_pt[rad]); inverse_kinematics(pos); - LOOP_XYZ(axis) mm_at_pt_axis[rad][axis] = delta[axis]; + mm_at_pt_axis[rad] = delta; } } -static void forward_kinematics_probe_points(float mm_at_pt_axis[NPP + 1][ABC], float z_pt[NPP + 1]) { +static void forward_kinematics_probe_points(abc_float_t mm_at_pt_axis[NPP + 1], float z_pt[NPP + 1]) { const float r_quot = delta_calibration_radius / delta_radius; - #define ZPP(N,I,A) ((1 / 3.0f + r_quot * (N) / 3.0f ) * mm_at_pt_axis[I][A]) + #define ZPP(N,I,A) (((1.0f + r_quot * (N)) / 3.0f) * mm_at_pt_axis[I].A) #define Z00(I, A) ZPP( 0, I, A) #define Zp1(I, A) ZPP(+1, I, A) #define Zm1(I, A) ZPP(-1, I, A) #define Zp2(I, A) ZPP(+2, I, A) #define Zm2(I, A) ZPP(-2, I, A) - z_pt[CEN] = Z00(CEN, A_AXIS) + Z00(CEN, B_AXIS) + Z00(CEN, C_AXIS); - z_pt[__A] = Zp2(__A, A_AXIS) + Zm1(__A, B_AXIS) + Zm1(__A, C_AXIS); - z_pt[__B] = Zm1(__B, A_AXIS) + Zp2(__B, B_AXIS) + Zm1(__B, C_AXIS); - z_pt[__C] = Zm1(__C, A_AXIS) + Zm1(__C, B_AXIS) + Zp2(__C, C_AXIS); - z_pt[_BC] = Zm2(_BC, A_AXIS) + Zp1(_BC, B_AXIS) + Zp1(_BC, C_AXIS); - z_pt[_CA] = Zp1(_CA, A_AXIS) + Zm2(_CA, B_AXIS) + Zp1(_CA, C_AXIS); - z_pt[_AB] = Zp1(_AB, A_AXIS) + Zp1(_AB, B_AXIS) + Zm2(_AB, C_AXIS); + z_pt[CEN] = Z00(CEN, a) + Z00(CEN, b) + Z00(CEN, c); + z_pt[__A] = Zp2(__A, a) + Zm1(__A, b) + Zm1(__A, c); + z_pt[__B] = Zm1(__B, a) + Zp2(__B, b) + Zm1(__B, c); + z_pt[__C] = Zm1(__C, a) + Zm1(__C, b) + Zp2(__C, c); + z_pt[_BC] = Zm2(_BC, a) + Zp1(_BC, b) + Zp1(_BC, c); + z_pt[_CA] = Zp1(_CA, a) + Zm2(_CA, b) + Zp1(_CA, c); + z_pt[_AB] = Zp1(_AB, a) + Zp1(_AB, b) + Zm2(_AB, c); } -static void calc_kinematics_diff_probe_points(float z_pt[NPP + 1], float delta_e[ABC], float delta_r, float delta_t[ABC]) { +static void calc_kinematics_diff_probe_points(float z_pt[NPP + 1], abc_float_t delta_e, const float delta_r, abc_float_t delta_t) { const float z_center = z_pt[CEN]; - float diff_mm_at_pt_axis[NPP + 1][ABC], - new_mm_at_pt_axis[NPP + 1][ABC]; + abc_float_t diff_mm_at_pt_axis[NPP + 1], new_mm_at_pt_axis[NPP + 1]; reverse_kinematics_probe_points(z_pt, diff_mm_at_pt_axis); delta_radius += delta_r; - LOOP_XYZ(axis) delta_tower_angle_trim[axis] += delta_t[axis]; + delta_tower_angle_trim += delta_t; recalc_delta_settings(); reverse_kinematics_probe_points(z_pt, new_mm_at_pt_axis); - LOOP_XYZ(axis) LOOP_CAL_ALL(rad) diff_mm_at_pt_axis[rad][axis] -= new_mm_at_pt_axis[rad][axis] + delta_e[axis]; + LOOP_CAL_ALL(rad) diff_mm_at_pt_axis[rad] -= new_mm_at_pt_axis[rad] + delta_e; forward_kinematics_probe_points(diff_mm_at_pt_axis, z_pt); LOOP_CAL_RAD(rad) z_pt[rad] -= z_pt[CEN] - z_center; z_pt[CEN] = z_center; delta_radius -= delta_r; - LOOP_XYZ(axis) delta_tower_angle_trim[axis] -= delta_t[axis]; + delta_tower_angle_trim -= delta_t; recalc_delta_settings(); } static float auto_tune_h() { const float r_quot = delta_calibration_radius / delta_radius; - float h_fac = 0.0f; - - h_fac = r_quot / (2.0f / 3.0f); - h_fac = 1.0f / h_fac; // (2/3)/CR - return h_fac; + return RECIPROCAL(r_quot / (2.0f / 3.0f)); // (2/3)/CR } static float auto_tune_r() { - const float diff = 0.01f; - float r_fac = 0.0f, - z_pt[NPP + 1] = { 0.0f }, - delta_e[ABC] = { 0.0f }, - delta_r = { 0.0f }, - delta_t[ABC] = { 0.0f }; - - delta_r = diff; + constexpr float diff = 0.01f, delta_r = diff; + float r_fac = 0.0f, z_pt[NPP + 1] = { 0.0f }; + abc_float_t delta_e = { 0.0f }, delta_t = { 0.0f }; + calc_kinematics_diff_probe_points(z_pt, delta_e, delta_r, delta_t); r_fac = -(z_pt[__A] + z_pt[__B] + z_pt[__C] + z_pt[_BC] + z_pt[_CA] + z_pt[_AB]) / 6.0f; r_fac = diff / r_fac / 3.0f; // 1/(3*delta_Z) @@ -362,14 +354,11 @@ static float auto_tune_r() { } static float auto_tune_a() { - const float diff = 0.01f; - float a_fac = 0.0f, - z_pt[NPP + 1] = { 0.0f }, - delta_e[ABC] = { 0.0f }, - delta_r = { 0.0f }, - delta_t[ABC] = { 0.0f }; - - ZERO(delta_t); + constexpr float diff = 0.01f, delta_r = 0.0f; + float a_fac = 0.0f, z_pt[NPP + 1] = { 0.0f }; + abc_float_t delta_e = { 0.0f }, delta_t = { 0.0f }; + + delta_t.reset(); LOOP_XYZ(axis) { delta_t[axis] = diff; calc_kinematics_diff_probe_points(z_pt, delta_e, delta_r, delta_t); @@ -453,21 +442,11 @@ void GcodeSuite::G33() { zero_std_dev = (verbose_level ? 999.0f : 0.0f), // 0.0 in dry-run mode : forced end zero_std_dev_min = zero_std_dev, zero_std_dev_old = zero_std_dev, - h_factor, - r_factor, - a_factor, - e_old[ABC] = { - delta_endstop_adj[A_AXIS], - delta_endstop_adj[B_AXIS], - delta_endstop_adj[C_AXIS] - }, + h_factor, r_factor, a_factor, r_old = delta_radius, - h_old = delta_height, - a_old[ABC] = { - delta_tower_angle_trim[A_AXIS], - delta_tower_angle_trim[B_AXIS], - delta_tower_angle_trim[C_AXIS] - }; + h_old = delta_height; + + abc_pos_t e_old = delta_endstop_adj, a_old = delta_tower_angle_trim; SERIAL_ECHOLNPGM("G33 Auto Calibrate"); @@ -520,15 +499,14 @@ void GcodeSuite::G33() { if (zero_std_dev < zero_std_dev_min) { // set roll-back point - COPY(e_old, delta_endstop_adj); + e_old = delta_endstop_adj; r_old = delta_radius; h_old = delta_height; - COPY(a_old, delta_tower_angle_trim); + a_old = delta_tower_angle_trim; } - float e_delta[ABC] = { 0.0f }, - r_delta = 0.0f, - t_delta[ABC] = { 0.0f }; + abc_float_t e_delta = { 0.0f }, t_delta = { 0.0f }; + float r_delta = 0.0f; /** * convergence matrices: @@ -563,42 +541,42 @@ void GcodeSuite::G33() { case 2: if (towers_set) { // see 4 point calibration (towers) matrix - e_delta[A_AXIS] = (+Z4(__A) -Z2(__B) -Z2(__C)) * h_factor +Z4(CEN); - e_delta[B_AXIS] = (-Z2(__A) +Z4(__B) -Z2(__C)) * h_factor +Z4(CEN); - e_delta[C_AXIS] = (-Z2(__A) -Z2(__B) +Z4(__C)) * h_factor +Z4(CEN); - r_delta = (+Z4(__A) +Z4(__B) +Z4(__C) -Z12(CEN)) * r_factor; + e_delta.set((+Z4(__A) -Z2(__B) -Z2(__C)) * h_factor +Z4(CEN), + (-Z2(__A) +Z4(__B) -Z2(__C)) * h_factor +Z4(CEN), + (-Z2(__A) -Z2(__B) +Z4(__C)) * h_factor +Z4(CEN)); + r_delta = (+Z4(__A) +Z4(__B) +Z4(__C) -Z12(CEN)) * r_factor; } else { // see 4 point calibration (opposites) matrix - e_delta[A_AXIS] = (-Z4(_BC) +Z2(_CA) +Z2(_AB)) * h_factor +Z4(CEN); - e_delta[B_AXIS] = (+Z2(_BC) -Z4(_CA) +Z2(_AB)) * h_factor +Z4(CEN); - e_delta[C_AXIS] = (+Z2(_BC) +Z2(_CA) -Z4(_AB)) * h_factor +Z4(CEN); - r_delta = (+Z4(_BC) +Z4(_CA) +Z4(_AB) -Z12(CEN)) * r_factor; + e_delta.set((-Z4(_BC) +Z2(_CA) +Z2(_AB)) * h_factor +Z4(CEN), + (+Z2(_BC) -Z4(_CA) +Z2(_AB)) * h_factor +Z4(CEN), + (+Z2(_BC) +Z2(_CA) -Z4(_AB)) * h_factor +Z4(CEN)); + r_delta = (+Z4(_BC) +Z4(_CA) +Z4(_AB) -Z12(CEN)) * r_factor; } break; default: // see 7 point calibration (towers & opposites) matrix - e_delta[A_AXIS] = (+Z2(__A) -Z1(__B) -Z1(__C) -Z2(_BC) +Z1(_CA) +Z1(_AB)) * h_factor +Z4(CEN); - e_delta[B_AXIS] = (-Z1(__A) +Z2(__B) -Z1(__C) +Z1(_BC) -Z2(_CA) +Z1(_AB)) * h_factor +Z4(CEN); - e_delta[C_AXIS] = (-Z1(__A) -Z1(__B) +Z2(__C) +Z1(_BC) +Z1(_CA) -Z2(_AB)) * h_factor +Z4(CEN); - r_delta = (+Z2(__A) +Z2(__B) +Z2(__C) +Z2(_BC) +Z2(_CA) +Z2(_AB) -Z12(CEN)) * r_factor; + e_delta.set((+Z2(__A) -Z1(__B) -Z1(__C) -Z2(_BC) +Z1(_CA) +Z1(_AB)) * h_factor +Z4(CEN), + (-Z1(__A) +Z2(__B) -Z1(__C) +Z1(_BC) -Z2(_CA) +Z1(_AB)) * h_factor +Z4(CEN), + (-Z1(__A) -Z1(__B) +Z2(__C) +Z1(_BC) +Z1(_CA) -Z2(_AB)) * h_factor +Z4(CEN)); + r_delta = (+Z2(__A) +Z2(__B) +Z2(__C) +Z2(_BC) +Z2(_CA) +Z2(_AB) -Z12(CEN)) * r_factor; if (towers_set) { // see 7 point tower angle calibration (towers & opposites) matrix - t_delta[A_AXIS] = (+Z0(__A) -Z4(__B) +Z4(__C) +Z0(_BC) -Z4(_CA) +Z4(_AB) +Z0(CEN)) * a_factor; - t_delta[B_AXIS] = (+Z4(__A) +Z0(__B) -Z4(__C) +Z4(_BC) +Z0(_CA) -Z4(_AB) +Z0(CEN)) * a_factor; - t_delta[C_AXIS] = (-Z4(__A) +Z4(__B) +Z0(__C) -Z4(_BC) +Z4(_CA) +Z0(_AB) +Z0(CEN)) * a_factor; + t_delta.set((+Z0(__A) -Z4(__B) +Z4(__C) +Z0(_BC) -Z4(_CA) +Z4(_AB) +Z0(CEN)) * a_factor, + (+Z4(__A) +Z0(__B) -Z4(__C) +Z4(_BC) +Z0(_CA) -Z4(_AB) +Z0(CEN)) * a_factor, + (-Z4(__A) +Z4(__B) +Z0(__C) -Z4(_BC) +Z4(_CA) +Z0(_AB) +Z0(CEN)) * a_factor); } break; } - LOOP_XYZ(axis) delta_endstop_adj[axis] += e_delta[axis]; + delta_endstop_adj += e_delta; delta_radius += r_delta; - LOOP_XYZ(axis) delta_tower_angle_trim[axis] += t_delta[axis]; + delta_tower_angle_trim += t_delta; } else if (zero_std_dev >= test_precision) { // roll back - COPY(delta_endstop_adj, e_old); + delta_endstop_adj = e_old; delta_radius = r_old; delta_height = h_old; - COPY(delta_tower_angle_trim, a_old); + delta_tower_angle_trim = a_old; } if (verbose_level != 0) { // !dry run @@ -611,7 +589,7 @@ void GcodeSuite::G33() { } // adjust delta_height and endstops by the max amount - const float z_temp = _MAX(delta_endstop_adj[A_AXIS], delta_endstop_adj[B_AXIS], delta_endstop_adj[C_AXIS]); + const float z_temp = _MAX(delta_endstop_adj.a, delta_endstop_adj.b, delta_endstop_adj.c); delta_height -= z_temp; LOOP_XYZ(axis) delta_endstop_adj[axis] -= z_temp; } diff --git a/Marlin/src/gcode/calibrate/G34_M422.cpp b/Marlin/src/gcode/calibrate/G34_M422.cpp index b7b366a1c..48ed8fe98 100644 --- a/Marlin/src/gcode/calibrate/G34_M422.cpp +++ b/Marlin/src/gcode/calibrate/G34_M422.cpp @@ -45,8 +45,17 @@ #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) #include "../../core/debug_out.h" -float z_auto_align_xpos[Z_STEPPER_COUNT] = Z_STEPPER_ALIGN_X, - z_auto_align_ypos[Z_STEPPER_COUNT] = Z_STEPPER_ALIGN_Y; +// Sanity-check +constexpr xy_pos_t sanity_arr_z_align[] = Z_STEPPER_ALIGN_XY; +static_assert(COUNT(sanity_arr_z_align) == Z_STEPPER_COUNT, + #if ENABLED(Z_TRIPLE_STEPPER_DRIVERS) + "Z_STEPPER_ALIGN_XY requires three {X,Y} entries (Z, Z2, and Z3)." + #else + "Z_STEPPER_ALIGN_XY requires two {X,Y} entries (Z and Z2)." + #endif +); + +xy_pos_t z_auto_align_pos[Z_STEPPER_COUNT] = Z_STEPPER_ALIGN_XY; inline void set_all_z_lock(const bool lock) { stepper.set_z_lock(lock); @@ -123,11 +132,11 @@ void GcodeSuite::G34() { float z_probe = Z_BASIC_CLEARANCE + (G34_MAX_GRADE) * 0.01f * ( #if ENABLED(Z_TRIPLE_STEPPER_DRIVERS) - SQRT(_MAX(HYPOT2(z_auto_align_xpos[0] - z_auto_align_ypos[0], z_auto_align_xpos[1] - z_auto_align_ypos[1]), - HYPOT2(z_auto_align_xpos[1] - z_auto_align_ypos[1], z_auto_align_xpos[2] - z_auto_align_ypos[2]), - HYPOT2(z_auto_align_xpos[2] - z_auto_align_ypos[2], z_auto_align_xpos[0] - z_auto_align_ypos[0]))) + SQRT(_MAX(HYPOT2(z_auto_align_pos[0].x - z_auto_align_pos[0].y, z_auto_align_pos[1].x - z_auto_align_pos[1].y), + HYPOT2(z_auto_align_pos[1].x - z_auto_align_pos[1].y, z_auto_align_pos[2].x - z_auto_align_pos[2].y), + HYPOT2(z_auto_align_pos[2].x - z_auto_align_pos[2].y, z_auto_align_pos[0].x - z_auto_align_pos[0].y))) #else - HYPOT(z_auto_align_xpos[0] - z_auto_align_ypos[0], z_auto_align_xpos[1] - z_auto_align_ypos[1]) + HYPOT(z_auto_align_pos[0].x - z_auto_align_pos[0].y, z_auto_align_pos[1].x - z_auto_align_pos[1].y) #endif ); @@ -135,7 +144,7 @@ void GcodeSuite::G34() { if (!all_axes_known()) home_all_axes(); // Move the Z coordinate realm towards the positive - dirty trick - current_position[Z_AXIS] -= z_probe * 0.5; + current_position.z -= z_probe * 0.5f; float last_z_align_move[Z_STEPPER_COUNT] = ARRAY_N(Z_STEPPER_COUNT, 10000.0f, 10000.0f, 10000.0f), z_measured[Z_STEPPER_COUNT] = { 0 }, @@ -162,7 +171,7 @@ void GcodeSuite::G34() { if (iteration == 0 || izstepper > 0) do_blocking_move_to_z(z_probe); // Probe a Z height for each stepper. - const float z_probed_height = probe_at_point(z_auto_align_xpos[zstepper], z_auto_align_ypos[zstepper], raise_after, 0, true); + const float z_probed_height = probe_at_point(z_auto_align_pos[zstepper], raise_after, 0, true); if (isnan(z_probed_height)) { SERIAL_ECHOLNPGM("Probing failed."); err_break = true; @@ -240,7 +249,7 @@ void GcodeSuite::G34() { } // Do a move to correct part of the misalignment for the current stepper - do_blocking_move_to_z(amplification * z_align_move + current_position[Z_AXIS]); + do_blocking_move_to_z(amplification * z_align_move + current_position.z); } // for (zstepper) // Back to normal stepper operations @@ -299,20 +308,22 @@ void GcodeSuite::M422() { return; } - const float x_pos = parser.floatval('X', z_auto_align_xpos[zstepper]); - if (!WITHIN(x_pos, X_MIN_POS, X_MAX_POS)) { + const xy_pos_t pos = { + parser.floatval('X', z_auto_align_pos[zstepper].x), + parser.floatval('Y', z_auto_align_pos[zstepper].y) + }; + + if (!WITHIN(pos.x, X_MIN_POS, X_MAX_POS)) { SERIAL_ECHOLNPGM("?(X) out of bounds."); return; } - const float y_pos = parser.floatval('Y', z_auto_align_ypos[zstepper]); - if (!WITHIN(y_pos, Y_MIN_POS, Y_MAX_POS)) { + if (!WITHIN(pos.y, Y_MIN_POS, Y_MAX_POS)) { SERIAL_ECHOLNPGM("?(Y) out of bounds."); return; } - z_auto_align_xpos[zstepper] = x_pos; - z_auto_align_ypos[zstepper] = y_pos; + z_auto_align_pos[zstepper] = pos; } #endif // Z_STEPPER_AUTO_ALIGN diff --git a/Marlin/src/gcode/calibrate/G425.cpp b/Marlin/src/gcode/calibrate/G425.cpp index 5c4272346..2b2c16657 100644 --- a/Marlin/src/gcode/calibrate/G425.cpp +++ b/Marlin/src/gcode/calibrate/G425.cpp @@ -61,17 +61,17 @@ enum side_t : uint8_t { TOP, RIGHT, FRONT, LEFT, BACK, NUM_SIDES }; -struct measurements_t { - static constexpr float dimensions[XYZ] = CALIBRATION_OBJECT_DIMENSIONS; - static constexpr float true_center[XYZ] = CALIBRATION_OBJECT_CENTER; +static constexpr xyz_pos_t true_center CALIBRATION_OBJECT_CENTER; +static constexpr xyz_float_t dimensions CALIBRATION_OBJECT_DIMENSIONS; +static constexpr xy_float_t nod = { CALIBRATION_NOZZLE_OUTER_DIAMETER, CALIBRATION_NOZZLE_OUTER_DIAMETER }; - float obj_center[XYZ] = CALIBRATION_OBJECT_CENTER; - float obj_side[NUM_SIDES]; +struct measurements_t { + xyz_pos_t obj_center = true_center; // Non-static must be assigned from xyz_pos_t - float backlash[NUM_SIDES]; - float pos_error[XYZ]; + float obj_side[NUM_SIDES], backlash[NUM_SIDES]; + xyz_float_t pos_error; - float nozzle_outer_dimension[2] = {CALIBRATION_NOZZLE_OUTER_DIAMETER, CALIBRATION_NOZZLE_OUTER_DIAMETER}; + xy_float_t nozzle_outer_dimension = nod; }; #define TEMPORARY_SOFT_ENDSTOP_STATE(enable) REMEMBER(tes, soft_endstops_enabled, enable); @@ -88,29 +88,8 @@ struct measurements_t { #define TEMPORARY_BACKLASH_SMOOTHING(value) #endif -/** - * Move to a particular location. Up to three individual axes - * and their destinations can be specified, in any order. - */ -inline void move_to( - const AxisEnum a1 = NO_AXIS, const float p1 = 0, - const AxisEnum a2 = NO_AXIS, const float p2 = 0, - const AxisEnum a3 = NO_AXIS, const float p3 = 0 -) { - set_destination_from_current(); - - // Note: The order of p1, p2, p3 may not correspond to X, Y, Z - if (a1 != NO_AXIS) destination[a1] = p1; - if (a2 != NO_AXIS) destination[a2] = p2; - if (a3 != NO_AXIS) destination[a3] = p3; - - // Make sure coordinates are within bounds - destination[X_AXIS] = _MAX(_MIN(destination[X_AXIS], X_MAX_POS), X_MIN_POS); - destination[Y_AXIS] = _MAX(_MIN(destination[Y_AXIS], Y_MAX_POS), Y_MIN_POS); - destination[Z_AXIS] = _MAX(_MIN(destination[Z_AXIS], Z_MAX_POS), Z_MIN_POS); - - // Move to position - do_blocking_move_to(destination, MMM_TO_MMS(CALIBRATION_FEEDRATE_TRAVEL)); +inline void calibration_move() { + do_blocking_move_to(current_position, MMM_TO_MMS(CALIBRATION_FEEDRATE_TRAVEL)); } /** @@ -121,10 +100,12 @@ inline void move_to( */ inline void park_above_object(measurements_t &m, const float uncertainty) { // Move to safe distance above calibration object - move_to(Z_AXIS, m.obj_center[Z_AXIS] + m.dimensions[Z_AXIS] / 2 + uncertainty); + current_position.z = m.obj_center.z + dimensions.z / 2 + uncertainty; + calibration_move(); // Move to center of calibration object in XY - move_to(X_AXIS, m.obj_center[X_AXIS], Y_AXIS, m.obj_center[Y_AXIS]); + current_position = xy_pos_t(m.obj_center); + calibration_move(); } #if HOTENDS > 1 @@ -139,14 +120,9 @@ inline void park_above_object(measurements_t &m, const float uncertainty) { #if HAS_HOTEND_OFFSET inline void normalize_hotend_offsets() { - for (uint8_t e = 1; e < HOTENDS; e++) { - hotend_offset[X_AXIS][e] -= hotend_offset[X_AXIS][0]; - hotend_offset[Y_AXIS][e] -= hotend_offset[Y_AXIS][0]; - hotend_offset[Z_AXIS][e] -= hotend_offset[Z_AXIS][0]; - } - hotend_offset[X_AXIS][0] = 0; - hotend_offset[Y_AXIS][0] = 0; - hotend_offset[Z_AXIS][0] = 0; + for (uint8_t e = 1; e < HOTENDS; e++) + hotend_offset[e] -= hotend_offset[0]; + hotend_offset[0].reset(); } #endif @@ -175,7 +151,7 @@ float measuring_movement(const AxisEnum axis, const int dir, const bool stop_sta const feedRate_t mms = fast ? MMM_TO_MMS(CALIBRATION_FEEDRATE_FAST) : MMM_TO_MMS(CALIBRATION_FEEDRATE_SLOW); const float limit = fast ? 50 : 5; - set_destination_from_current(); + destination = current_position; for (float travel = 0; travel < limit; travel += step) { destination[axis] += dir * step; do_blocking_move_to(destination, mms); @@ -199,7 +175,7 @@ inline float measure(const AxisEnum axis, const int dir, const bool stop_state, const bool fast = uncertainty == CALIBRATION_MEASUREMENT_UNKNOWN; // Save position - set_destination_from_current(); + destination = current_position; const float start_pos = destination[axis]; const float measured_pos = measuring_movement(axis, dir, stop_state, fast); // Measure backlash @@ -223,7 +199,7 @@ inline float measure(const AxisEnum axis, const int dir, const bool stop_state, * to find out height of edge */ inline void probe_side(measurements_t &m, const float uncertainty, const side_t side, const bool probe_top_at_edge=false) { - const float dimensions[] = CALIBRATION_OBJECT_DIMENSIONS; + const xyz_float_t dimensions = CALIBRATION_OBJECT_DIMENSIONS; AxisEnum axis; float dir; @@ -232,7 +208,7 @@ inline void probe_side(measurements_t &m, const float uncertainty, const side_t switch (side) { case TOP: { const float measurement = measure(Z_AXIS, -1, true, &m.backlash[TOP], uncertainty); - m.obj_center[Z_AXIS] = measurement - dimensions[Z_AXIS] / 2; + m.obj_center.z = measurement - dimensions.z / 2; m.obj_side[TOP] = measurement; return; } @@ -240,22 +216,24 @@ inline void probe_side(measurements_t &m, const float uncertainty, const side_t case FRONT: axis = Y_AXIS; dir = 1; break; case LEFT: axis = X_AXIS; dir = 1; break; case BACK: axis = Y_AXIS; dir = -1; break; - default: - return; + default: return; } if (probe_top_at_edge) { // Probe top nearest the side we are probing - move_to(axis, m.obj_center[axis] + (-dir) * (dimensions[axis] / 2 - m.nozzle_outer_dimension[axis])); + current_position[axis] = m.obj_center[axis] + (-dir) * (dimensions[axis] / 2 - m.nozzle_outer_dimension[axis]); + calibration_move(); m.obj_side[TOP] = measure(Z_AXIS, -1, true, &m.backlash[TOP], uncertainty); - m.obj_center[Z_AXIS] = m.obj_side[TOP] - dimensions[Z_AXIS] / 2; + m.obj_center.z = m.obj_side[TOP] - dimensions.z / 2; } // Move to safe distance to the side of the calibration object - move_to(axis, m.obj_center[axis] + (-dir) * (dimensions[axis] / 2 + m.nozzle_outer_dimension[axis] / 2 + uncertainty)); + current_position[axis] = m.obj_center[axis] + (-dir) * (dimensions[axis] / 2 + m.nozzle_outer_dimension[axis] / 2 + uncertainty); + calibration_move(); // Plunge below the side of the calibration object and measure - move_to(Z_AXIS, m.obj_side[TOP] - CALIBRATION_NOZZLE_TIP_HEIGHT * 0.7); + current_position.z = m.obj_side[TOP] - CALIBRATION_NOZZLE_TIP_HEIGHT * 0.7; + calibration_move(); const float measurement = measure(axis, dir, true, &m.backlash[side], uncertainty); m.obj_center[axis] = measurement + dir * (dimensions[axis] / 2 + m.nozzle_outer_dimension[axis] / 2); m.obj_side[side] = measurement; @@ -294,36 +272,36 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { // Compute the measured center of the calibration object. #if HAS_X_CENTER - m.obj_center[X_AXIS] = (m.obj_side[LEFT] + m.obj_side[RIGHT]) / 2; + m.obj_center.x = (m.obj_side[LEFT] + m.obj_side[RIGHT]) / 2; #endif #if HAS_Y_CENTER - m.obj_center[Y_AXIS] = (m.obj_side[FRONT] + m.obj_side[BACK]) / 2; + m.obj_center.y = (m.obj_side[FRONT] + m.obj_side[BACK]) / 2; #endif // Compute the outside diameter of the nozzle at the height // at which it makes contact with the calibration object #if HAS_X_CENTER - m.nozzle_outer_dimension[X_AXIS] = m.obj_side[RIGHT] - m.obj_side[LEFT] - m.dimensions[X_AXIS]; + m.nozzle_outer_dimension.x = m.obj_side[RIGHT] - m.obj_side[LEFT] - dimensions.x; #endif #if HAS_Y_CENTER - m.nozzle_outer_dimension[Y_AXIS] = m.obj_side[BACK] - m.obj_side[FRONT] - m.dimensions[Y_AXIS]; + m.nozzle_outer_dimension.y = m.obj_side[BACK] - m.obj_side[FRONT] - dimensions.y; #endif park_above_object(m, uncertainty); // The difference between the known and the measured location // of the calibration object is the positional error - m.pos_error[X_AXIS] = (0 + m.pos_error.x = (0 #if HAS_X_CENTER - + m.true_center[X_AXIS] - m.obj_center[X_AXIS] + + true_center.x - m.obj_center.x #endif ); - m.pos_error[Y_AXIS] = (0 + m.pos_error.y = (0 #if HAS_Y_CENTER - + m.true_center[Y_AXIS] - m.obj_center[Y_AXIS] + + true_center.y - m.obj_center.y #endif ); - m.pos_error[Z_AXIS] = m.true_center[Z_AXIS] - m.obj_center[Z_AXIS]; + m.pos_error.z = true_center.z - m.obj_center.z; } #if ENABLED(CALIBRATION_REPORTING) @@ -348,12 +326,12 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { inline void report_measured_center(const measurements_t &m) { SERIAL_ECHOLNPGM("Center:"); #if HAS_X_CENTER - SERIAL_ECHOLNPAIR(" X", m.obj_center[X_AXIS]); + SERIAL_ECHOLNPAIR(" X", m.obj_center.x); #endif #if HAS_Y_CENTER - SERIAL_ECHOLNPAIR(" Y", m.obj_center[Y_AXIS]); + SERIAL_ECHOLNPAIR(" Y", m.obj_center.y); #endif - SERIAL_ECHOLNPAIR(" Z", m.obj_center[Z_AXIS]); + SERIAL_ECHOLNPAIR(" Z", m.obj_center.z); SERIAL_EOL(); } @@ -380,12 +358,12 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { SERIAL_ECHO(int(active_extruder)); SERIAL_ECHOLNPGM(" Positional Error:"); #if HAS_X_CENTER - SERIAL_ECHOLNPAIR(" X", m.pos_error[X_AXIS]); + SERIAL_ECHOLNPAIR(" X", m.pos_error.x); #endif #if HAS_Y_CENTER - SERIAL_ECHOLNPAIR(" Y", m.pos_error[Y_AXIS]); + SERIAL_ECHOLNPAIR(" Y", m.pos_error.y); #endif - SERIAL_ECHOLNPAIR(" Z", m.pos_error[Z_AXIS]); + SERIAL_ECHOLNPAIR(" Z", m.pos_error.z); SERIAL_EOL(); } @@ -393,10 +371,10 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { SERIAL_ECHOLNPGM("Nozzle Tip Outer Dimensions:"); #if HAS_X_CENTER || HAS_Y_CENTER #if HAS_X_CENTER - SERIAL_ECHOLNPAIR(" X", m.nozzle_outer_dimension[X_AXIS]); + SERIAL_ECHOLNPAIR(" X", m.nozzle_outer_dimension.x); #endif #if HAS_Y_CENTER - SERIAL_ECHOLNPAIR(" Y", m.nozzle_outer_dimension[Y_AXIS]); + SERIAL_ECHOLNPAIR(" Y", m.nozzle_outer_dimension.y); #endif #else UNUSED(m); @@ -410,7 +388,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { // inline void report_hotend_offsets() { for (uint8_t e = 1; e < HOTENDS; e++) - SERIAL_ECHOLNPAIR("T", int(e), " Hotend Offset X", hotend_offset[X_AXIS][e], " Y", hotend_offset[Y_AXIS][e], " Z", hotend_offset[Z_AXIS][e]); + SERIAL_ECHOLNPAIR("T", int(e), " Hotend Offset X", hotend_offset[e].x, " Y", hotend_offset[e].y, " Z", hotend_offset[e].z); } #endif @@ -434,49 +412,40 @@ inline void calibrate_backlash(measurements_t &m, const float uncertainty) { #if ENABLED(BACKLASH_GCODE) #if HAS_X_CENTER - backlash.distance_mm[X_AXIS] = (m.backlash[LEFT] + m.backlash[RIGHT]) / 2; + backlash.distance_mm.x = (m.backlash[LEFT] + m.backlash[RIGHT]) / 2; #elif ENABLED(CALIBRATION_MEASURE_LEFT) - backlash.distance_mm[X_AXIS] = m.backlash[LEFT]; + backlash.distance_mm.x = m.backlash[LEFT]; #elif ENABLED(CALIBRATION_MEASURE_RIGHT) - backlash.distance_mm[X_AXIS] = m.backlash[RIGHT]; + backlash.distance_mm.x = m.backlash[RIGHT]; #endif #if HAS_Y_CENTER - backlash.distance_mm[Y_AXIS] = (m.backlash[FRONT] + m.backlash[BACK]) / 2; + backlash.distance_mm.y = (m.backlash[FRONT] + m.backlash[BACK]) / 2; #elif ENABLED(CALIBRATION_MEASURE_FRONT) - backlash.distance_mm[Y_AXIS] = m.backlash[FRONT]; + backlash.distance_mm.y = m.backlash[FRONT]; #elif ENABLED(CALIBRATION_MEASURE_BACK) - backlash.distance_mm[Y_AXIS] = m.backlash[BACK]; + backlash.distance_mm.y = m.backlash[BACK]; #endif - backlash.distance_mm[Z_AXIS] = m.backlash[TOP]; + backlash.distance_mm.z = m.backlash[TOP]; #endif } #if ENABLED(BACKLASH_GCODE) // Turn on backlash compensation and move in all // directions to take up any backlash - { // New scope for TEMPORARY_BACKLASH_CORRECTION TEMPORARY_BACKLASH_CORRECTION(all_on); TEMPORARY_BACKLASH_SMOOTHING(0.0f); - move_to( - X_AXIS, current_position[X_AXIS] + 3, - Y_AXIS, current_position[Y_AXIS] + 3, - Z_AXIS, current_position[Z_AXIS] + 3 - ); - move_to( - X_AXIS, current_position[X_AXIS] - 3, - Y_AXIS, current_position[Y_AXIS] - 3, - Z_AXIS, current_position[Z_AXIS] - 3 - ); + const xyz_float_t move = { 3, 3, 3 }; + current_position += move; calibration_move(); + current_position -= move; calibration_move(); } #endif } inline void update_measurements(measurements_t &m, const AxisEnum axis) { - const float true_center[XYZ] = CALIBRATION_OBJECT_CENTER; current_position[axis] += m.pos_error[axis]; m.obj_center[axis] = true_center[axis]; m.pos_error[axis] = 0; @@ -508,12 +477,12 @@ inline void calibrate_toolhead(measurements_t &m, const float uncertainty, const // Adjust the hotend offset #if HAS_HOTEND_OFFSET #if HAS_X_CENTER - hotend_offset[X_AXIS][extruder] += m.pos_error[X_AXIS]; + hotend_offset[extruder].x += m.pos_error.x; #endif #if HAS_Y_CENTER - hotend_offset[Y_AXIS][extruder] += m.pos_error[Y_AXIS]; + hotend_offset[extruder].y += m.pos_error.y; #endif - hotend_offset[Z_AXIS][extruder] += m.pos_error[Z_AXIS]; + hotend_offset[extruder].z += m.pos_error.z; normalize_hotend_offsets(); #endif @@ -589,7 +558,8 @@ inline void calibrate_all() { // Do a slow and precise calibration of the toolheads calibrate_all_toolheads(m, CALIBRATION_MEASUREMENT_UNCERTAIN); - move_to(X_AXIS, 150); // Park nozzle away from calibration object + current_position.x = X_CENTER; + calibration_move(); // Park nozzle away from calibration object } /** diff --git a/Marlin/src/gcode/calibrate/M48.cpp b/Marlin/src/gcode/calibrate/M48.cpp index 49fc9982d..d8fe4e410 100644 --- a/Marlin/src/gcode/calibrate/M48.cpp +++ b/Marlin/src/gcode/calibrate/M48.cpp @@ -74,13 +74,14 @@ void GcodeSuite::M48() { const ProbePtRaise raise_after = parser.boolval('E') ? PROBE_PT_STOW : PROBE_PT_RAISE; - float X_current = current_position[X_AXIS], - Y_current = current_position[Y_AXIS]; + xy_float_t next_pos = current_position; - const float X_probe_location = parser.linearval('X', X_current + probe_offset[X_AXIS]), - Y_probe_location = parser.linearval('Y', Y_current + probe_offset[Y_AXIS]); + const xy_pos_t probe_pos = { + parser.linearval('X', next_pos.x + probe_offset.x), + parser.linearval('Y', next_pos.y + probe_offset.y) + }; - if (!position_is_reachable_by_probe(X_probe_location, Y_probe_location)) { + if (!position_is_reachable_by_probe(probe_pos)) { SERIAL_ECHOLNPGM("? (X,Y) out of bounds."); return; } @@ -116,7 +117,7 @@ void GcodeSuite::M48() { float mean = 0.0, sigma = 0.0, min = 99999.9, max = -99999.9, sample_set[n_samples]; // Move to the first point, deploy, and probe - const float t = probe_at_point(X_probe_location, Y_probe_location, raise_after, verbose_level); + const float t = probe_at_point(probe_pos, raise_after, verbose_level); bool probing_good = !isnan(t); if (probing_good) { @@ -165,32 +166,31 @@ void GcodeSuite::M48() { while (angle < 0.0) angle += 360.0; // outside of this range. It looks like they behave correctly with // numbers outside of the range, but just to be safe we clamp them. - X_current = X_probe_location - probe_offset[X_AXIS] + cos(RADIANS(angle)) * radius; - Y_current = Y_probe_location - probe_offset[Y_AXIS] + sin(RADIANS(angle)) * radius; + next_pos.set(probe_pos.x - probe_offset.x + cos(RADIANS(angle)) * radius, + probe_pos.y - probe_offset.y + sin(RADIANS(angle)) * radius); #if DISABLED(DELTA) - LIMIT(X_current, X_MIN_POS, X_MAX_POS); - LIMIT(Y_current, Y_MIN_POS, Y_MAX_POS); + LIMIT(next_pos.x, X_MIN_POS, X_MAX_POS); + LIMIT(next_pos.y, Y_MIN_POS, Y_MAX_POS); #else // If we have gone out too far, we can do a simple fix and scale the numbers // back in closer to the origin. - while (!position_is_reachable_by_probe(X_current, Y_current)) { - X_current *= 0.8; - Y_current *= 0.8; + while (!position_is_reachable_by_probe(next_pos)) { + next_pos *= 0.8; if (verbose_level > 3) - SERIAL_ECHOLNPAIR("Moving inward: X", X_current, " Y", Y_current); + SERIAL_ECHOLNPAIR("Moving inward: X", next_pos.x, " Y", next_pos.y); } #endif if (verbose_level > 3) - SERIAL_ECHOLNPAIR("Going to: X", X_current, " Y", Y_current, " Z", current_position[Z_AXIS]); + SERIAL_ECHOLNPAIR("Going to: X", next_pos.x, " Y", next_pos.y); - do_blocking_move_to_xy(X_current, Y_current); + do_blocking_move_to_xy(next_pos); } // n_legs loop } // n_legs // Probe a single point - sample_set[n] = probe_at_point(X_probe_location, Y_probe_location, raise_after, 0); + sample_set[n] = probe_at_point(probe_pos, raise_after, 0); // Break the loop if the probe fails probing_good = !isnan(sample_set[n]); diff --git a/Marlin/src/gcode/calibrate/M665.cpp b/Marlin/src/gcode/calibrate/M665.cpp index 6422057ef..1b37fa8bb 100644 --- a/Marlin/src/gcode/calibrate/M665.cpp +++ b/Marlin/src/gcode/calibrate/M665.cpp @@ -43,14 +43,14 @@ * Z = Gamma (Tower 3) angle trim */ void GcodeSuite::M665() { - if (parser.seen('H')) delta_height = parser.value_linear_units(); - if (parser.seen('L')) delta_diagonal_rod = parser.value_linear_units(); - if (parser.seen('R')) delta_radius = parser.value_linear_units(); - if (parser.seen('S')) delta_segments_per_second = parser.value_float(); - if (parser.seen('B')) delta_calibration_radius = parser.value_float(); - if (parser.seen('X')) delta_tower_angle_trim[A_AXIS] = parser.value_float(); - if (parser.seen('Y')) delta_tower_angle_trim[B_AXIS] = parser.value_float(); - if (parser.seen('Z')) delta_tower_angle_trim[C_AXIS] = parser.value_float(); + if (parser.seen('H')) delta_height = parser.value_linear_units(); + if (parser.seen('L')) delta_diagonal_rod = parser.value_linear_units(); + if (parser.seen('R')) delta_radius = parser.value_linear_units(); + if (parser.seen('S')) delta_segments_per_second = parser.value_float(); + if (parser.seen('B')) delta_calibration_radius = parser.value_float(); + if (parser.seen('X')) delta_tower_angle_trim.a = parser.value_float(); + if (parser.seen('Y')) delta_tower_angle_trim.b = parser.value_float(); + if (parser.seen('Z')) delta_tower_angle_trim.c = parser.value_float(); recalc_delta_settings(); } @@ -76,13 +76,13 @@ #if HAS_SCARA_OFFSET - if (parser.seenval('Z')) scara_home_offset[Z_AXIS] = parser.value_linear_units(); + if (parser.seenval('Z')) scara_home_offset.z = parser.value_linear_units(); const bool hasA = parser.seenval('A'), hasP = parser.seenval('P'), hasX = parser.seenval('X'); const uint8_t sumAPX = hasA + hasP + hasX; if (sumAPX) { if (sumAPX == 1) - scara_home_offset[A_AXIS] = parser.value_float(); + scara_home_offset.a = parser.value_float(); else { SERIAL_ERROR_MSG("Only one of A, P, or X is allowed."); return; @@ -93,7 +93,7 @@ const uint8_t sumBTY = hasB + hasT + hasY; if (sumBTY) { if (sumBTY == 1) - scara_home_offset[B_AXIS] = parser.value_float(); + scara_home_offset.b = parser.value_float(); else { SERIAL_ERROR_MSG("Only one of B, T, or Y is allowed."); return; diff --git a/Marlin/src/gcode/config/M200-M205.cpp b/Marlin/src/gcode/config/M200-M205.cpp index c43b88924..0edffe5b4 100644 --- a/Marlin/src/gcode/config/M200-M205.cpp +++ b/Marlin/src/gcode/config/M200-M205.cpp @@ -152,17 +152,17 @@ void GcodeSuite::M205() { } #endif #if HAS_CLASSIC_JERK - if (parser.seen('X')) planner.max_jerk[X_AXIS] = parser.value_linear_units(); - if (parser.seen('Y')) planner.max_jerk[Y_AXIS] = parser.value_linear_units(); + if (parser.seen('X')) planner.max_jerk.x = parser.value_linear_units(); + if (parser.seen('Y')) planner.max_jerk.y = parser.value_linear_units(); if (parser.seen('Z')) { - planner.max_jerk[Z_AXIS] = parser.value_linear_units(); + planner.max_jerk.z = parser.value_linear_units(); #if HAS_MESH - if (planner.max_jerk[Z_AXIS] <= 0.1f) + if (planner.max_jerk.z <= 0.1f) SERIAL_ECHOLNPGM("WARNING! Low Z Jerk may lead to unwanted pauses."); #endif } #if !BOTH(JUNCTION_DEVIATION, LIN_ADVANCE) - if (parser.seen('E')) planner.max_jerk[E_AXIS] = parser.value_linear_units(); + if (parser.seen('E')) planner.max_jerk.e = parser.value_linear_units(); #endif #endif } diff --git a/Marlin/src/gcode/config/M218.cpp b/Marlin/src/gcode/config/M218.cpp index d43991171..790d7714a 100644 --- a/Marlin/src/gcode/config/M218.cpp +++ b/Marlin/src/gcode/config/M218.cpp @@ -44,27 +44,27 @@ void GcodeSuite::M218() { const int8_t target_extruder = get_target_extruder_from_command(); if (target_extruder < 0) return; - if (parser.seenval('X')) hotend_offset[X_AXIS][target_extruder] = parser.value_linear_units(); - if (parser.seenval('Y')) hotend_offset[Y_AXIS][target_extruder] = parser.value_linear_units(); - if (parser.seenval('Z')) hotend_offset[Z_AXIS][target_extruder] = parser.value_linear_units(); + if (parser.seenval('X')) hotend_offset[target_extruder].x = parser.value_linear_units(); + if (parser.seenval('Y')) hotend_offset[target_extruder].y = parser.value_linear_units(); + if (parser.seenval('Z')) hotend_offset[target_extruder].z = parser.value_linear_units(); if (!parser.seen("XYZ")) { SERIAL_ECHO_START(); SERIAL_ECHOPGM(MSG_HOTEND_OFFSET); HOTEND_LOOP() { SERIAL_CHAR(' '); - SERIAL_ECHO(hotend_offset[X_AXIS][e]); + SERIAL_ECHO(hotend_offset[e].x); SERIAL_CHAR(','); - SERIAL_ECHO(hotend_offset[Y_AXIS][e]); + SERIAL_ECHO(hotend_offset[e].y); SERIAL_CHAR(','); - SERIAL_ECHO_F(hotend_offset[Z_AXIS][e], 3); + SERIAL_ECHO_F(hotend_offset[e].z, 3); } SERIAL_EOL(); } #if ENABLED(DELTA) if (target_extruder == active_extruder) - do_blocking_move_to_xy(current_position[X_AXIS], current_position[Y_AXIS], planner.settings.max_feedrate_mm_s[X_AXIS]); + do_blocking_move_to_xy(current_position, planner.settings.max_feedrate_mm_s[X_AXIS]); #endif } diff --git a/Marlin/src/gcode/config/M92.cpp b/Marlin/src/gcode/config/M92.cpp index f0e27e82d..0fd8dbea1 100644 --- a/Marlin/src/gcode/config/M92.cpp +++ b/Marlin/src/gcode/config/M92.cpp @@ -77,7 +77,7 @@ void GcodeSuite::M92() { if (value < 20) { float factor = planner.settings.axis_steps_per_mm[E_AXIS_N(target_extruder)] / value; // increase e constants if M92 E14 is given for netfab. #if HAS_CLASSIC_JERK && !BOTH(JUNCTION_DEVIATION, LIN_ADVANCE) - planner.max_jerk[E_AXIS] *= factor; + planner.max_jerk.e *= factor; #endif planner.settings.max_feedrate_mm_s[E_AXIS_N(target_extruder)] *= factor; planner.max_acceleration_steps_per_s2[E_AXIS_N(target_extruder)] *= factor; diff --git a/Marlin/src/gcode/control/M211.cpp b/Marlin/src/gcode/control/M211.cpp index 64c273275..432ab1379 100644 --- a/Marlin/src/gcode/control/M211.cpp +++ b/Marlin/src/gcode/control/M211.cpp @@ -33,18 +33,14 @@ * Usage: M211 S1 to enable, M211 S0 to disable, M211 alone for report */ void GcodeSuite::M211() { + const xyz_pos_t l_soft_min = soft_endstop.min.asLogical(), + l_soft_max = soft_endstop.max.asLogical(); SERIAL_ECHO_START(); SERIAL_ECHOPGM(MSG_SOFT_ENDSTOPS); if (parser.seen('S')) soft_endstops_enabled = parser.value_bool(); serialprint_onoff(soft_endstops_enabled); - SERIAL_ECHOPGM(MSG_SOFT_MIN); - SERIAL_ECHOPAIR( MSG_X, LOGICAL_X_POSITION(soft_endstop[X_AXIS].min)); - SERIAL_ECHOPAIR(" " MSG_Y, LOGICAL_Y_POSITION(soft_endstop[Y_AXIS].min)); - SERIAL_ECHOPAIR(" " MSG_Z, LOGICAL_Z_POSITION(soft_endstop[Z_AXIS].min)); - SERIAL_ECHOPGM(MSG_SOFT_MAX); - SERIAL_ECHOPAIR( MSG_X, LOGICAL_X_POSITION(soft_endstop[X_AXIS].max)); - SERIAL_ECHOPAIR(" " MSG_Y, LOGICAL_Y_POSITION(soft_endstop[Y_AXIS].max)); - SERIAL_ECHOLNPAIR(" " MSG_Z, LOGICAL_Z_POSITION(soft_endstop[Z_AXIS].max)); + print_xyz(l_soft_min, PSTR(MSG_SOFT_MIN), PSTR(" ")); + print_xyz(l_soft_max, PSTR(MSG_SOFT_MAX)); } #endif diff --git a/Marlin/src/gcode/control/M605.cpp b/Marlin/src/gcode/control/M605.cpp index 84a75686a..007c6fc6b 100644 --- a/Marlin/src/gcode/control/M605.cpp +++ b/Marlin/src/gcode/control/M605.cpp @@ -79,9 +79,9 @@ } mirrored_duplication_mode = true; stepper.set_directions(); - float x_jog = current_position[X_AXIS] - .1; + float x_jog = current_position.x - .1; for (uint8_t i = 2; --i;) { - planner.buffer_line(x_jog, current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], feedrate_mm_s, 0); + planner.buffer_line(x_jog, current_position.y, current_position.z, current_position.e, feedrate_mm_s, 0); x_jog += .1; } return; @@ -122,7 +122,7 @@ DEBUG_ECHOPAIR("\nActive Ext: ", int(active_extruder)); if (!active_extruder_parked) DEBUG_ECHOPGM(" NOT "); DEBUG_ECHOPGM(" parked."); - DEBUG_ECHOPAIR("\nactive_extruder_x_pos: ", current_position[X_AXIS]); + DEBUG_ECHOPAIR("\nactive_extruder_x_pos: ", current_position.x); DEBUG_ECHOPAIR("\ninactive_extruder_x_pos: ", inactive_extruder_x_pos); DEBUG_ECHOPAIR("\nextruder_duplication_enabled: ", int(extruder_duplication_enabled)); DEBUG_ECHOPAIR("\nduplicate_extruder_x_offset: ", duplicate_extruder_x_offset); @@ -138,7 +138,7 @@ HOTEND_LOOP() { DEBUG_ECHOPAIR(" T", int(e)); - LOOP_XYZ(a) DEBUG_ECHOPAIR(" hotend_offset[", axis_codes[a], "_AXIS][", int(e), "]=", hotend_offset[a][e]); + LOOP_XYZ(a) DEBUG_ECHOPAIR(" hotend_offset[", int(e), "].", axis_codes[a] | 0x20, "=", hotend_offset[e][a]); DEBUG_EOL(); } DEBUG_EOL(); diff --git a/Marlin/src/gcode/feature/camera/M240.cpp b/Marlin/src/gcode/feature/camera/M240.cpp index 3144126fe..6fb68d454 100644 --- a/Marlin/src/gcode/feature/camera/M240.cpp +++ b/Marlin/src/gcode/feature/camera/M240.cpp @@ -48,8 +48,8 @@ #if ENABLED(ADVANCED_PAUSE_FEATURE) do_pause_e_move(length, fr_mm_s); #else - current_position[E_AXIS] += length / planner.e_factor[active_extruder]; - planner.buffer_line(current_position, fr_mm_s, active_extruder); + current_position.e += length / planner.e_factor[active_extruder]; + line_to_current_position(fr_mm_s); #endif } } @@ -97,10 +97,10 @@ void GcodeSuite::M240() { if (axis_unhomed_error()) return; - const float old_pos[XYZ] = { - current_position[X_AXIS] + parser.linearval('A'), - current_position[Y_AXIS] + parser.linearval('B'), - current_position[Z_AXIS] + const xyz_pos_t old_pos = { + current_position.x + parser.linearval('A'), + current_position.y + parser.linearval('B'), + current_position.z }; #ifdef PHOTO_RETRACT_MM @@ -121,22 +121,22 @@ void GcodeSuite::M240() { feedRate_t fr_mm_s = MMM_TO_MMS(parser.linearval('F')); if (fr_mm_s) NOLESS(fr_mm_s, 10.0f); - constexpr float photo_position[XYZ] = PHOTO_POSITION; - float raw[XYZ] = { - parser.seenval('X') ? RAW_X_POSITION(parser.value_linear_units()) : photo_position[X_AXIS], - parser.seenval('Y') ? RAW_Y_POSITION(parser.value_linear_units()) : photo_position[Y_AXIS], - (parser.seenval('Z') ? parser.value_linear_units() : photo_position[Z_AXIS]) + current_position[Z_AXIS] + constexpr xyz_pos_t photo_position = PHOTO_POSITION; + xyz_pos_t raw = { + parser.seenval('X') ? RAW_X_POSITION(parser.value_linear_units()) : photo_position.x, + parser.seenval('Y') ? RAW_Y_POSITION(parser.value_linear_units()) : photo_position.y, + (parser.seenval('Z') ? parser.value_linear_units() : photo_position.z) + current_position.z }; apply_motion_limits(raw); do_blocking_move_to(raw, fr_mm_s); #ifdef PHOTO_SWITCH_POSITION - constexpr float photo_switch_position[2] = PHOTO_SWITCH_POSITION; - const float sraw[] = { - parser.seenval('I') ? RAW_X_POSITION(parser.value_linear_units()) : photo_switch_position[X_AXIS], - parser.seenval('J') ? RAW_Y_POSITION(parser.value_linear_units()) : photo_switch_position[Y_AXIS] + constexpr xy_pos_t photo_switch_position = PHOTO_SWITCH_POSITION; + const xy_pos_t sraw = { + parser.seenval('I') ? RAW_X_POSITION(parser.value_linear_units()) : photo_switch_position.x, + parser.seenval('J') ? RAW_Y_POSITION(parser.value_linear_units()) : photo_switch_position.y }; - do_blocking_move_to_xy(sraw[X_AXIS], sraw[Y_AXIS], get_homing_bump_feedrate(X_AXIS)); + do_blocking_move_to_xy(sraw, get_homing_bump_feedrate(X_AXIS)); #if PHOTO_SWITCH_MS > 0 safe_delay(parser.intval('D', PHOTO_SWITCH_MS)); #endif diff --git a/Marlin/src/gcode/feature/pause/M125.cpp b/Marlin/src/gcode/feature/pause/M125.cpp index 86e8f61c1..22aaf2c44 100644 --- a/Marlin/src/gcode/feature/pause/M125.cpp +++ b/Marlin/src/gcode/feature/pause/M125.cpp @@ -58,7 +58,7 @@ void GcodeSuite::M125() { #endif ); - point_t park_point = NOZZLE_PARK_POINT; + xyz_pos_t park_point = NOZZLE_PARK_POINT; // Move XY axes to filament change position or given position if (parser.seenval('X')) park_point.x = RAW_X_POSITION(parser.linearval('X')); @@ -68,8 +68,7 @@ void GcodeSuite::M125() { if (parser.seenval('Z')) park_point.z = parser.linearval('Z'); #if HAS_HOTEND_OFFSET && NONE(DUAL_X_CARRIAGE, DELTA) - park_point.x += hotend_offset[X_AXIS][active_extruder]; - park_point.y += hotend_offset[Y_AXIS][active_extruder]; + park_point += hotend_offset[active_extruder]; #endif #if ENABLED(SDSUPPORT) diff --git a/Marlin/src/gcode/feature/pause/M600.cpp b/Marlin/src/gcode/feature/pause/M600.cpp index f2ade740b..4056a398e 100644 --- a/Marlin/src/gcode/feature/pause/M600.cpp +++ b/Marlin/src/gcode/feature/pause/M600.cpp @@ -60,7 +60,6 @@ * Default values are used for omitted arguments. */ void GcodeSuite::M600() { - point_t park_point = NOZZLE_PARK_POINT; #if ENABLED(MIXING_EXTRUDER) const int8_t target_e_stepper = get_target_e_stepper_from_command(); @@ -119,6 +118,8 @@ void GcodeSuite::M600() { #endif ); + xyz_pos_t park_point NOZZLE_PARK_POINT; + // Lift Z axis if (parser.seenval('Z')) park_point.z = parser.linearval('Z'); @@ -127,8 +128,7 @@ void GcodeSuite::M600() { if (parser.seenval('Y')) park_point.y = parser.linearval('Y'); #if HAS_HOTEND_OFFSET && NONE(DUAL_X_CARRIAGE, DELTA) - park_point.x += hotend_offset[X_AXIS][active_extruder]; - park_point.y += hotend_offset[Y_AXIS][active_extruder]; + park_point += hotend_offset[active_extruder]; #endif #if ENABLED(MMU2_MENUS) diff --git a/Marlin/src/gcode/feature/pause/M701_M702.cpp b/Marlin/src/gcode/feature/pause/M701_M702.cpp index 6add2ebfa..80a7f76d9 100644 --- a/Marlin/src/gcode/feature/pause/M701_M702.cpp +++ b/Marlin/src/gcode/feature/pause/M701_M702.cpp @@ -28,7 +28,6 @@ #include "../../../Marlin.h" #include "../../../module/motion.h" #include "../../../module/temperature.h" -#include "../../../libs/point_t.h" #if EXTRUDERS > 1 #include "../../../module/tool_change.h" @@ -57,7 +56,7 @@ * Default values are used for omitted arguments. */ void GcodeSuite::M701() { - point_t park_point = NOZZLE_PARK_POINT; + xyz_pos_t park_point = NOZZLE_PARK_POINT; #if ENABLED(NO_MOTION_BEFORE_HOMING) // Don't raise Z if the machine isn't homed @@ -97,7 +96,7 @@ void GcodeSuite::M701() { // Lift Z axis if (park_point.z > 0) - do_blocking_move_to_z(_MIN(current_position[Z_AXIS] + park_point.z, Z_MAX_POS), feedRate_t(NOZZLE_PARK_Z_FEEDRATE)); + do_blocking_move_to_z(_MIN(current_position.z + park_point.z, Z_MAX_POS), feedRate_t(NOZZLE_PARK_Z_FEEDRATE)); // Load filament #if ENABLED(PRUSA_MMU2) @@ -116,7 +115,7 @@ void GcodeSuite::M701() { // Restore Z axis if (park_point.z > 0) - do_blocking_move_to_z(_MAX(current_position[Z_AXIS] - park_point.z, 0), feedRate_t(NOZZLE_PARK_Z_FEEDRATE)); + do_blocking_move_to_z(_MAX(current_position.z - park_point.z, 0), feedRate_t(NOZZLE_PARK_Z_FEEDRATE)); #if EXTRUDERS > 1 && DISABLED(PRUSA_MMU2) // Restore toolhead if it was changed @@ -146,7 +145,7 @@ void GcodeSuite::M701() { * Default values are used for omitted arguments. */ void GcodeSuite::M702() { - point_t park_point = NOZZLE_PARK_POINT; + xyz_pos_t park_point = NOZZLE_PARK_POINT; #if ENABLED(NO_MOTION_BEFORE_HOMING) // Don't raise Z if the machine isn't homed @@ -196,7 +195,7 @@ void GcodeSuite::M702() { // Lift Z axis if (park_point.z > 0) - do_blocking_move_to_z(_MIN(current_position[Z_AXIS] + park_point.z, Z_MAX_POS), feedRate_t(NOZZLE_PARK_Z_FEEDRATE)); + do_blocking_move_to_z(_MIN(current_position.z + park_point.z, Z_MAX_POS), feedRate_t(NOZZLE_PARK_Z_FEEDRATE)); // Unload filament #if ENABLED(PRUSA_MMU2) @@ -226,7 +225,7 @@ void GcodeSuite::M702() { // Restore Z axis if (park_point.z > 0) - do_blocking_move_to_z(_MAX(current_position[Z_AXIS] - park_point.z, 0), feedRate_t(NOZZLE_PARK_Z_FEEDRATE)); + do_blocking_move_to_z(_MAX(current_position.z - park_point.z, 0), feedRate_t(NOZZLE_PARK_Z_FEEDRATE)); #if EXTRUDERS > 1 && DISABLED(PRUSA_MMU2) // Restore toolhead if it was changed diff --git a/Marlin/src/gcode/feature/trinamic/M122.cpp b/Marlin/src/gcode/feature/trinamic/M122.cpp index bbbe86bdb..a7e6d6517 100644 --- a/Marlin/src/gcode/feature/trinamic/M122.cpp +++ b/Marlin/src/gcode/feature/trinamic/M122.cpp @@ -31,8 +31,8 @@ * M122: Debug TMC drivers */ void GcodeSuite::M122() { - bool print_axis[XYZE] = { false, false, false, false }, - print_all = true; + xyze_bool_t print_axis = { false, false, false, false }; + bool print_all = true; LOOP_XYZE(i) if (parser.seen(axis_codes[i])) { print_axis[i] = true; print_all = false; } if (print_all) LOOP_XYZE(i) print_axis[i] = true; @@ -45,12 +45,12 @@ void GcodeSuite::M122() { #endif if (parser.seen('V')) - tmc_get_registers(print_axis[X_AXIS], print_axis[Y_AXIS], print_axis[Z_AXIS], print_axis[E_AXIS]); + tmc_get_registers(print_axis.x, print_axis.y, print_axis.z, print_axis.e); else - tmc_report_all(print_axis[X_AXIS], print_axis[Y_AXIS], print_axis[Z_AXIS], print_axis[E_AXIS]); + tmc_report_all(print_axis.x, print_axis.y, print_axis.z, print_axis.e); #endif - test_tmc_connection(print_axis[X_AXIS], print_axis[Y_AXIS], print_axis[Z_AXIS], print_axis[E_AXIS]); + test_tmc_connection(print_axis.x, print_axis.y, print_axis.z, print_axis.e); } #endif // HAS_TRINAMIC diff --git a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp index 27a0be9a6..feb891544 100644 --- a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp +++ b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp @@ -104,25 +104,25 @@ */ void GcodeSuite::M912() { #if M91x_SOME_X - const bool hasX = parser.seen(axis_codes[X_AXIS]); + const bool hasX = parser.seen(axis_codes.x); #else constexpr bool hasX = false; #endif #if M91x_SOME_Y - const bool hasY = parser.seen(axis_codes[Y_AXIS]); + const bool hasY = parser.seen(axis_codes.y); #else constexpr bool hasY = false; #endif #if M91x_SOME_Z - const bool hasZ = parser.seen(axis_codes[Z_AXIS]); + const bool hasZ = parser.seen(axis_codes.z); #else constexpr bool hasZ = false; #endif #if M91x_SOME_E - const bool hasE = parser.seen(axis_codes[E_AXIS]); + const bool hasE = parser.seen(axis_codes.e); #else constexpr bool hasE = false; #endif @@ -130,7 +130,7 @@ const bool hasNone = !hasX && !hasY && !hasZ && !hasE; #if M91x_SOME_X - const int8_t xval = int8_t(parser.byteval(axis_codes[X_AXIS], 0xFF)); + const int8_t xval = int8_t(parser.byteval(axis_codes.x, 0xFF)); #if M91x_USE(X) if (hasNone || xval == 1 || (hasX && xval < 0)) tmc_clear_otpw(stepperX); #endif @@ -140,7 +140,7 @@ #endif #if M91x_SOME_Y - const int8_t yval = int8_t(parser.byteval(axis_codes[Y_AXIS], 0xFF)); + const int8_t yval = int8_t(parser.byteval(axis_codes.y, 0xFF)); #if M91x_USE(Y) if (hasNone || yval == 1 || (hasY && yval < 0)) tmc_clear_otpw(stepperY); #endif @@ -150,7 +150,7 @@ #endif #if M91x_SOME_Z - const int8_t zval = int8_t(parser.byteval(axis_codes[Z_AXIS], 0xFF)); + const int8_t zval = int8_t(parser.byteval(axis_codes.z, 0xFF)); #if M91x_USE(Z) if (hasNone || zval == 1 || (hasZ && zval < 0)) tmc_clear_otpw(stepperZ); #endif @@ -163,7 +163,7 @@ #endif #if M91x_SOME_E - const int8_t eval = int8_t(parser.byteval(axis_codes[E_AXIS], 0xFF)); + const int8_t eval = int8_t(parser.byteval(axis_codes.e, 0xFF)); #if M91x_USE_E(0) if (hasNone || eval == 0 || (hasE && eval < 0)) tmc_clear_otpw(stepperE0); #endif diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index f542f842c..32885af6c 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -49,12 +49,13 @@ GcodeSuite gcode; millis_t GcodeSuite::previous_move_ms; -static constexpr bool ar_init[XYZE] = AXIS_RELATIVE_MODES; +// Relative motion mode for each logical axis +static constexpr xyze_bool_t ar_init = AXIS_RELATIVE_MODES; uint8_t GcodeSuite::axis_relative = ( - (ar_init[X_AXIS] ? _BV(REL_X) : 0) - | (ar_init[Y_AXIS] ? _BV(REL_Y) : 0) - | (ar_init[Z_AXIS] ? _BV(REL_Z) : 0) - | (ar_init[E_AXIS] ? _BV(REL_E) : 0) + (ar_init.x ? _BV(REL_X) : 0) + | (ar_init.y ? _BV(REL_Y) : 0) + | (ar_init.z ? _BV(REL_Z) : 0) + | (ar_init.e ? _BV(REL_E) : 0) ); #if ENABLED(HOST_KEEPALIVE_FEATURE) @@ -68,7 +69,7 @@ uint8_t GcodeSuite::axis_relative = ( #if ENABLED(CNC_COORDINATE_SYSTEMS) int8_t GcodeSuite::active_coordinate_system = -1; // machine space - float GcodeSuite::coordinate_system[MAX_COORDINATE_SYSTEMS][XYZ]; + xyz_pos_t GcodeSuite::coordinate_system[MAX_COORDINATE_SYSTEMS]; #endif /** @@ -112,7 +113,7 @@ int8_t GcodeSuite::get_target_e_stepper_from_command() { * - Set the feedrate, if included */ void GcodeSuite::get_destination_from_command() { - bool seen[XYZE] = { false, false, false, false }; + xyze_bool_t seen = { false, false, false, false }; LOOP_XYZE(i) { if ( (seen[i] = parser.seenval(axis_codes[i])) ) { const float v = parser.value_axis_units((AxisEnum)i); @@ -124,7 +125,7 @@ void GcodeSuite::get_destination_from_command() { #if ENABLED(POWER_LOSS_RECOVERY) && !PIN_EXISTS(POWER_LOSS) // Only update power loss recovery on moves with E - if (recovery.enabled && IS_SD_PRINTING() && seen[E_AXIS] && (seen[X_AXIS] || seen[Y_AXIS])) + if (recovery.enabled && IS_SD_PRINTING() && seen.e && (seen.x || seen.y)) recovery.save(); #endif @@ -133,7 +134,7 @@ void GcodeSuite::get_destination_from_command() { #if ENABLED(PRINTCOUNTER) if (!DEBUGGING(DRYRUN)) - print_job_timer.incFilamentUsed(destination[E_AXIS] - current_position[E_AXIS]); + print_job_timer.incFilamentUsed(destination.e - current_position.e); #endif // Get ABCDHI mixing factors diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index f871d6d21..619f50b61 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -321,7 +321,7 @@ public: #define MAX_COORDINATE_SYSTEMS 9 #if ENABLED(CNC_COORDINATE_SYSTEMS) static int8_t active_coordinate_system; - static float coordinate_system[MAX_COORDINATE_SYSTEMS][XYZ]; + static xyz_pos_t coordinate_system[MAX_COORDINATE_SYSTEMS]; static bool select_coordinate_system(const int8_t _new); #endif diff --git a/Marlin/src/gcode/geometry/G53-G59.cpp b/Marlin/src/gcode/geometry/G53-G59.cpp index 88914ccff..38f72ae62 100644 --- a/Marlin/src/gcode/geometry/G53-G59.cpp +++ b/Marlin/src/gcode/geometry/G53-G59.cpp @@ -36,9 +36,9 @@ bool GcodeSuite::select_coordinate_system(const int8_t _new) { if (active_coordinate_system == _new) return false; active_coordinate_system = _new; - float new_offset[XYZ] = { 0 }; + xyz_float_t new_offset{0}; if (WITHIN(_new, 0, MAX_COORDINATE_SYSTEMS - 1)) - COPY(new_offset, coordinate_system[_new]); + new_offset = coordinate_system[_new]; LOOP_XYZ(i) { if (position_shift[i] != new_offset[i]) { position_shift[i] = new_offset[i]; diff --git a/Marlin/src/gcode/geometry/G92.cpp b/Marlin/src/gcode/geometry/G92.cpp index 0ecf43e58..65ad06fe2 100644 --- a/Marlin/src/gcode/geometry/G92.cpp +++ b/Marlin/src/gcode/geometry/G92.cpp @@ -86,7 +86,7 @@ void GcodeSuite::G92() { #elif HAS_POSITION_SHIFT if (i == E_AXIS) { didE = true; - current_position[E_AXIS] = v; // When using coordinate spaces, only E is set directly + current_position.e = v; // When using coordinate spaces, only E is set directly } else { position_shift[i] += d; // Other axes simply offset the coordinate space @@ -102,7 +102,7 @@ void GcodeSuite::G92() { #if ENABLED(CNC_COORDINATE_SYSTEMS) // Apply workspace offset to the active coordinate system if (WITHIN(active_coordinate_system, 0, MAX_COORDINATE_SYSTEMS - 1)) - COPY(coordinate_system[active_coordinate_system], position_shift); + coordinate_system[active_coordinate_system] = position_shift; #endif if (didXYZ) sync_plan_position(); diff --git a/Marlin/src/gcode/geometry/M206_M428.cpp b/Marlin/src/gcode/geometry/M206_M428.cpp index f2d166e0a..e17f41f83 100644 --- a/Marlin/src/gcode/geometry/M206_M428.cpp +++ b/Marlin/src/gcode/geometry/M206_M428.cpp @@ -63,7 +63,7 @@ void GcodeSuite::M206() { void GcodeSuite::M428() { if (axis_unhomed_error()) return; - float diff[XYZ]; + xyz_float_t diff; LOOP_XYZ(i) { diff[i] = base_home_pos((AxisEnum)i) - current_position[i]; if (!WITHIN(diff[i], -20, 20) && home_dir((AxisEnum)i) > 0) diff --git a/Marlin/src/gcode/host/M114.cpp b/Marlin/src/gcode/host/M114.cpp index c10b58f70..8b65f2983 100644 --- a/Marlin/src/gcode/host/M114.cpp +++ b/Marlin/src/gcode/host/M114.cpp @@ -36,7 +36,7 @@ #include "../../core/debug_out.h" #endif - void report_xyze(const float pos[], const uint8_t n = 4, const uint8_t precision = 3) { + void report_xyze(const xyze_pos_t &pos, const uint8_t n=4, const uint8_t precision=3) { char str[12]; for (uint8_t a = 0; a < n; a++) { SERIAL_CHAR(' '); @@ -47,22 +47,27 @@ SERIAL_EOL(); } - inline void report_xyz(const float pos[]) { report_xyze(pos, 3); } + void report_xyz(const xyz_pos_t &pos, const uint8_t precision=3) { + char str[12]; + for (uint8_t a = X_AXIS; a <= Z_AXIS; a++) { + SERIAL_CHAR(' '); + SERIAL_CHAR(axis_codes[a]); + SERIAL_CHAR(':'); + SERIAL_ECHO(dtostrf(pos[a], 1, precision, str)); + } + SERIAL_EOL(); + } + inline void report_xyz(const xyze_pos_t &pos) { report_xyze(pos, 3); } void report_current_position_detail() { SERIAL_ECHOPGM("\nLogical:"); - const float logical[XYZ] = { - LOGICAL_X_POSITION(current_position[X_AXIS]), - LOGICAL_Y_POSITION(current_position[Y_AXIS]), - LOGICAL_Z_POSITION(current_position[Z_AXIS]) - }; - report_xyz(logical); + report_xyz(current_position.asLogical()); SERIAL_ECHOPGM("Raw: "); report_xyz(current_position); - float leveled[XYZ] = { current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS] }; + xyze_pos_t leveled = current_position; #if HAS_LEVELING SERIAL_ECHOPGM("Leveled:"); @@ -70,7 +75,7 @@ report_xyz(leveled); SERIAL_ECHOPGM("UnLevel:"); - float unleveled[XYZ] = { leveled[X_AXIS], leveled[Y_AXIS], leveled[Z_AXIS] }; + xyze_pos_t unleveled = leveled; planner.unapply_leveling(unleveled); report_xyz(unleveled); #endif @@ -153,7 +158,7 @@ SERIAL_EOL(); #if IS_SCARA - const float deg[XYZ] = { + const xy_float_t deg = { planner.get_axis_position_degrees(A_AXIS), planner.get_axis_position_degrees(B_AXIS) }; @@ -162,17 +167,12 @@ #endif SERIAL_ECHOPGM("FromStp:"); - get_cartesian_from_steppers(); // writes cartes[XYZ] (with forward kinematics) - const float from_steppers[XYZE] = { cartes[X_AXIS], cartes[Y_AXIS], cartes[Z_AXIS], planner.get_axis_position_mm(E_AXIS) }; + get_cartesian_from_steppers(); // writes 'cartes' (with forward kinematics) + xyze_pos_t from_steppers = { cartes.x, cartes.y, cartes.z, planner.get_axis_position_mm(E_AXIS) }; report_xyze(from_steppers); - const float diff[XYZE] = { - from_steppers[X_AXIS] - leveled[X_AXIS], - from_steppers[Y_AXIS] - leveled[Y_AXIS], - from_steppers[Z_AXIS] - leveled[Z_AXIS], - from_steppers[E_AXIS] - current_position[E_AXIS] - }; - SERIAL_ECHOPGM("Differ: "); + const xyze_float_t diff = from_steppers - leveled; + SERIAL_ECHOPGM("Diff: "); report_xyze(diff); } diff --git a/Marlin/src/gcode/motion/G0_G1.cpp b/Marlin/src/gcode/motion/G0_G1.cpp index fed70f553..36bc29026 100644 --- a/Marlin/src/gcode/motion/G0_G1.cpp +++ b/Marlin/src/gcode/motion/G0_G1.cpp @@ -35,7 +35,7 @@ #include "../../module/stepper.h" #endif -extern float destination[XYZE]; +extern xyze_pos_t destination; #if ENABLED(VARIABLE_G0_FEEDRATE) feedRate_t fast_move_feedrate = MMM_TO_MMS(G0_FEEDRATE); @@ -87,12 +87,12 @@ void GcodeSuite::G0_G1( if (MIN_AUTORETRACT <= MAX_AUTORETRACT) { // When M209 Autoretract is enabled, convert E-only moves to firmware retract/recover moves if (fwretract.autoretract_enabled && parser.seen('E') && !(parser.seen('X') || parser.seen('Y') || parser.seen('Z'))) { - const float echange = destination[E_AXIS] - current_position[E_AXIS]; + const float echange = destination.e - current_position.e; // Is this a retract or recover move? if (WITHIN(ABS(echange), MIN_AUTORETRACT, MAX_AUTORETRACT) && fwretract.retracted[active_extruder] == (echange > 0.0)) { - current_position[E_AXIS] = destination[E_AXIS]; // Hide a G1-based retract/recover from calculations - sync_plan_position_e(); // AND from the planner - return fwretract.retract(echange < 0.0); // Firmware-based retract/recover (double-retract ignored) + current_position.e = destination.e; // Hide a G1-based retract/recover from calculations + sync_plan_position_e(); // AND from the planner + return fwretract.retract(echange < 0.0); // Firmware-based retract/recover (double-retract ignored) } } } diff --git a/Marlin/src/gcode/motion/G2_G3.cpp b/Marlin/src/gcode/motion/G2_G3.cpp index 2a713a9f4..e856afff1 100644 --- a/Marlin/src/gcode/motion/G2_G3.cpp +++ b/Marlin/src/gcode/motion/G2_G3.cpp @@ -50,9 +50,9 @@ * options for G2/G3 arc generation. In future these options may be GCode tunable. */ void plan_arc( - const float (&cart)[XYZE], // Destination position - const float (&offset)[2], // Center of rotation relative to current_position - const uint8_t clockwise // Clockwise? + const xyze_pos_t &cart, // Destination position + const ab_float_t &offset, // Center of rotation relative to current_position + const uint8_t clockwise // Clockwise? ) { #if ENABLED(CNC_WORKSPACE_PLANES) AxisEnum p_axis, q_axis, l_axis; @@ -67,21 +67,21 @@ void plan_arc( #endif // Radius vector from center to current location - float r_P = -offset[0], r_Q = -offset[1]; + ab_float_t rvec = -offset; - const float radius = HYPOT(r_P, r_Q), + const float radius = HYPOT(rvec.a, rvec.b), #if ENABLED(AUTO_BED_LEVELING_UBL) start_L = current_position[l_axis], #endif - center_P = current_position[p_axis] - r_P, - center_Q = current_position[q_axis] - r_Q, + center_P = current_position[p_axis] - rvec.a, + center_Q = current_position[q_axis] - rvec.b, rt_X = cart[p_axis] - center_P, rt_Y = cart[q_axis] - center_Q, linear_travel = cart[l_axis] - current_position[l_axis], - extruder_travel = cart[E_AXIS] - current_position[E_AXIS]; + extruder_travel = cart.e - current_position.e; // CCW angle of rotation between position and target from the circle center. Only one atan2() trig computation required. - float angular_travel = ATAN2(r_P * rt_Y - r_Q * rt_X, r_P * rt_X + r_Q * rt_Y); + float angular_travel = ATAN2(rvec.a * rt_Y - rvec.b * rt_X, rvec.a * rt_X + rvec.b * rt_Y); if (angular_travel < 0) angular_travel += RADIANS(360); #ifdef MIN_ARC_SEGMENTS uint16_t min_segments = CEIL((MIN_ARC_SEGMENTS) * (angular_travel / RADIANS(360))); @@ -133,7 +133,7 @@ void plan_arc( * This is important when there are successive arc motions. */ // Vector rotation matrix values - float raw[XYZE]; + xyze_pos_t raw; const float theta_per_segment = angular_travel / segments, linear_per_segment = linear_travel / segments, extruder_per_segment = extruder_travel / segments, @@ -144,7 +144,7 @@ void plan_arc( raw[l_axis] = current_position[l_axis]; // Initialize the extruder axis - raw[E_AXIS] = current_position[E_AXIS]; + raw.e = current_position.e; const feedRate_t scaled_fr_mm_s = MMS_SCALED(feedrate_mm_s); @@ -168,10 +168,10 @@ void plan_arc( #if N_ARC_CORRECTION > 1 if (--arc_recalc_count) { - // Apply vector rotation matrix to previous r_P / 1 - const float r_new_Y = r_P * sin_T + r_Q * cos_T; - r_P = r_P * cos_T - r_Q * sin_T; - r_Q = r_new_Y; + // Apply vector rotation matrix to previous rvec.a / 1 + const float r_new_Y = rvec.a * sin_T + rvec.b * cos_T; + rvec.a = rvec.a * cos_T - rvec.b * sin_T; + rvec.b = r_new_Y; } else #endif @@ -185,20 +185,20 @@ void plan_arc( // To reduce stuttering, the sin and cos could be computed at different times. // For now, compute both at the same time. const float cos_Ti = cos(i * theta_per_segment), sin_Ti = sin(i * theta_per_segment); - r_P = -offset[0] * cos_Ti + offset[1] * sin_Ti; - r_Q = -offset[0] * sin_Ti - offset[1] * cos_Ti; + rvec.a = -offset[0] * cos_Ti + offset[1] * sin_Ti; + rvec.b = -offset[0] * sin_Ti - offset[1] * cos_Ti; } // Update raw location - raw[p_axis] = center_P + r_P; - raw[q_axis] = center_Q + r_Q; + raw[p_axis] = center_P + rvec.a; + raw[q_axis] = center_Q + rvec.b; #if ENABLED(AUTO_BED_LEVELING_UBL) raw[l_axis] = start_L; UNUSED(linear_per_segment); #else raw[l_axis] += linear_per_segment; #endif - raw[E_AXIS] += extruder_per_segment; + raw.e += extruder_per_segment; apply_motion_limits(raw); @@ -215,7 +215,7 @@ void plan_arc( } // Ensure last segment arrives at target location. - COPY(raw, cart); + raw = cart; #if ENABLED(AUTO_BED_LEVELING_UBL) raw[l_axis] = start_L; #endif @@ -235,7 +235,7 @@ void plan_arc( #if ENABLED(AUTO_BED_LEVELING_UBL) raw[l_axis] = start_L; #endif - COPY(current_position, raw); + current_position = raw; } // plan_arc /** @@ -278,32 +278,27 @@ void GcodeSuite::G2_G3(const bool clockwise) { relative_mode = relative_mode_backup; #endif - float arc_offset[2] = { 0, 0 }; + ab_float_t arc_offset = { 0, 0 }; if (parser.seenval('R')) { const float r = parser.value_linear_units(); if (r) { - const float p1 = current_position[X_AXIS], q1 = current_position[Y_AXIS], - p2 = destination[X_AXIS], q2 = destination[Y_AXIS]; - if (p2 != p1 || q2 != q1) { - const float e = clockwise ^ (r < 0) ? -1 : 1, // clockwise -1/1, counterclockwise 1/-1 - dx = p2 - p1, dy = q2 - q1, // X and Y differences - d = HYPOT(dx, dy), // Linear distance between the points - dinv = 1/d, // Inverse of d - h = SQRT(sq(r) - sq(d * 0.5f)), // Distance to the arc pivot-point - mx = (p1 + p2) * 0.5f, my = (q1 + q2) * 0.5f,// Point between the two points - sx = -dy * dinv, sy = dx * dinv, // Slope of the perpendicular bisector - cx = mx + e * h * sx, cy = my + e * h * sy; // Pivot-point of the arc - arc_offset[0] = cx - p1; - arc_offset[1] = cy - q1; + const xy_pos_t p1 = current_position, p2 = destination; + if (p1 != p2) { + const xy_pos_t d = p2 - p1, m = (p1 + p2) * 0.5f; // XY distance and midpoint + const float e = clockwise ^ (r < 0) ? -1 : 1, // clockwise -1/1, counterclockwise 1/-1 + len = d.magnitude(), // Total move length + h = SQRT(sq(r) - sq(len * 0.5f)); // Distance to the arc pivot-point + const xy_pos_t s = { d.x, -d.y }; // Inverse Slope of the perpendicular bisector + arc_offset = m + s * RECIPROCAL(len) * e * h - p1; // The calculated offset } } } else { - if (parser.seenval('I')) arc_offset[0] = parser.value_linear_units(); - if (parser.seenval('J')) arc_offset[1] = parser.value_linear_units(); + if (parser.seenval('I')) arc_offset.a = parser.value_linear_units(); + if (parser.seenval('J')) arc_offset.b = parser.value_linear_units(); } - if (arc_offset[0] || arc_offset[1]) { + if (arc_offset) { #if ENABLED(ARC_P_CIRCLES) // P indicates number of circles to do diff --git a/Marlin/src/gcode/motion/G5.cpp b/Marlin/src/gcode/motion/G5.cpp index f392668ce..7125532e9 100644 --- a/Marlin/src/gcode/motion/G5.cpp +++ b/Marlin/src/gcode/motion/G5.cpp @@ -27,11 +27,6 @@ #include "../../module/motion.h" #include "../../module/planner_bezier.h" -void plan_cubic_move(const float (&cart)[XYZE], const float (&offset)[4]) { - cubic_b_spline(current_position, cart, offset, MMS_SCALED(feedrate_mm_s), active_extruder); - COPY(current_position, cart); -} - /** * Parameters interpreted according to: * http://linuxcnc.org/docs/2.6/html/gcode/parser.html#sec:G5-Cubic-Spline @@ -57,14 +52,13 @@ void GcodeSuite::G5() { get_destination_from_command(); - const float offset[4] = { - parser.linearval('I'), - parser.linearval('J'), - parser.linearval('P'), - parser.linearval('Q') + const xy_pos_t offsets[2] = { + { parser.linearval('I'), parser.linearval('J') }, + { parser.linearval('P'), parser.linearval('Q') } }; - plan_cubic_move(destination, offset); + cubic_b_spline(current_position, destination, offsets, MMS_SCALED(feedrate_mm_s), active_extruder); + current_position = destination; } } diff --git a/Marlin/src/gcode/motion/M290.cpp b/Marlin/src/gcode/motion/M290.cpp index 7763f965c..7bf274a18 100644 --- a/Marlin/src/gcode/motion/M290.cpp +++ b/Marlin/src/gcode/motion/M290.cpp @@ -40,21 +40,21 @@ #if ENABLED(BABYSTEP_ZPROBE_OFFSET) - FORCE_INLINE void mod_zprobe_zoffset(const float &offs) { + FORCE_INLINE void mod_probe_offset(const float &offs) { if (true #if ENABLED(BABYSTEP_HOTEND_Z_OFFSET) && active_extruder == 0 #endif ) { - probe_offset[Z_AXIS] += offs; + probe_offset.z += offs; SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR(MSG_PROBE_OFFSET MSG_Z ": ", probe_offset[Z_AXIS]); + SERIAL_ECHOLNPAIR(MSG_PROBE_OFFSET MSG_Z ": ", probe_offset.z); } else { #if ENABLED(BABYSTEP_HOTEND_Z_OFFSET) - hotend_offset[Z_AXIS][active_extruder] -= offs; + hotend_offset[active_extruder].z -= offs; SERIAL_ECHO_START(); - SERIAL_ECHOLNPAIR(MSG_PROBE_OFFSET MSG_Z ": ", hotend_offset[Z_AXIS][active_extruder]); + SERIAL_ECHOLNPAIR(MSG_PROBE_OFFSET MSG_Z ": ", hotend_offset[active_extruder].z); #endif } } @@ -81,7 +81,7 @@ void GcodeSuite::M290() { const float offs = constrain(parser.value_axis_units((AxisEnum)a), -2, 2); babystep.add_mm((AxisEnum)a, offs); #if ENABLED(BABYSTEP_ZPROBE_OFFSET) - if (a == Z_AXIS && (!parser.seen('P') || parser.value_bool())) mod_zprobe_zoffset(offs); + if (a == Z_AXIS && (!parser.seen('P') || parser.value_bool())) mod_probe_offset(offs); #endif } #else @@ -89,7 +89,7 @@ void GcodeSuite::M290() { const float offs = constrain(parser.value_axis_units(Z_AXIS), -2, 2); babystep.add_mm(Z_AXIS, offs); #if ENABLED(BABYSTEP_ZPROBE_OFFSET) - if (!parser.seen('P') || parser.value_bool()) mod_zprobe_zoffset(offs); + if (!parser.seen('P') || parser.value_bool()) mod_probe_offset(offs); #endif } #endif @@ -98,17 +98,17 @@ void GcodeSuite::M290() { SERIAL_ECHO_START(); #if ENABLED(BABYSTEP_ZPROBE_OFFSET) - SERIAL_ECHOLNPAIR(MSG_PROBE_OFFSET " " MSG_Z, probe_offset[Z_AXIS]); + SERIAL_ECHOLNPAIR(MSG_PROBE_OFFSET " " MSG_Z, probe_offset.z); #endif #if ENABLED(BABYSTEP_HOTEND_Z_OFFSET) { SERIAL_ECHOLNPAIR("Hotend ", int(active_extruder), "Offset" #if ENABLED(BABYSTEP_XY) - " X", hotend_offset[X_AXIS][active_extruder], - " Y", hotend_offset[Y_AXIS][active_extruder], + " X", hotend_offset[active_extruder].x, + " Y", hotend_offset[active_extruder].y, #endif - " Z", hotend_offset[Z_AXIS][active_extruder] + " Z", hotend_offset[active_extruder].z ); } #endif diff --git a/Marlin/src/gcode/probe/G30.cpp b/Marlin/src/gcode/probe/G30.cpp index 50d0ea6ae..e91e3e9d8 100644 --- a/Marlin/src/gcode/probe/G30.cpp +++ b/Marlin/src/gcode/probe/G30.cpp @@ -39,10 +39,10 @@ * E Engage the probe for each probe (default 1) */ void GcodeSuite::G30() { - const float xpos = parser.linearval('X', current_position[X_AXIS] + probe_offset[X_AXIS]), - ypos = parser.linearval('Y', current_position[Y_AXIS] + probe_offset[Y_AXIS]); + const xy_pos_t pos = { parser.linearval('X', current_position.x + probe_offset.x), + parser.linearval('Y', current_position.y + probe_offset.y) }; - if (!position_is_reachable_by_probe(xpos, ypos)) return; + if (!position_is_reachable_by_probe(pos)) return; // Disable leveling so the planner won't mess with us #if HAS_LEVELING @@ -52,10 +52,9 @@ void GcodeSuite::G30() { remember_feedrate_scaling_off(); const ProbePtRaise raise_after = parser.boolval('E', true) ? PROBE_PT_STOW : PROBE_PT_NONE; - const float measured_z = probe_at_point(xpos, ypos, raise_after, 1); - + const float measured_z = probe_at_point(pos, raise_after, 1); if (!isnan(measured_z)) - SERIAL_ECHOLNPAIR("Bed X: ", FIXFLOAT(xpos), " Y: ", FIXFLOAT(ypos), " Z: ", FIXFLOAT(measured_z)); + SERIAL_ECHOLNPAIR("Bed X: ", FIXFLOAT(pos.x), " Y: ", FIXFLOAT(pos.y), " Z: ", FIXFLOAT(measured_z)); restore_feedrate_and_scaling(); diff --git a/Marlin/src/gcode/probe/G38.cpp b/Marlin/src/gcode/probe/G38.cpp index 33f5611a4..cb298bccc 100644 --- a/Marlin/src/gcode/probe/G38.cpp +++ b/Marlin/src/gcode/probe/G38.cpp @@ -48,7 +48,7 @@ inline bool G38_run_probe() { #if MULTIPLE_PROBING > 1 // Get direction of move and retract - float retract_mm[XYZ]; + xyz_float_t retract_mm; LOOP_XYZ(i) { const float dist = destination[i] - current_position[i]; retract_mm[i] = ABS(dist) < G38_MINIMUM_MOVE ? 0 : home_bump_mm((AxisEnum)i) * (dist > 0 ? -1 : 1); @@ -75,8 +75,7 @@ inline bool G38_run_probe() { #if MULTIPLE_PROBING > 1 // Move away by the retract distance - set_destination_from_current(); - LOOP_XYZ(i) destination[i] += retract_mm[i]; + destination = current_position + retract_mm; endstops.enable(false); prepare_move_to_destination(); planner.synchronize(); @@ -84,7 +83,7 @@ inline bool G38_run_probe() { REMEMBER(fr, feedrate_mm_s, feedrate_mm_s * 0.25); // Bump the target more slowly - LOOP_XYZ(i) destination[i] -= retract_mm[i] * 2; + destination -= retract_mm * 2; G38_single_probe(move_value); #endif diff --git a/Marlin/src/gcode/probe/M851.cpp b/Marlin/src/gcode/probe/M851.cpp index eec6b2f25..19f96eecd 100644 --- a/Marlin/src/gcode/probe/M851.cpp +++ b/Marlin/src/gcode/probe/M851.cpp @@ -35,18 +35,18 @@ void GcodeSuite::M851() { // Show usage with no parameters if (!parser.seen("XYZ")) { - SERIAL_ECHOLNPAIR(MSG_PROBE_OFFSET " X", probe_offset[X_AXIS], " Y", probe_offset[Y_AXIS], " Z", probe_offset[Z_AXIS]); + SERIAL_ECHOLNPAIR(MSG_PROBE_OFFSET " X", probe_offset.x, " Y", probe_offset.y, " Z", probe_offset.z); return; } - float offs[XYZ] = { probe_offset[X_AXIS], probe_offset[Y_AXIS], probe_offset[Z_AXIS] }; + xyz_pos_t offs = probe_offset; bool ok = true; if (parser.seenval('X')) { const float x = parser.value_float(); if (WITHIN(x, -(X_BED_SIZE), X_BED_SIZE)) - offs[X_AXIS] = x; + offs.x = x; else { SERIAL_ECHOLNPAIR("?X out of range (-", int(X_BED_SIZE), " to ", int(X_BED_SIZE), ")"); ok = false; @@ -56,7 +56,7 @@ void GcodeSuite::M851() { if (parser.seenval('Y')) { const float y = parser.value_float(); if (WITHIN(y, -(Y_BED_SIZE), Y_BED_SIZE)) - offs[Y_AXIS] = y; + offs.y = y; else { SERIAL_ECHOLNPAIR("?Y out of range (-", int(Y_BED_SIZE), " to ", int(Y_BED_SIZE), ")"); ok = false; @@ -66,7 +66,7 @@ void GcodeSuite::M851() { if (parser.seenval('Z')) { const float z = parser.value_float(); if (WITHIN(z, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX)) - offs[Z_AXIS] = z; + offs.z = z; else { SERIAL_ECHOLNPAIR("?Z out of range (", int(Z_PROBE_OFFSET_RANGE_MIN), " to ", int(Z_PROBE_OFFSET_RANGE_MAX), ")"); ok = false; @@ -74,7 +74,7 @@ void GcodeSuite::M851() { } // Save the new offsets - if (ok) COPY(probe_offset, offs); + if (ok) probe_offset = offs; } #endif // HAS_BED_PROBE diff --git a/Marlin/src/gcode/scara/M360-M364.cpp b/Marlin/src/gcode/scara/M360-M364.cpp index 585c4d8c8..0e6f51b62 100644 --- a/Marlin/src/gcode/scara/M360-M364.cpp +++ b/Marlin/src/gcode/scara/M360-M364.cpp @@ -32,7 +32,7 @@ inline bool SCARA_move_to_cal(const uint8_t delta_a, const uint8_t delta_b) { if (IsRunning()) { forward_kinematics_SCARA(delta_a, delta_b); - do_blocking_move_to_xy(cartes[X_AXIS], cartes[Y_AXIS]); + do_blocking_move_to_xy(cartes); return true; } return false; diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index d5aae1e0f..8b7e393bd 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -1472,7 +1472,7 @@ #define _PROBE_RADIUS (DELTA_PRINTABLE_RADIUS - (MIN_PROBE_EDGE)) #ifndef DELTA_CALIBRATION_RADIUS #ifdef NOZZLE_TO_PROBE_OFFSET - #define DELTA_CALIBRATION_RADIUS (DELTA_PRINTABLE_RADIUS - _MAX(ABS(nozzle_to_probe_offset[X_AXIS]), ABS(nozzle_to_probe_offset[Y_AXIS]), ABS(MIN_PROBE_EDGE))) + #define DELTA_CALIBRATION_RADIUS (DELTA_PRINTABLE_RADIUS - _MAX(ABS(nozzle_to_probe_offset.x), ABS(nozzle_to_probe_offset.y), ABS(MIN_PROBE_EDGE))) #else #define DELTA_CALIBRATION_RADIUS _PROBE_RADIUS #endif @@ -1506,6 +1506,7 @@ #define PROBE_Y_MIN (Y_CENTER - (SCARA_PRINTABLE_RADIUS) + MIN_PROBE_EDGE_FRONT) #define PROBE_X_MAX (X_CENTER + SCARA_PRINTABLE_RADIUS - (MIN_PROBE_EDGE_RIGHT)) #define PROBE_Y_MAX (Y_CENTER + SCARA_PRINTABLE_RADIUS - (MIN_PROBE_EDGE_BACK)) + #endif #if ENABLED(SEGMENT_LEVELED_MOVES) && !defined(LEVELED_SEGMENT_LENGTH) @@ -1532,10 +1533,10 @@ #define _MESH_MAX_X (_MIN(X_MAX_BED - (MESH_INSET), X_MAX_POS)) #define _MESH_MAX_Y (_MIN(Y_MAX_BED - (MESH_INSET), Y_MAX_POS)) #else - #define _MESH_MIN_X (_MAX(X_MIN_BED + MESH_INSET, X_MIN_POS + nozzle_to_probe_offset[X_AXIS])) - #define _MESH_MIN_Y (_MAX(Y_MIN_BED + MESH_INSET, Y_MIN_POS + nozzle_to_probe_offset[Y_AXIS])) - #define _MESH_MAX_X (_MIN(X_MAX_BED - (MESH_INSET), X_MAX_POS + nozzle_to_probe_offset[X_AXIS])) - #define _MESH_MAX_Y (_MIN(Y_MAX_BED - (MESH_INSET), Y_MAX_POS + nozzle_to_probe_offset[Y_AXIS])) + #define _MESH_MIN_X (_MAX(X_MIN_BED + MESH_INSET, X_MIN_POS + nozzle_to_probe_offset.x)) + #define _MESH_MIN_Y (_MAX(Y_MIN_BED + MESH_INSET, Y_MIN_POS + nozzle_to_probe_offset.y)) + #define _MESH_MAX_X (_MIN(X_MAX_BED - (MESH_INSET), X_MAX_POS + nozzle_to_probe_offset.x)) + #define _MESH_MAX_Y (_MIN(Y_MAX_BED - (MESH_INSET), Y_MAX_POS + nozzle_to_probe_offset.y)) #endif #endif diff --git a/Marlin/src/inc/MarlinConfig.h b/Marlin/src/inc/MarlinConfig.h index bb974e64d..fc2686285 100644 --- a/Marlin/src/inc/MarlinConfig.h +++ b/Marlin/src/inc/MarlinConfig.h @@ -39,7 +39,7 @@ #include HAL_PATH(../HAL, inc/SanityCheck.h) // Include all core headers -#include "../core/enum.h" +#include "../core/types.h" #include "../core/language.h" #include "../core/utility.h" #include "../core/serial.h" diff --git a/Marlin/src/inc/MarlinConfigPre.h b/Marlin/src/inc/MarlinConfigPre.h index 96ee5d347..e34b70376 100644 --- a/Marlin/src/inc/MarlinConfigPre.h +++ b/Marlin/src/inc/MarlinConfigPre.h @@ -34,7 +34,6 @@ #include "../core/boards.h" #include "../core/macros.h" -#include "../core/millis_t.h" #include "Version.h" #include "../../Configuration.h" diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index bf76e5fe8..5b0c63021 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -402,6 +402,8 @@ #error "[XYZ]_PROBE_OFFSET_FROM_EXTRUDER is now NOZZLE_TO_PROBE_OFFSET. Please update your configuration." #elif defined(MIN_PROBE_X) || defined(MIN_PROBE_Y) || defined(MAX_PROBE_X) || defined(MAX_PROBE_Y) #error "(MIN|MAX)_PROBE_[XY] are now calculated at runtime. Please remove them from Configuration.h." +#elif defined(Z_STEPPER_ALIGN_X) || defined(Z_STEPPER_ALIGN_X) + #error "Z_STEPPER_ALIGN_X and Z_STEPPER_ALIGN_Y are now combined as Z_STEPPER_ALIGN_XY. Please update your Configuration_adv.h." #endif #define BOARD_MKS_13 -1000 @@ -2305,11 +2307,6 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #elif !HAS_BED_PROBE #error "Z_STEPPER_AUTO_ALIGN requires a Z-bed probe." #endif - constexpr float sanity_arr_z_align_x[] = Z_STEPPER_ALIGN_X, sanity_arr_z_align_y[] = Z_STEPPER_ALIGN_Y; - static_assert( - COUNT(sanity_arr_z_align_x) == Z_STEPPER_COUNT && COUNT(sanity_arr_z_align_y) == Z_STEPPER_COUNT, - "Z_STEPPER_ALIGN_[XY] settings require one element per Z stepper." - ); #endif #if ENABLED(PRINTCOUNTER) && DISABLED(EEPROM_SETTINGS) diff --git a/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp b/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp index 146563750..819a5c5bc 100644 --- a/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp +++ b/Marlin/src/lcd/HD44780/ultralcd_HD44780.cpp @@ -817,11 +817,10 @@ void MarlinUI::draw_status_screen() { #else - _draw_axis_value(X_AXIS, ftostr4sign(LOGICAL_X_POSITION(current_position[X_AXIS])), blink); - + xy_pos_t lpos = current_position; toLogical(lpos); + _draw_axis_value(X_AXIS, ftostr4sign(lpos.x), blink); lcd_put_wchar(' '); - - _draw_axis_value(Y_AXIS, ftostr4sign(LOGICAL_Y_POSITION(current_position[Y_AXIS])), blink); + _draw_axis_value(Y_AXIS, ftostr4sign(lpos.y), blink); #endif @@ -830,7 +829,7 @@ void MarlinUI::draw_status_screen() { #endif // LCD_WIDTH >= 20 lcd_moveto(LCD_WIDTH - 8, 1); - _draw_axis_value(Z_AXIS, ftostr52sp(LOGICAL_Z_POSITION(current_position[Z_AXIS])), blink); + _draw_axis_value(Z_AXIS, ftostr52sp(LOGICAL_Z_POSITION(current_position.z)), blink); #if HAS_LEVELING && !HAS_HEATED_BED lcd_put_wchar(planner.leveling_active || blink ? '_' : ' '); @@ -902,7 +901,7 @@ void MarlinUI::draw_status_screen() { // Z Coordinate // lcd_moveto(LCD_WIDTH - 9, 0); - _draw_axis_value(Z_AXIS, ftostr52sp(LOGICAL_Z_POSITION(current_position[Z_AXIS])), blink); + _draw_axis_value(Z_AXIS, ftostr52sp(LOGICAL_Z_POSITION(current_position.z)), blink); #if HAS_LEVELING && (HOTENDS > 1 || !HAS_HEATED_BED) lcd_put_wchar(LCD_WIDTH - 1, 0, planner.leveling_active || blink ? '_' : ' '); @@ -1189,10 +1188,9 @@ void MarlinUI::draw_status_screen() { * Show X and Y positions */ _XLABEL(_PLOT_X, 0); - lcd_put_u8str(ftostr52(LOGICAL_X_POSITION(pgm_read_float(&ubl._mesh_index_to_xpos[x_plot])))); - + lcd_put_u8str(ftostr52(LOGICAL_X_POSITION(ubl.mesh_index_to_xpos(x_plot)))); _YLABEL(_LCD_W_POS, 0); - lcd_put_u8str(ftostr52(LOGICAL_Y_POSITION(pgm_read_float(&ubl._mesh_index_to_ypos[y_plot])))); + lcd_put_u8str(ftostr52(LOGICAL_Y_POSITION(ubl.mesh_index_to_ypos(y_plot)))); lcd_moveto(_PLOT_X, 0); @@ -1395,9 +1393,9 @@ void MarlinUI::draw_status_screen() { * Show all values at right of screen */ _XLABEL(_LCD_W_POS, 1); - lcd_put_u8str(ftostr52(LOGICAL_X_POSITION(pgm_read_float(&ubl._mesh_index_to_xpos[x_plot])))); + lcd_put_u8str(ftostr52(LOGICAL_X_POSITION(ubl.mesh_index_to_xpos(x_plot)))); _YLABEL(_LCD_W_POS, 2); - lcd_put_u8str(ftostr52(LOGICAL_Y_POSITION(pgm_read_float(&ubl._mesh_index_to_ypos[y_plot])))); + lcd_put_u8str(ftostr52(LOGICAL_Y_POSITION(ubl.mesh_index_to_ypos(y_plot)))); /** * Show the location value diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index e9023515c..34d014008 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -345,9 +345,10 @@ void MarlinUI::draw_status_screen() { #endif heat_bits = new_bits; #endif - strcpy(xstring, ftostr4sign(LOGICAL_X_POSITION(current_position[X_AXIS]))); - strcpy(ystring, ftostr4sign(LOGICAL_Y_POSITION(current_position[Y_AXIS]))); - strcpy(zstring, ftostr52sp( LOGICAL_Z_POSITION(current_position[Z_AXIS]))); + const xyz_pos_t lpos = current_position.asLogical(); + strcpy(xstring, ftostr4sign(lpos.x)); + strcpy(ystring, ftostr4sign(lpos.y)); + strcpy(zstring, ftostr52sp( lpos.z)); #if ENABLED(FILAMENT_LCD_DISPLAY) strcpy(wstring, ftostr12ns(filwidth.measured_mm)); strcpy(mstring, i16tostr3(planner.volumetric_percent(parser.volumetric_enabled))); diff --git a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp index 660cf0767..5e73ba8bf 100644 --- a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp +++ b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp @@ -660,7 +660,7 @@ void ST7920_Lite_Status_Screen::draw_status_message() { #endif } -void ST7920_Lite_Status_Screen::draw_position(const float (&pos)[XYZE], const bool position_known) { +void ST7920_Lite_Status_Screen::draw_position(const xyz_pos_t &pos, const bool position_known) { char str[7]; set_ddram_address(DDRAM_LINE_4); begin_data(); @@ -669,13 +669,13 @@ void ST7920_Lite_Status_Screen::draw_position(const float (&pos)[XYZE], const bo const unsigned char alt_label = position_known ? 0 : (ui.get_blink() ? ' ' : 0); write_byte(alt_label ? alt_label : 'X'); - write_str(dtostrf(pos[X_AXIS], -4, 0, str), 4); + write_str(dtostrf(pos.x, -4, 0, str), 4); write_byte(alt_label ? alt_label : 'Y'); - write_str(dtostrf(pos[Y_AXIS], -4, 0, str), 4); + write_str(dtostrf(pos.y, -4, 0, str), 4); write_byte(alt_label ? alt_label : 'Z'); - write_str(dtostrf(pos[Z_AXIS], -5, 1, str), 5); + write_str(dtostrf(pos.z, -5, 1, str), 5); } bool ST7920_Lite_Status_Screen::indicators_changed() { @@ -750,8 +750,8 @@ void ST7920_Lite_Status_Screen::update_indicators(const bool forceUpdate) { } bool ST7920_Lite_Status_Screen::position_changed() { - const float x_pos = current_position[X_AXIS], y_pos = current_position[Y_AXIS], z_pos = current_position[Z_AXIS]; - const uint8_t checksum = uint8_t(x_pos) ^ uint8_t(y_pos) ^ uint8_t(z_pos); + const xyz_pos_t pos = current_position; + const uint8_t checksum = uint8_t(pos.x) ^ uint8_t(pos.y) ^ uint8_t(pos.z); static uint8_t last_checksum = 0, changed = last_checksum != checksum; if (changed) last_checksum = checksum; return changed; diff --git a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.h b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.h index 18a5ed77f..754c9933e 100644 --- a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.h +++ b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.h @@ -17,6 +17,7 @@ #include "../../HAL/shared/HAL_ST7920.h" +#include "../../core/types.h" #include "../../core/macros.h" #include "../../libs/duration_t.h" @@ -86,7 +87,7 @@ class ST7920_Lite_Status_Screen { static void draw_print_time(const duration_t &elapsed); static void draw_feedrate_percentage(const uint16_t percentage); static void draw_status_message(); - static void draw_position(const float (&pos)[XYZE], bool position_known = true); + static void draw_position(const xyz_pos_t &pos, bool position_known = true); static bool indicators_changed(); static bool position_changed(); diff --git a/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp b/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp index 7eb51eea4..7f9376fbc 100644 --- a/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp +++ b/Marlin/src/lcd/dogm/ultralcd_DOGM.cpp @@ -547,10 +547,12 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop // Show X and Y positions at top of screen u8g.setColorIndex(1); if (PAGE_UNDER(7)) { + const xy_pos_t pos = { ubl.mesh_index_to_xpos(x_plot), ubl.mesh_index_to_ypos(y_plot) }, + lpos = pos.asLogical(); lcd_put_u8str(5, 7, "X:"); - lcd_put_u8str(ftostr52(LOGICAL_X_POSITION(pgm_read_float(&ubl._mesh_index_to_xpos[x_plot])))); + lcd_put_u8str(ftostr52(lpos.x)); lcd_put_u8str(74, 7, "Y:"); - lcd_put_u8str(ftostr52(LOGICAL_Y_POSITION(pgm_read_float(&ubl._mesh_index_to_ypos[y_plot])))); + lcd_put_u8str(ftostr52(lpos.y)); } // Print plot position diff --git a/Marlin/src/lcd/extensible_ui/lib/dgus/DGUSDisplayDefinition.cpp b/Marlin/src/lcd/extensible_ui/lib/dgus/DGUSDisplayDefinition.cpp index 1ac5270c4..bc1296f2f 100644 --- a/Marlin/src/lcd/extensible_ui/lib/dgus/DGUSDisplayDefinition.cpp +++ b/Marlin/src/lcd/extensible_ui/lib/dgus/DGUSDisplayDefinition.cpp @@ -169,7 +169,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[0].celsius, nullptr, DGUSScreenVariableHandler::DGUSLCD_SendFloatAsLongValueToDisplay<0>), VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[0].target, DGUSScreenVariableHandler::HandleTemperatureChanged, &DGUSScreenVariableHandler::DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_Flowrate_E1, nullptr, DGUSScreenVariableHandler::HandleFlowRateChanged, &DGUSScreenVariableHandler::DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_EPos, &destination[3], nullptr, DGUSScreenVariableHandler::DGUSLCD_SendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_EPos, &destination.e, nullptr, DGUSScreenVariableHandler::DGUSLCD_SendFloatAsLongValueToDisplay<2>), VPHELPER(VP_MOVE_E1, nullptr, &DGUSScreenVariableHandler::HandleManualExtrude, nullptr), #endif #if HOTENDS >= 2 @@ -195,9 +195,9 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_Feedrate_Percentage, &feedrate_percentage, DGUSScreenVariableHandler::DGUSLCD_SetValueDirectly, &DGUSScreenVariableHandler::DGUSLCD_SendWordValueToDisplay ), // Position Data. - VPHELPER(VP_XPos, ¤t_position[0], nullptr, DGUSScreenVariableHandler::DGUSLCD_SendFloatAsLongValueToDisplay<2>), - VPHELPER(VP_YPos, ¤t_position[1], nullptr, DGUSScreenVariableHandler::DGUSLCD_SendFloatAsLongValueToDisplay<2>), - VPHELPER(VP_ZPos, ¤t_position[2], nullptr, DGUSScreenVariableHandler::DGUSLCD_SendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_XPos, ¤t_position.x, nullptr, DGUSScreenVariableHandler::DGUSLCD_SendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_YPos, ¤t_position.y, nullptr, DGUSScreenVariableHandler::DGUSLCD_SendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_ZPos, ¤t_position.z, nullptr, DGUSScreenVariableHandler::DGUSLCD_SendFloatAsLongValueToDisplay<2>), // Print Progress. VPHELPER(VP_PrintProgress_Percentage, &ui.progress_bar_percent, nullptr, DGUSScreenVariableHandler::DGUSLCD_SendWordValueToDisplay ), diff --git a/Marlin/src/lcd/extensible_ui/lib/lulzbot/screens/bio_status_screen.cpp b/Marlin/src/lcd/extensible_ui/lib/lulzbot/screens/bio_status_screen.cpp index 17d9eefbc..1efce50a1 100644 --- a/Marlin/src/lcd/extensible_ui/lib/lulzbot/screens/bio_status_screen.cpp +++ b/Marlin/src/lcd/extensible_ui/lib/lulzbot/screens/bio_status_screen.cpp @@ -258,22 +258,22 @@ bool StatusScreen::onTouchStart(uint8_t) { bool StatusScreen::onTouchEnd(uint8_t tag) { switch (tag) { - case 1: - case 2: - case 3: - case 4: + case 1: + case 2: + case 3: + case 4: case 12: if (!jog_xy) { jog_xy = true; injectCommands_P(PSTR("M17")); } - jog(0, 0, 0); + jog({ 0, 0, 0 }); break; - case 5: - case 6: - jog(0, 0, 0); + case 5: + case 6: + jog({ 0, 0, 0 }); break; - case 9: GOTO_SCREEN(FilesScreen); break; + case 9: GOTO_SCREEN(FilesScreen); break; case 10: GOTO_SCREEN(MainMenu); break; case 13: SpinnerDialogBox::enqueueAndWait_P(F("G112")); break; case 14: SpinnerDialogBox::enqueueAndWait_P(F("G28 Z")); break; @@ -291,14 +291,13 @@ bool StatusScreen::onTouchHeld(uint8_t tag) { if (tag >= 1 && tag <= 4 && !jog_xy) return false; const float s = min_speed + (fine_motion ? 0 : (max_speed - min_speed) * sq(increment)); switch (tag) { - case 1: jog(-s, 0, 0); break; - case 2: jog( s, 0, 0); break; - case 4: jog( 0, -s, 0); break; // NOTE: Y directions inverted because bed rather than needle moves - case 3: jog( 0, s, 0); break; - case 5: jog( 0, 0, -s); break; - case 6: jog( 0, 0, s); break; - case 7: - case 8: + case 1: jog({-s, 0, 0}); break; + case 2: jog({ s, 0, 0}); break; + case 4: jog({ 0, -s, 0}); break; // NOTE: Y directions inverted because bed rather than needle moves + case 3: jog({ 0, s, 0}); break; + case 5: jog({ 0, 0, -s}); break; + case 6: jog({ 0, 0, s}); break; + case 7: case 8: { if (ExtUI::isMoving()) return false; const feedRate_t feedrate = emin_speed + (fine_motion ? 0 : (emax_speed - emin_speed) * sq(increment)); diff --git a/Marlin/src/lcd/extensible_ui/lib/lulzbot/screens/change_filament_screen.cpp b/Marlin/src/lcd/extensible_ui/lib/lulzbot/screens/change_filament_screen.cpp index de63824f0..969257294 100644 --- a/Marlin/src/lcd/extensible_ui/lib/lulzbot/screens/change_filament_screen.cpp +++ b/Marlin/src/lcd/extensible_ui/lib/lulzbot/screens/change_filament_screen.cpp @@ -305,8 +305,8 @@ bool ChangeFilamentScreen::onTouchEnd(uint8_t tag) { bool ChangeFilamentScreen::onTouchHeld(uint8_t tag) { if (ExtUI::isMoving()) return false; // Don't allow moves to accumulate constexpr float increment = 1; - #define UI_INCREMENT_AXIS(axis) MoveAxisScreen::setManualFeedrate(axis, increment); UI_INCREMENT(AxisPosition_mm, axis); - #define UI_DECREMENT_AXIS(axis) MoveAxisScreen::setManualFeedrate(axis, increment); UI_DECREMENT(AxisPosition_mm, axis); + #define UI_INCREMENT_AXIS(axis) UI_INCREMENT(AxisPosition_mm, axis); + #define UI_DECREMENT_AXIS(axis) UI_DECREMENT(AxisPosition_mm, axis); switch (tag) { case 5: case 7: UI_DECREMENT_AXIS(getExtruder()); break; case 6: case 8: UI_INCREMENT_AXIS(getExtruder()); break; diff --git a/Marlin/src/lcd/extensible_ui/lib/lulzbot/screens/move_axis_screen.cpp b/Marlin/src/lcd/extensible_ui/lib/lulzbot/screens/move_axis_screen.cpp index 86032e856..620604323 100644 --- a/Marlin/src/lcd/extensible_ui/lib/lulzbot/screens/move_axis_screen.cpp +++ b/Marlin/src/lcd/extensible_ui/lib/lulzbot/screens/move_axis_screen.cpp @@ -110,8 +110,8 @@ float MoveAxisScreen::getManualFeedrate(uint8_t axis, float increment_mm) { // Compute feedrate so that the tool lags the adjuster when it is // being held down, this allows enough margin for the planner to // connect segments and even out the motion. - constexpr float manual_feedrate[XYZE] = MANUAL_FEEDRATE; - return min(manual_feedrate[axis] / 60.0f, abs(increment_mm * (TOUCH_REPEATS_PER_SECOND) * 0.80f)); + constexpr xyze_feedrate_t max_manual_feedrate = MANUAL_FEEDRATE; + return min(max_manual_feedrate[axis] / 60.0f, abs(increment_mm * (TOUCH_REPEATS_PER_SECOND) * 0.80f)); } void MoveAxisScreen::setManualFeedrate(ExtUI::axis_t axis, float increment_mm) { diff --git a/Marlin/src/lcd/extensible_ui/lib/lulzbot/screens/nudge_nozzle_screen.cpp b/Marlin/src/lcd/extensible_ui/lib/lulzbot/screens/nudge_nozzle_screen.cpp index 74e7c4504..069fea343 100644 --- a/Marlin/src/lcd/extensible_ui/lib/lulzbot/screens/nudge_nozzle_screen.cpp +++ b/Marlin/src/lcd/extensible_ui/lib/lulzbot/screens/nudge_nozzle_screen.cpp @@ -36,9 +36,8 @@ void NudgeNozzleScreen::onEntry() { #if EXTRUDERS > 1 screen_data.NudgeNozzleScreen.link_nozzles = true; #endif - LOOP_XYZ(i) { - screen_data.NudgeNozzleScreen.rel[i] = 0; - } + screen_data.NudgeNozzleScreen.rel.reset(); + BaseNumericAdjustmentScreen::onEntry(); } @@ -48,10 +47,10 @@ void NudgeNozzleScreen::onRedraw(draw_mode_t what) { w.heading( GET_TEXTF(NUDGE_NOZZLE)); #if ENABLED(BABYSTEP_XY) - w.color(x_axis).adjuster(2, GET_TEXTF(AXIS_X), screen_data.NudgeNozzleScreen.rel[0] / getAxisSteps_per_mm(X)); - w.color(y_axis).adjuster(4, GET_TEXTF(AXIS_Y), screen_data.NudgeNozzleScreen.rel[1] / getAxisSteps_per_mm(Y)); + w.color(x_axis).adjuster(2, GET_TEXTF(AXIS_X), screen_data.NudgeNozzleScreen.rel.x / getAxisSteps_per_mm(X)); + w.color(y_axis).adjuster(4, GET_TEXTF(AXIS_Y), screen_data.NudgeNozzleScreen.rel.y / getAxisSteps_per_mm(Y)); #endif - w.color(z_axis).adjuster(6, GET_TEXTF(AXIS_Z), screen_data.NudgeNozzleScreen.rel[2] / getAxisSteps_per_mm(Z)); + w.color(z_axis).adjuster(6, GET_TEXTF(AXIS_Z), screen_data.NudgeNozzleScreen.rel.z / getAxisSteps_per_mm(Z)); w.increments(); #if EXTRUDERS > 1 w.toggle (8, GET_TEXTF(ADJUST_BOTH_NOZZLES), screen_data.NudgeNozzleScreen.link_nozzles); @@ -90,12 +89,12 @@ bool NudgeNozzleScreen::onTouchHeld(uint8_t tag) { #endif int16_t steps; switch (tag) { - case 2: steps = mmToWholeSteps(inc, X); smartAdjustAxis_steps(-steps, X, link); screen_data.NudgeNozzleScreen.rel[0] -= steps; break; - case 3: steps = mmToWholeSteps(inc, X); smartAdjustAxis_steps( steps, X, link); screen_data.NudgeNozzleScreen.rel[0] += steps; break; - case 4: steps = mmToWholeSteps(inc, Y); smartAdjustAxis_steps(-steps, Y, link); screen_data.NudgeNozzleScreen.rel[1] -= steps; break; - case 5: steps = mmToWholeSteps(inc, Y); smartAdjustAxis_steps( steps, Y, link); screen_data.NudgeNozzleScreen.rel[1] += steps; break; - case 6: steps = mmToWholeSteps(inc, Z); smartAdjustAxis_steps(-steps, Z, link); screen_data.NudgeNozzleScreen.rel[2] -= steps; break; - case 7: steps = mmToWholeSteps(inc, Z); smartAdjustAxis_steps( steps, Z, link); screen_data.NudgeNozzleScreen.rel[2] += steps; break; + case 2: steps = mmToWholeSteps(inc, X); smartAdjustAxis_steps(-steps, X, link); screen_data.NudgeNozzleScreen.rel.x -= steps; break; + case 3: steps = mmToWholeSteps(inc, X); smartAdjustAxis_steps( steps, X, link); screen_data.NudgeNozzleScreen.rel.x += steps; break; + case 4: steps = mmToWholeSteps(inc, Y); smartAdjustAxis_steps(-steps, Y, link); screen_data.NudgeNozzleScreen.rel.y -= steps; break; + case 5: steps = mmToWholeSteps(inc, Y); smartAdjustAxis_steps( steps, Y, link); screen_data.NudgeNozzleScreen.rel.y += steps; break; + case 6: steps = mmToWholeSteps(inc, Z); smartAdjustAxis_steps(-steps, Z, link); screen_data.NudgeNozzleScreen.rel.z -= steps; break; + case 7: steps = mmToWholeSteps(inc, Z); smartAdjustAxis_steps( steps, Z, link); screen_data.NudgeNozzleScreen.rel.z += steps; break; #if EXTRUDERS > 1 case 8: screen_data.NudgeNozzleScreen.link_nozzles = !link; break; #endif diff --git a/Marlin/src/lcd/extensible_ui/lib/lulzbot/screens/screen_data.h b/Marlin/src/lcd/extensible_ui/lib/lulzbot/screens/screen_data.h index 65cb6e85d..adaccc8e5 100644 --- a/Marlin/src/lcd/extensible_ui/lib/lulzbot/screens/screen_data.h +++ b/Marlin/src/lcd/extensible_ui/lib/lulzbot/screens/screen_data.h @@ -65,7 +65,7 @@ union screen_data_t { #if ENABLED(BABYSTEPPING) struct { struct base_numeric_adjustment_t placeholder; - int16_t rel[XYZ]; + xyz_int_t rel; #if EXTRUDERS > 1 bool link_nozzles; #endif diff --git a/Marlin/src/lcd/extensible_ui/ui_api.cpp b/Marlin/src/lcd/extensible_ui/ui_api.cpp index fc6c47e26..2cbb0e082 100644 --- a/Marlin/src/lcd/extensible_ui/ui_api.cpp +++ b/Marlin/src/lcd/extensible_ui/ui_api.cpp @@ -204,33 +204,29 @@ namespace ExtUI { * The axis will continue to jog until this function is * called with all zeros. */ - void jog(float dx, float dy, float dz) { + void jog(const xyz_float_t &dir) { // The "destination" variable is used as a scratchpad in // Marlin by GCODE routines, but should remain untouched // during manual jogging, allowing us to reuse the space // for our direction vector. - destination[X] = dx; - destination[Y] = dy; - destination[Z] = dz; - flags.jogging = !NEAR_ZERO(dx) || !NEAR_ZERO(dy) || !NEAR_ZERO(dz); + destination = dir; + flags.jogging = !NEAR_ZERO(dir.x) || !NEAR_ZERO(dir.y) || !NEAR_ZERO(dir.z); } // Called by the polling routine in "joystick.cpp" - void _joystick_update(float (&norm_jog)[XYZ]) { + void _joystick_update(xyz_float_t &norm_jog) { if (flags.jogging) { #define OUT_OF_RANGE(VALUE) (VALUE < -1.0f || VALUE > 1.0f) - if (OUT_OF_RANGE(destination[X_AXIS]) || OUT_OF_RANGE(destination[Y_AXIS]) || OUT_OF_RANGE(destination[Z_AXIS])) { - // If destination[] on any axis is out of range, it + if (OUT_OF_RANGE(destination.x) || OUT_OF_RANGE(destination.y) || OUT_OF_RANGE(destination.z)) { + // If destination on any axis is out of range, it // probably means the UI forgot to stop jogging and - // ran GCODE that wrote a position to destination[]. + // ran GCODE that wrote a position to destination. // To prevent a disaster, stop jogging. flags.jogging = false; return; } - norm_jog[X_AXIS] = destination[X_AXIS]; - norm_jog[Y_AXIS] = destination[Y_AXIS]; - norm_jog[Z_AXIS] = destination[Z_AXIS]; + norm_jog = destination; } } #endif @@ -328,18 +324,16 @@ namespace ExtUI { float getAxisPosition_mm(const extruder_t extruder) { const extruder_t old_tool = getActiveTool(); setActiveTool(extruder, true); - const float pos = ( + const float epos = ( #if ENABLED(JOYSTICK) - flags.jogging ? destination[E_AXIS] : + flags.jogging ? destination.e : #endif - current_position[E_AXIS] + current_position.e ); setActiveTool(old_tool, true); - return pos; + return epos; } - constexpr feedRate_t manual_feedrate_mm_m[XYZE] = MANUAL_FEEDRATE; - void setAxisPosition_mm(const float position, const axis_t axis) { // Start with no limits to movement float min = current_position[axis] - 1000, @@ -350,26 +344,26 @@ namespace ExtUI { if (soft_endstops_enabled) switch (axis) { case X_AXIS: #if ENABLED(MIN_SOFTWARE_ENDSTOP_X) - min = soft_endstop[X_AXIS].min; + min = soft_endstop.min.x; #endif #if ENABLED(MAX_SOFTWARE_ENDSTOP_X) - max = soft_endstop[X_AXIS].max; + max = soft_endstop.max.x; #endif break; case Y_AXIS: #if ENABLED(MIN_SOFTWARE_ENDSTOP_Y) - min = soft_endstop[Y_AXIS].min; + min = soft_endstop.min.y; #endif #if ENABLED(MAX_SOFTWARE_ENDSTOP_Y) - max = soft_endstop[Y_AXIS].max; + max = soft_endstop.max.y; #endif break; case Z_AXIS: #if ENABLED(MIN_SOFTWARE_ENDSTOP_Z) - min = soft_endstop[Z_AXIS].min; + min = soft_endstop.min.z; #endif #if ENABLED(MAX_SOFTWARE_ENDSTOP_Z) - max = soft_endstop[Z_AXIS].max; + max = soft_endstop.max.z; #endif default: break; } @@ -391,8 +385,8 @@ namespace ExtUI { void setAxisPosition_mm(const float position, const extruder_t extruder) { setActiveTool(extruder, true); - current_position[E_AXIS] = position; - line_to_current_position(MMM_TO_MMS(manual_feedrate_mm_m[E_AXIS])); + current_position.e = position; + line_to_current_position(MMM_TO_MMS(manual_feedrate_mm_m.e)); } void setActiveTool(const extruder_t extruder, bool no_move) { @@ -652,7 +646,7 @@ namespace ExtUI { } float getAxisMaxJerk_mm_s(const extruder_t) { - return planner.max_jerk[E_AXIS]; + return planner.max_jerk.e; } void setAxisMaxJerk_mm_s(const float value, const axis_t axis) { @@ -660,7 +654,7 @@ namespace ExtUI { } void setAxisMaxJerk_mm_s(const float value, const extruder_t) { - planner.max_jerk[E_AXIS] = value; + planner.max_jerk.e = value; } #endif @@ -710,7 +704,7 @@ namespace ExtUI { #if EXTRUDERS > 1 && (linked_nozzles || active_extruder == 0) #endif - ) probe_offset[Z_AXIS] += mm; + ) probe_offset.z += mm; #else UNUSED(mm); #endif @@ -724,7 +718,7 @@ namespace ExtUI { if (!linked_nozzles) { HOTEND_LOOP() if (e != active_extruder) - hotend_offset[axis][e] += mm; + hotend_offset[e][axis] += mm; normalizeNozzleOffset(X); normalizeNozzleOffset(Y); @@ -748,7 +742,7 @@ namespace ExtUI { float getZOffset_mm() { #if HAS_BED_PROBE - return probe_offset[Z_AXIS]; + return probe_offset.z; #elif ENABLED(BABYSTEP_DISPLAY_TOTAL) return babystep.axis_total[BS_TOTAL_AXIS(Z_AXIS) + 1]; #else @@ -759,7 +753,7 @@ namespace ExtUI { void setZOffset_mm(const float value) { #if HAS_BED_PROBE if (WITHIN(value, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX)) - probe_offset[Z_AXIS] = value; + probe_offset.z = value; #elif ENABLED(BABYSTEP_DISPLAY_TOTAL) babystep.add_mm(Z_AXIS, (value - babystep.axis_total[BS_TOTAL_AXIS(Z_AXIS) + 1])); #else @@ -771,12 +765,12 @@ namespace ExtUI { float getNozzleOffset_mm(const axis_t axis, const extruder_t extruder) { if (extruder - E0 >= HOTENDS) return 0; - return hotend_offset[axis][extruder - E0]; + return hotend_offset[extruder - E0][axis]; } void setNozzleOffset_mm(const float value, const axis_t axis, const extruder_t extruder) { if (extruder - E0 >= HOTENDS) return; - hotend_offset[axis][extruder - E0] = value; + hotend_offset[extruder - E0][axis] = value; } /** @@ -785,8 +779,8 @@ namespace ExtUI { * user to edit the offset the first nozzle). */ void normalizeNozzleOffset(const axis_t axis) { - const float offs = hotend_offset[axis][0]; - HOTEND_LOOP() hotend_offset[axis][e] -= offs; + const float offs = hotend_offset[0][axis]; + HOTEND_LOOP() hotend_offset[e][axis] -= offs; } #endif // HAS_HOTEND_OFFSET @@ -820,10 +814,10 @@ namespace ExtUI { bool getMeshValid() { return leveling_is_valid(); } #if HAS_MESH bed_mesh_t& getMeshArray() { return Z_VALUES_ARR; } - float getMeshPoint(const uint8_t xpos, const uint8_t ypos) { return Z_VALUES(xpos,ypos); } - void setMeshPoint(const uint8_t xpos, const uint8_t ypos, const float zoff) { - if (WITHIN(xpos, 0, GRID_MAX_POINTS_X) && WITHIN(ypos, 0, GRID_MAX_POINTS_Y)) { - Z_VALUES(xpos, ypos) = zoff; + float getMeshPoint(const xy_uint8_t &pos) { return Z_VALUES(pos.x, pos.y); } + void setMeshPoint(const xy_uint8_t &pos, const float zoff) { + if (WITHIN(pos.x, 0, GRID_MAX_POINTS_X) && WITHIN(pos.y, 0, GRID_MAX_POINTS_Y)) { + Z_VALUES(pos.x, pos.y) = zoff; #if ENABLED(ABL_BILINEAR_SUBDIVISION) bed_level_virt_interpolate(); #endif diff --git a/Marlin/src/lcd/extensible_ui/ui_api.h b/Marlin/src/lcd/extensible_ui/ui_api.h index 38cd19b57..1ae2ebd4c 100644 --- a/Marlin/src/lcd/extensible_ui/ui_api.h +++ b/Marlin/src/lcd/extensible_ui/ui_api.h @@ -81,8 +81,8 @@ namespace ExtUI { void enableHeater(const extruder_t); #if ENABLED(JOYSTICK) - void jog(float dx, float dy, float dz); - void _joystick_update(float (&norm_jog)[XYZ]); + void jog(const xyz_float_t &dir); + void _joystick_update(xyz_float_t &norm_jog); #endif /** @@ -135,9 +135,10 @@ namespace ExtUI { bool getMeshValid(); #if HAS_MESH bed_mesh_t& getMeshArray(); - float getMeshPoint(const uint8_t xpos, const uint8_t ypos); - void setMeshPoint(const uint8_t xpos, const uint8_t ypos, const float zval); + float getMeshPoint(const xy_uint8_t &pos); + void setMeshPoint(const xy_uint8_t &pos, const float zval); void onMeshUpdate(const uint8_t xpos, const uint8_t ypos, const float zval); + inline void onMeshUpdate(const xy_uint8_t &pos, const float zval) { setMeshPoint(pos, zval); } #endif #endif diff --git a/Marlin/src/lcd/menu/menu.cpp b/Marlin/src/lcd/menu/menu.cpp index 012b3b584..ca5dd29a2 100644 --- a/Marlin/src/lcd/menu/menu.cpp +++ b/Marlin/src/lcd/menu/menu.cpp @@ -379,8 +379,8 @@ void scroll_screen(const uint8_t limit, const bool is_menu) { #if HAS_LINE_TO_Z void line_to_z(const float &z) { - current_position[Z_AXIS] = z; - planner.buffer_line(current_position, MMM_TO_MMS(manual_feedrate_mm_m[Z_AXIS]), active_extruder); + current_position.z = z; + line_to_current_position(MMM_TO_MMS(manual_feedrate_mm_m.z)); } #endif @@ -402,10 +402,10 @@ void scroll_screen(const uint8_t limit, const bool is_menu) { ui.encoderPosition = 0; const float diff = planner.steps_to_mm[Z_AXIS] * babystep_increment, - new_probe_offset = probe_offset[Z_AXIS] + diff, + new_probe_offset = probe_offset.z + diff, new_offs = #if ENABLED(BABYSTEP_HOTEND_Z_OFFSET) - do_probe ? new_probe_offset : hotend_offset[Z_AXIS][active_extruder] - diff + do_probe ? new_probe_offset : hotend_offset[active_extruder].z - diff #else new_probe_offset #endif @@ -414,9 +414,9 @@ void scroll_screen(const uint8_t limit, const bool is_menu) { babystep.add_steps(Z_AXIS, babystep_increment); - if (do_probe) probe_offset[Z_AXIS] = new_offs; + if (do_probe) probe_offset.z = new_offs; #if ENABLED(BABYSTEP_HOTEND_Z_OFFSET) - else hotend_offset[Z_AXIS][active_extruder] = new_offs; + else hotend_offset[active_extruder].z = new_offs; #endif ui.refresh(LCDVIEW_CALL_REDRAW_NEXT); @@ -425,13 +425,13 @@ void scroll_screen(const uint8_t limit, const bool is_menu) { if (ui.should_draw()) { #if ENABLED(BABYSTEP_HOTEND_Z_OFFSET) if (!do_probe) - draw_edit_screen(PSTR(MSG_Z_OFFSET), ftostr43sign(hotend_offset[Z_AXIS][active_extruder])); + draw_edit_screen(PSTR(MSG_Z_OFFSET), ftostr43sign(hotend_offset[active_extruder].z)); else #endif - draw_edit_screen(PSTR(MSG_ZPROBE_ZOFFSET), ftostr43sign(probe_offset[Z_AXIS])); + draw_edit_screen(PSTR(MSG_ZPROBE_ZOFFSET), ftostr43sign(probe_offset.z)); #if ENABLED(BABYSTEP_ZPROBE_GFX_OVERLAY) - if (do_probe) _lcd_zoffset_overlay_gfx(probe_offset[Z_AXIS]); + if (do_probe) _lcd_zoffset_overlay_gfx(probe_offset.z); #endif } } diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index 9e2746920..1d5f728c1 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -55,7 +55,7 @@ void menu_backlash(); #include "../../feature/dac/stepper_dac.h" - uint8_t driverPercent[XYZE]; + xyze_uint8_t driverPercent; inline void dac_driver_getValues() { LOOP_XYZE(i) driverPercent[i] = dac_current_get_percent((AxisEnum)i); } static void dac_driver_commit() { dac_current_set_percents(driverPercent); } @@ -552,7 +552,7 @@ void menu_backlash(); #if ENABLED(DELTA) EDIT_JERK(C); #else - MENU_MULTIPLIER_ITEM_EDIT(float52sign, MSG_VC_JERK, &planner.max_jerk[C_AXIS], 0.1f, 990); + MENU_MULTIPLIER_ITEM_EDIT(float52sign, MSG_VC_JERK, &planner.max_jerk.c, 0.1f, 990); #endif #if !BOTH(JUNCTION_DEVIATION, LIN_ADVANCE) EDIT_JERK(E); diff --git a/Marlin/src/lcd/menu/menu_bed_corners.cpp b/Marlin/src/lcd/menu/menu_bed_corners.cpp index 07629b717..13441e6f3 100644 --- a/Marlin/src/lcd/menu/menu_bed_corners.cpp +++ b/Marlin/src/lcd/menu/menu_bed_corners.cpp @@ -58,26 +58,24 @@ static inline void _lcd_goto_next_corner() { line_to_z(LEVEL_CORNERS_Z_HOP); switch (bed_corner) { case 0: - current_position[X_AXIS] = X_MIN_BED + LEVEL_CORNERS_INSET; - current_position[Y_AXIS] = Y_MIN_BED + LEVEL_CORNERS_INSET; + current_position.set(X_MIN_BED + LEVEL_CORNERS_INSET, Y_MIN_BED + LEVEL_CORNERS_INSET); break; case 1: - current_position[X_AXIS] = X_MAX_BED - (LEVEL_CORNERS_INSET); + current_position.x = X_MAX_BED - (LEVEL_CORNERS_INSET); break; case 2: - current_position[Y_AXIS] = Y_MAX_BED - (LEVEL_CORNERS_INSET); + current_position.y = Y_MAX_BED - (LEVEL_CORNERS_INSET); break; case 3: - current_position[X_AXIS] = X_MIN_BED + LEVEL_CORNERS_INSET; + current_position.x = X_MIN_BED + LEVEL_CORNERS_INSET; break; #if ENABLED(LEVEL_CENTER_TOO) case 4: - current_position[X_AXIS] = X_CENTER; - current_position[Y_AXIS] = Y_CENTER; + current_position.set(X_CENTER, Y_CENTER); break; #endif } - planner.buffer_line(current_position, MMM_TO_MMS(manual_feedrate_mm_m[X_AXIS]), active_extruder); + line_to_current_position(MMM_TO_MMS(manual_feedrate_mm_m.x)); line_to_z(LEVEL_CORNERS_HEIGHT); if (++bed_corner > 3 #if ENABLED(LEVEL_CENTER_TOO) diff --git a/Marlin/src/lcd/menu/menu_bed_leveling.cpp b/Marlin/src/lcd/menu/menu_bed_leveling.cpp index bb4eaa845..3155a3418 100644 --- a/Marlin/src/lcd/menu/menu_bed_leveling.cpp +++ b/Marlin/src/lcd/menu/menu_bed_leveling.cpp @@ -121,7 +121,7 @@ // Encoder knob or keypad buttons adjust the Z position // if (ui.encoderPosition) { - const float z = current_position[Z_AXIS] + float(int16_t(ui.encoderPosition)) * (MESH_EDIT_Z_STEP); + const float z = current_position.z + float(int16_t(ui.encoderPosition)) * (MESH_EDIT_Z_STEP); line_to_z(constrain(z, -(LCD_PROBE_Z_RANGE) * 0.5f, (LCD_PROBE_Z_RANGE) * 0.5f)); ui.refresh(LCDVIEW_CALL_REDRAW_NEXT); ui.encoderPosition = 0; @@ -131,7 +131,7 @@ // Draw on first display, then only on Z change // if (ui.should_draw()) { - const float v = current_position[Z_AXIS]; + const float v = current_position.z; draw_edit_screen(PSTR(MSG_MOVE_Z), ftostr43sign(v + (v < 0 ? -0.0001f : 0.0001f), '+')); } } @@ -279,7 +279,7 @@ void menu_bed_leveling() { #if ENABLED(BABYSTEP_ZPROBE_OFFSET) MENU_ITEM(submenu, MSG_ZPROBE_ZOFFSET, lcd_babystep_zoffset); #elif HAS_BED_PROBE - MENU_ITEM_EDIT(float52, MSG_ZPROBE_ZOFFSET, &probe_offset[Z_AXIS], Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX); + MENU_ITEM_EDIT(float52, MSG_ZPROBE_ZOFFSET, &probe_offset.z, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX); #endif #if ENABLED(LEVEL_BED_CORNERS) diff --git a/Marlin/src/lcd/menu/menu_configuration.cpp b/Marlin/src/lcd/menu/menu_configuration.cpp index 8708c7d96..596ab682d 100644 --- a/Marlin/src/lcd/menu/menu_configuration.cpp +++ b/Marlin/src/lcd/menu/menu_configuration.cpp @@ -145,12 +145,12 @@ static void lcd_factory_settings() { START_MENU(); MENU_BACK(MSG_CONFIGURATION); #if ENABLED(DUAL_X_CARRIAGE) - MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float51, MSG_X_OFFSET, &hotend_offset[X_AXIS][1], float(X2_HOME_POS - 25), float(X2_HOME_POS + 25), _recalc_offsets); + MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float51, MSG_X_OFFSET, &hotend_offset[1].x, float(X2_HOME_POS - 25), float(X2_HOME_POS + 25), _recalc_offsets); #else - MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float52sign, MSG_X_OFFSET, &hotend_offset[X_AXIS][1], -99.0, 99.0, _recalc_offsets); + MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float52sign, MSG_X_OFFSET, &hotend_offset[1].x, -99.0, 99.0, _recalc_offsets); #endif - MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float52sign, MSG_Y_OFFSET, &hotend_offset[Y_AXIS][1], -99.0, 99.0, _recalc_offsets); - MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float52sign, MSG_Z_OFFSET, &hotend_offset[Z_AXIS][1], Z_PROBE_LOW_POINT, 10.0, _recalc_offsets); + MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float52sign, MSG_Y_OFFSET, &hotend_offset[1].y, -99.0, 99.0, _recalc_offsets); + MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float52sign, MSG_Z_OFFSET, &hotend_offset[1].z, Z_PROBE_LOW_POINT, 10.0, _recalc_offsets); #if ENABLED(EEPROM_SETTINGS) MENU_ITEM(function, MSG_STORE_EEPROM, lcd_store_settings); #endif @@ -347,7 +347,7 @@ void menu_configuration() { #if ENABLED(BABYSTEP_ZPROBE_OFFSET) MENU_ITEM(submenu, MSG_ZPROBE_ZOFFSET, lcd_babystep_zoffset); #elif HAS_BED_PROBE - MENU_ITEM_EDIT(float52, MSG_ZPROBE_ZOFFSET, &probe_offset[Z_AXIS], Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX); + MENU_ITEM_EDIT(float52, MSG_ZPROBE_ZOFFSET, &probe_offset.z, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX); #endif const bool busy = printer_busy(); diff --git a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp index b8232ba38..b42c9a9a7 100644 --- a/Marlin/src/lcd/menu/menu_delta_calibrate.cpp +++ b/Marlin/src/lcd/menu/menu_delta_calibrate.cpp @@ -40,8 +40,8 @@ #include "../../lcd/extensible_ui/ui_api.h" #endif -void _man_probe_pt(const float &rx, const float &ry) { - do_blocking_move_to(rx, ry, Z_CLEARANCE_BETWEEN_PROBES); +void _man_probe_pt(const xy_pos_t &xy) { + do_blocking_move_to(xy, Z_CLEARANCE_BETWEEN_PROBES); ui.synchronize(); move_menu_scale = _MAX(PROBE_MANUALLY_STEP, MIN_STEPS_PER_SEGMENT / float(DEFAULT_XYZ_STEPS_PER_UNIT)); ui.goto_screen(lcd_move_z); @@ -51,8 +51,8 @@ void _man_probe_pt(const float &rx, const float &ry) { #include "../../gcode/gcode.h" - float lcd_probe_pt(const float &rx, const float &ry) { - _man_probe_pt(rx, ry); + float lcd_probe_pt(const xy_pos_t &xy) { + _man_probe_pt(xy); KEEPALIVE_STATE(PAUSED_FOR_USER); ui.defer_status_screen(); wait_for_user = true; @@ -64,7 +64,7 @@ void _man_probe_pt(const float &rx, const float &ry) { #endif while (wait_for_user) idle(); ui.goto_previous_screen_no_defer(); - return current_position[Z_AXIS]; + return current_position.z; } #endif @@ -83,10 +83,14 @@ void _man_probe_pt(const float &rx, const float &ry) { ui.goto_screen(_lcd_calibrate_homing); } - void _goto_tower_x() { _man_probe_pt(cos(RADIANS(210)) * delta_calibration_radius, sin(RADIANS(210)) * delta_calibration_radius); } - void _goto_tower_y() { _man_probe_pt(cos(RADIANS(330)) * delta_calibration_radius, sin(RADIANS(330)) * delta_calibration_radius); } - void _goto_tower_z() { _man_probe_pt(cos(RADIANS( 90)) * delta_calibration_radius, sin(RADIANS( 90)) * delta_calibration_radius); } - void _goto_center() { _man_probe_pt(0,0); } + void _goto_tower_a(const float &a) { + xy_pos_t tower_vec = { cos(RADIANS(a)), sin(RADIANS(a)) }; + _man_probe_pt(tower_vec * delta_calibration_radius); + } + void _goto_tower_x() { _goto_tower_a(210); } + void _goto_tower_y() { _goto_tower_a(330); } + void _goto_tower_z() { _goto_tower_a( 90); } + void _goto_center() { xy_pos_t ctr{0}; _man_probe_pt(ctr); } #endif @@ -101,15 +105,15 @@ void lcd_delta_settings() { START_MENU(); MENU_BACK(MSG_DELTA_CALIBRATE); MENU_ITEM_EDIT_CALLBACK(float52sign, MSG_DELTA_HEIGHT, &delta_height, delta_height - 10, delta_height + 10, _recalc_delta_settings); - #define EDIT_ENDSTOP_ADJ(LABEL,N) MENU_ITEM_EDIT_CALLBACK(float43, LABEL, &delta_endstop_adj[_AXIS(N)], -5, 5, _recalc_delta_settings) - EDIT_ENDSTOP_ADJ("Ex",A); - EDIT_ENDSTOP_ADJ("Ey",B); - EDIT_ENDSTOP_ADJ("Ez",C); + #define EDIT_ENDSTOP_ADJ(LABEL,N) MENU_ITEM_EDIT_CALLBACK(float43, LABEL, &delta_endstop_adj.N, -5, 5, _recalc_delta_settings) + EDIT_ENDSTOP_ADJ("Ex",a); + EDIT_ENDSTOP_ADJ("Ey",b); + EDIT_ENDSTOP_ADJ("Ez",c); MENU_ITEM_EDIT_CALLBACK(float52sign, MSG_DELTA_RADIUS, &delta_radius, delta_radius - 5, delta_radius + 5, _recalc_delta_settings); - #define EDIT_ANGLE_TRIM(LABEL,N) MENU_ITEM_EDIT_CALLBACK(float43, LABEL, &delta_tower_angle_trim[_AXIS(N)], -5, 5, _recalc_delta_settings) - EDIT_ANGLE_TRIM("Tx",A); - EDIT_ANGLE_TRIM("Ty",B); - EDIT_ANGLE_TRIM("Tz",C); + #define EDIT_ANGLE_TRIM(LABEL,N) MENU_ITEM_EDIT_CALLBACK(float43, LABEL, &delta_tower_angle_trim.N, -5, 5, _recalc_delta_settings) + EDIT_ANGLE_TRIM("Tx",a); + EDIT_ANGLE_TRIM("Ty",b); + EDIT_ANGLE_TRIM("Tz",c); MENU_ITEM_EDIT_CALLBACK(float52sign, MSG_DELTA_DIAG_ROD, &delta_diagonal_rod, delta_diagonal_rod - 5, delta_diagonal_rod + 5, _recalc_delta_settings); END_MENU(); } diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index 2a75c2693..da8c33225 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -92,26 +92,26 @@ static void _lcd_move_xyz(PGM_P name, AxisEnum axis) { if (soft_endstops_enabled) switch (axis) { case X_AXIS: #if ENABLED(MIN_SOFTWARE_ENDSTOP_X) - min = soft_endstop[X_AXIS].min; + min = soft_endstop.min.x; #endif #if ENABLED(MAX_SOFTWARE_ENDSTOP_X) - max = soft_endstop[X_AXIS].max; + max = soft_endstop.max.x; #endif break; case Y_AXIS: #if ENABLED(MIN_SOFTWARE_ENDSTOP_Y) - min = soft_endstop[Y_AXIS].min; + min = soft_endstop.min.y; #endif #if ENABLED(MAX_SOFTWARE_ENDSTOP_Y) - max = soft_endstop[Y_AXIS].max; + max = soft_endstop.max.y; #endif break; case Z_AXIS: #if ENABLED(MIN_SOFTWARE_ENDSTOP_Z) - min = soft_endstop[Z_AXIS].min; + min = soft_endstop.min.z; #endif #if ENABLED(MAX_SOFTWARE_ENDSTOP_Z) - max = soft_endstop[Z_AXIS].max; + max = soft_endstop.max.z; #endif default: break; } @@ -173,7 +173,7 @@ void lcd_move_z() { _lcd_move_xyz(PSTR(MSG_MOVE_Z), Z_AXIS); } #if IS_KINEMATIC manual_move_offset += diff; #else - current_position[E_AXIS] += diff; + current_position.e += diff; #endif manual_move_to_current(E_AXIS #if E_MANUAL > 1 @@ -207,7 +207,7 @@ void lcd_move_z() { _lcd_move_xyz(PSTR(MSG_MOVE_Z), Z_AXIS); } } #endif // E_MANUAL > 1 - draw_edit_screen(pos_label, ftostr41sign(current_position[E_AXIS] + draw_edit_screen(pos_label, ftostr41sign(current_position.e #if IS_KINEMATIC + manual_move_offset #endif @@ -267,7 +267,7 @@ void _menu_move_distance(const AxisEnum axis, const screenFunc_t func, const int case Z_AXIS: STATIC_ITEM(MSG_MOVE_Z, SS_CENTER|SS_INVERT); break; default: #if ENABLED(MANUAL_E_MOVES_RELATIVE) - manual_move_e_origin = current_position[E_AXIS]; + manual_move_e_origin = current_position.e; #endif STATIC_ITEM(MSG_MOVE_E, SS_CENTER|SS_INVERT); break; @@ -345,7 +345,7 @@ void menu_move() { ) { if ( #if ENABLED(DELTA) - current_position[Z_AXIS] <= delta_clip_start_height + current_position.z <= delta_clip_start_height #else true #endif diff --git a/Marlin/src/lcd/menu/menu_ubl.cpp b/Marlin/src/lcd/menu/menu_ubl.cpp index 2364a818a..4065d5309 100644 --- a/Marlin/src/lcd/menu/menu_ubl.cpp +++ b/Marlin/src/lcd/menu/menu_ubl.cpp @@ -432,18 +432,16 @@ void _lcd_ubl_map_lcd_edit_cmd() { void ubl_map_move_to_xy() { const feedRate_t fr_mm_s = MMM_TO_MMS(XY_PROBE_SPEED); - set_destination_from_current(); // sync destination at the start + destination = current_position; // sync destination at the start #if ENABLED(DELTA) - if (current_position[Z_AXIS] > delta_clip_start_height) { - destination[Z_AXIS] = delta_clip_start_height; + if (current_position.z > delta_clip_start_height) { + destination.z = delta_clip_start_height; prepare_internal_move_to_destination(fr_mm_s); } #endif - destination[X_AXIS] = pgm_read_float(&ubl._mesh_index_to_xpos[x_plot]); - destination[Y_AXIS] = pgm_read_float(&ubl._mesh_index_to_ypos[y_plot]); - + destination.set(ubl.mesh_index_to_xpos(x_plot), ubl.mesh_index_to_ypos(y_plot)); prepare_internal_move_to_destination(fr_mm_s); } @@ -491,9 +489,8 @@ void _lcd_ubl_output_map_lcd() { if (y_plot < 0) y_plot = GRID_MAX_POINTS_Y - 1; #if IS_KINEMATIC - const float x = pgm_read_float(&ubl._mesh_index_to_xpos[x_plot]), - y = pgm_read_float(&ubl._mesh_index_to_ypos[y_plot]); - if (position_is_reachable(x, y)) break; // Found a valid point + const xy_pos_t xy = { ubl.mesh_index_to_xpos(x_plot), ubl.mesh_index_to_ypos(y_plot) }; + if (position_is_reachable(xy)) break; // Found a valid point x_plot += (step_scaler < 0) ? -1 : 1; #endif diff --git a/Marlin/src/lcd/ultralcd.cpp b/Marlin/src/lcd/ultralcd.cpp index 389a58f2d..63d1629f8 100644 --- a/Marlin/src/lcd/ultralcd.cpp +++ b/Marlin/src/lcd/ultralcd.cpp @@ -671,7 +671,7 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { #endif // Set movement on a single axis - set_destination_from_current(); + destination = current_position; destination[manual_move_axis] += manual_move_offset; // Reset for the next move diff --git a/Marlin/src/lcd/ultralcd.h b/Marlin/src/lcd/ultralcd.h index f3dcb3a38..32c51cd24 100644 --- a/Marlin/src/lcd/ultralcd.h +++ b/Marlin/src/lcd/ultralcd.h @@ -90,7 +90,6 @@ typedef void (*menuAction_t)(); // Manual Movement - constexpr feedRate_t manual_feedrate_mm_m[XYZE] = MANUAL_FEEDRATE; extern float move_menu_scale; #if ENABLED(ADVANCED_PAUSE_FEATURE) diff --git a/Marlin/src/libs/L6470/L6470_Marlin.cpp b/Marlin/src/libs/L6470/L6470_Marlin.cpp index d8b0fb833..549ba3c36 100644 --- a/Marlin/src/libs/L6470/L6470_Marlin.cpp +++ b/Marlin/src/libs/L6470/L6470_Marlin.cpp @@ -339,19 +339,19 @@ bool L6470_Marlin::get_user_input(uint8_t &driver_count, uint8_t axis_index[3], // Position calcs & checks // - const float center[] = { - LOGICAL_X_POSITION(current_position[X_AXIS]), - LOGICAL_Y_POSITION(current_position[Y_AXIS]), - LOGICAL_Z_POSITION(current_position[Z_AXIS]), - current_position[E_AXIS] + const xyze_pos_t center = { + LOGICAL_X_POSITION(current_position.x), + LOGICAL_Y_POSITION(current_position.y), + LOGICAL_Z_POSITION(current_position.z), + current_position.e }; switch (axis_mon[0][0]) { default: position_max = position_min = 0; break; case 'X': { - position_min = center[X_AXIS] - displacement; - position_max = center[X_AXIS] + displacement; + position_min = center.x - displacement; + position_max = center.x + displacement; echo_min_max('X', position_min, position_max); if (false #ifdef X_MIN_POS @@ -367,8 +367,8 @@ bool L6470_Marlin::get_user_input(uint8_t &driver_count, uint8_t axis_index[3], } break; case 'Y': { - position_min = center[Y_AXIS] - displacement; - position_max = center[Y_AXIS] + displacement; + position_min = center.y - displacement; + position_max = center.y + displacement; echo_min_max('Y', position_min, position_max); if (false #ifdef Y_MIN_POS @@ -384,8 +384,8 @@ bool L6470_Marlin::get_user_input(uint8_t &driver_count, uint8_t axis_index[3], } break; case 'Z': { - position_min = center[Z_AXIS] - displacement; - position_max = center[Z_AXIS] + displacement; + position_min = center.z - displacement; + position_max = center.z + displacement; echo_min_max('Z', position_min, position_max); if (false #ifdef Z_MIN_POS @@ -401,8 +401,8 @@ bool L6470_Marlin::get_user_input(uint8_t &driver_count, uint8_t axis_index[3], } break; case 'E': { - position_min = center[E_AXIS] - displacement; - position_max = center[E_AXIS] + displacement; + position_min = center.e - displacement; + position_max = center.e + displacement; echo_min_max('E', position_min, position_max); } break; } diff --git a/Marlin/src/libs/least_squares_fit.h b/Marlin/src/libs/least_squares_fit.h index bfef8b14a..acb29402c 100644 --- a/Marlin/src/libs/least_squares_fit.h +++ b/Marlin/src/libs/least_squares_fit.h @@ -65,6 +65,9 @@ inline void incremental_WLSF(struct linear_fit_data *lsf, const float &x, const lsf->max_absx = _MAX(ABS(wx), lsf->max_absx); lsf->max_absy = _MAX(ABS(wy), lsf->max_absy); } +inline void incremental_WLSF(struct linear_fit_data *lsf, const xy_pos_t &pos, const float &z, const float &w) { + incremental_WLSF(lsf, pos.x, pos.y, z, w); +} inline void incremental_LSF(struct linear_fit_data *lsf, const float &x, const float &y, const float &z) { lsf->xbar += x; @@ -80,5 +83,8 @@ inline void incremental_LSF(struct linear_fit_data *lsf, const float &x, const f lsf->max_absy = _MAX(ABS(y), lsf->max_absy); lsf->N += 1.0; } +inline void incremental_LSF(struct linear_fit_data *lsf, const xy_pos_t &pos, const float &z) { + incremental_LSF(lsf, pos.x, pos.y, z); +} int finish_incremental_LSF(struct linear_fit_data *); diff --git a/Marlin/src/libs/nozzle.cpp b/Marlin/src/libs/nozzle.cpp index 829d46e1d..b95a7c8af 100644 --- a/Marlin/src/libs/nozzle.cpp +++ b/Marlin/src/libs/nozzle.cpp @@ -30,7 +30,6 @@ Nozzle nozzle; #include "../Marlin.h" #include "../module/motion.h" -#include "point_t.h" #if ENABLED(NOZZLE_CLEAN_FEATURE) @@ -38,30 +37,30 @@ Nozzle nozzle; * @brief Stroke clean pattern * @details Wipes the nozzle back and forth in a linear movement * - * @param start point_t defining the starting point - * @param end point_t defining the ending point + * @param start xyz_pos_t defining the starting point + * @param end xyz_pos_t defining the ending point * @param strokes number of strokes to execute */ - void Nozzle::stroke(const point_t &start, const point_t &end, const uint8_t &strokes) { + void Nozzle::stroke(const xyz_pos_t &start, const xyz_pos_t &end, const uint8_t &strokes) { #if ENABLED(NOZZLE_CLEAN_GOBACK) - const float ix = current_position[X_AXIS], iy = current_position[Y_AXIS], iz = current_position[Z_AXIS]; + const xyz_pos_t oldpos = current_position; #endif // Move to the starting point #if ENABLED(NOZZLE_CLEAN_NO_Z) - do_blocking_move_to_xy(start.x, start.y); + do_blocking_move_to_xy(start); #else - do_blocking_move_to(start.x, start.y, start.z); + do_blocking_move_to(start); #endif // Start the stroke pattern for (uint8_t i = 0; i < (strokes >> 1); i++) { - do_blocking_move_to_xy(end.x, end.y); - do_blocking_move_to_xy(start.x, start.y); + do_blocking_move_to_xy(end); + do_blocking_move_to_xy(start); } #if ENABLED(NOZZLE_CLEAN_GOBACK) - do_blocking_move_to(ix, iy, iz); + do_blocking_move_to(oldpos); #endif } @@ -69,29 +68,29 @@ Nozzle nozzle; * @brief Zig-zag clean pattern * @details Apply a zig-zag cleaning pattern * - * @param start point_t defining the starting point - * @param end point_t defining the ending point + * @param start xyz_pos_t defining the starting point + * @param end xyz_pos_t defining the ending point * @param strokes number of strokes to execute * @param objects number of triangles to do */ - void Nozzle::zigzag(const point_t &start, const point_t &end, const uint8_t &strokes, const uint8_t &objects) { - const float diffx = end.x - start.x, diffy = end.y - start.y; - if (!diffx || !diffy) return; + void Nozzle::zigzag(const xyz_pos_t &start, const xyz_pos_t &end, const uint8_t &strokes, const uint8_t &objects) { + const xy_pos_t diff = end - start; + if (!diff.x || !diff.y) return; #if ENABLED(NOZZLE_CLEAN_GOBACK) - const float ix = current_position[X_AXIS], iy = current_position[Y_AXIS], iz = current_position[Z_AXIS]; + const xyz_pos_t back = current_position; #endif #if ENABLED(NOZZLE_CLEAN_NO_Z) - do_blocking_move_to_xy(start.x, start.y); + do_blocking_move_to_xy(start); #else - do_blocking_move_to(start.x, start.y, start.z); + do_blocking_move_to(start); #endif const uint8_t zigs = objects << 1; - const bool horiz = ABS(diffx) >= ABS(diffy); // Do a horizontal wipe? - const float P = (horiz ? diffx : diffy) / zigs; // Period of each zig / zag - const point_t *side; + const bool horiz = ABS(diff.x) >= ABS(diff.y); // Do a horizontal wipe? + const float P = (horiz ? diff.x : diff.y) / zigs; // Period of each zig / zag + const xyz_pos_t *side; for (uint8_t j = 0; j < strokes; j++) { for (int8_t i = 0; i < zigs; i++) { side = (i & 1) ? &end : &start; @@ -110,7 +109,7 @@ Nozzle nozzle; } #if ENABLED(NOZZLE_CLEAN_GOBACK) - do_blocking_move_to(ix, iy, iz); + do_blocking_move_to(back); #endif } @@ -118,21 +117,21 @@ Nozzle nozzle; * @brief Circular clean pattern * @details Apply a circular cleaning pattern * - * @param start point_t defining the middle of circle + * @param start xyz_pos_t defining the middle of circle * @param strokes number of strokes to execute * @param radius radius of circle */ - void Nozzle::circle(const point_t &start, const point_t &middle, const uint8_t &strokes, const float &radius) { + void Nozzle::circle(const xyz_pos_t &start, const xyz_pos_t &middle, const uint8_t &strokes, const float &radius) { if (strokes == 0) return; #if ENABLED(NOZZLE_CLEAN_GOBACK) - const float ix = current_position[X_AXIS], iy = current_position[Y_AXIS], iz = current_position[Z_AXIS]; + const xyz_pos_t back = current_position; #endif #if ENABLED(NOZZLE_CLEAN_NO_Z) - do_blocking_move_to_xy(start.x, start.y); + do_blocking_move_to_xy(start); #else - do_blocking_move_to(start.x, start.y, start.z); + do_blocking_move_to(start); #endif for (uint8_t s = 0; s < strokes; s++) @@ -143,10 +142,10 @@ Nozzle nozzle; ); // Let's be safe - do_blocking_move_to_xy(start.x, start.y); + do_blocking_move_to_xy(start); #if ENABLED(NOZZLE_CLEAN_GOBACK) - do_blocking_move_to(ix, iy, iz); + do_blocking_move_to(back); #endif } @@ -158,21 +157,21 @@ Nozzle nozzle; * @param argument depends on the cleaning pattern */ void Nozzle::clean(const uint8_t &pattern, const uint8_t &strokes, const float &radius, const uint8_t &objects, const uint8_t cleans) { - point_t start = NOZZLE_CLEAN_START_POINT; - point_t end = NOZZLE_CLEAN_END_POINT; + xyz_pos_t start = NOZZLE_CLEAN_START_POINT, end = NOZZLE_CLEAN_END_POINT; if (pattern == 2) { if (!(cleans & (_BV(X_AXIS) | _BV(Y_AXIS)))) { SERIAL_ECHOLNPGM("Warning : Clean Circle requires XY"); return; } - end = NOZZLE_CLEAN_CIRCLE_MIDDLE; + constexpr xyz_pos_t middle NOZZLE_CLEAN_CIRCLE_MIDDLE; + end = middle; } else { - if (!TEST(cleans, X_AXIS)) start.x = end.x = current_position[X_AXIS]; - if (!TEST(cleans, Y_AXIS)) start.y = end.y = current_position[Y_AXIS]; + if (!TEST(cleans, X_AXIS)) start.x = end.x = current_position.x; + if (!TEST(cleans, Y_AXIS)) start.y = end.y = current_position.y; } - if (!TEST(cleans, Z_AXIS)) start.z = end.z = current_position[Z_AXIS]; + if (!TEST(cleans, Z_AXIS)) start.z = end.z = current_position.z; switch (pattern) { case 1: zigzag(start, end, strokes, objects); break; @@ -185,7 +184,7 @@ Nozzle nozzle; #if ENABLED(NOZZLE_PARK_FEATURE) - void Nozzle::park(const uint8_t z_action, const point_t &park/*=NOZZLE_PARK_POINT*/) { + void Nozzle::park(const uint8_t z_action, const xyz_pos_t &park/*=NOZZLE_PARK_POINT*/) { constexpr feedRate_t fr_xy = NOZZLE_PARK_XY_FEEDRATE, fr_z = NOZZLE_PARK_Z_FEEDRATE; switch (z_action) { @@ -194,14 +193,14 @@ Nozzle nozzle; break; case 2: // Raise by Z-park height - do_blocking_move_to_z(_MIN(current_position[Z_AXIS] + park.z, Z_MAX_POS), fr_z); + do_blocking_move_to_z(_MIN(current_position.z + park.z, Z_MAX_POS), fr_z); break; default: // Raise to at least the Z-park height - do_blocking_move_to_z(_MAX(park.z, current_position[Z_AXIS]), fr_z); + do_blocking_move_to_z(_MAX(park.z, current_position.z), fr_z); } - do_blocking_move_to_xy(park.x, park.y, fr_xy); + do_blocking_move_to_xy(park, fr_xy); report_current_position(); } diff --git a/Marlin/src/libs/nozzle.h b/Marlin/src/libs/nozzle.h index d20b41de9..280f8b1a3 100644 --- a/Marlin/src/libs/nozzle.h +++ b/Marlin/src/libs/nozzle.h @@ -22,7 +22,6 @@ #pragma once #include "../inc/MarlinConfig.h" -#include "point_t.h" /** * @brief Nozzle class @@ -38,32 +37,32 @@ class Nozzle { * @brief Stroke clean pattern * @details Wipes the nozzle back and forth in a linear movement * - * @param start point_t defining the starting point - * @param end point_t defining the ending point + * @param start xyz_pos_t defining the starting point + * @param end xyz_pos_t defining the ending point * @param strokes number of strokes to execute */ - static void stroke(const point_t &start, const point_t &end, const uint8_t &strokes) _Os; + static void stroke(const xyz_pos_t &start, const xyz_pos_t &end, const uint8_t &strokes) _Os; /** * @brief Zig-zag clean pattern * @details Apply a zig-zag cleaning pattern * - * @param start point_t defining the starting point - * @param end point_t defining the ending point + * @param start xyz_pos_t defining the starting point + * @param end xyz_pos_t defining the ending point * @param strokes number of strokes to execute * @param objects number of objects to create */ - static void zigzag(const point_t &start, const point_t &end, const uint8_t &strokes, const uint8_t &objects) _Os; + static void zigzag(const xyz_pos_t &start, const xyz_pos_t &end, const uint8_t &strokes, const uint8_t &objects) _Os; /** * @brief Circular clean pattern * @details Apply a circular cleaning pattern * - * @param start point_t defining the middle of circle + * @param start xyz_pos_t defining the middle of circle * @param strokes number of strokes to execute * @param radius radius of circle */ - static void circle(const point_t &start, const point_t &middle, const uint8_t &strokes, const float &radius) _Os; + static void circle(const xyz_pos_t &start, const xyz_pos_t &middle, const uint8_t &strokes, const float &radius) _Os; #endif // NOZZLE_CLEAN_FEATURE @@ -84,7 +83,7 @@ class Nozzle { #if ENABLED(NOZZLE_PARK_FEATURE) - static void park(const uint8_t z_action, const point_t &park=NOZZLE_PARK_POINT) _Os; + static void park(const uint8_t z_action, const xyz_pos_t &park=NOZZLE_PARK_POINT) _Os; #endif }; diff --git a/Marlin/src/libs/point_t.h b/Marlin/src/libs/point_t.h deleted file mode 100644 index 5c7d8feac..000000000 --- a/Marlin/src/libs/point_t.h +++ /dev/null @@ -1,55 +0,0 @@ -/** - * Marlin 3D Printer Firmware - * Copyright (c) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * - * Based on Sprinter and grbl. - * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ -#pragma once - -#include - -/** - * @brief Cartesian Point - * @details Represents a three dimensional point on Cartesian coordinate system, - * using an additional fourth dimension for the extrusion length. - * - * @param x The x-coordinate of the point. - * @param y The y-coordinate of the point. - * @param z The z-coordinate of the point. - */ -struct point_t { - float x, y, z; - - /** - * @brief Three dimensional point constructor - * - * @param x The x-coordinate of the point. - * @param y The y-coordinate of the point. - * @param z The z-coordinate of the point. - */ - point_t(const float x, const float y, const float z) : x(x), y(y), z(z) {} - - /** - * @brief Two dimensional point constructor - * - * @param x The x-coordinate of the point. - * @param y The y-coordinate of the point. - */ - point_t(const float x, const float y) : point_t(x, y, NAN) {} - -}; diff --git a/Marlin/src/libs/vector_3.cpp b/Marlin/src/libs/vector_3.cpp index e733cce3a..0363318e5 100644 --- a/Marlin/src/libs/vector_3.cpp +++ b/Marlin/src/libs/vector_3.cpp @@ -47,81 +47,74 @@ #include -vector_3::vector_3() : x(0), y(0), z(0) { } - -vector_3::vector_3(float x_, float y_, float z_) : x(x_), y(y_), z(z_) { } +/** + * vector_3 + */ vector_3 vector_3::cross(const vector_3 &left, const vector_3 &right) { - return vector_3(left.y * right.z - left.z * right.y, - left.z * right.x - left.x * right.z, - left.x * right.y - left.y * right.x); + const xyz_float_t &lv = left, &rv = right; + return vector_3(lv.y * rv.z - lv.z * rv.y, // YZ cross + lv.z * rv.x - lv.x * rv.z, // ZX cross + lv.x * rv.y - lv.y * rv.x); // XY cross } -vector_3 vector_3::operator+(const vector_3 &v) { return vector_3(x + v.x, y + v.y, z + v.z); } -vector_3 vector_3::operator-(const vector_3 &v) { return vector_3(x - v.x, y - v.y, z - v.z); } - -vector_3 vector_3::operator* (const float &v) { return vector_3(x * v, y * v, z * v); } -vector_3& vector_3::operator*=(const float &v) { x *= v; y *= v; z *= v; return *this; } - vector_3 vector_3::get_normal() const { - vector_3 normalized = vector_3(x, y, z); + vector_3 normalized = *this; normalized.normalize(); return normalized; } -float vector_3::get_length() const { return SQRT(sq(x) + sq(y) + sq(z)); } - void vector_3::normalize() { - const float inv_length = RSQRT(sq(x) + sq(y) + sq(z)); - x *= inv_length; - y *= inv_length; - z *= inv_length; + *this *= RSQRT(sq(x) + sq(y) + sq(z)); } +// Apply a rotation to the matrix void vector_3::apply_rotation(const matrix_3x3 &matrix) { - const float _x = x, _y = y; - x = _x * matrix.matrix[3 * 0 + 0] + _y * matrix.matrix[3 * 1 + 0] + z * matrix.matrix[3 * 2 + 0]; - y = _x * matrix.matrix[3 * 0 + 1] + _y * matrix.matrix[3 * 1 + 1] + z * matrix.matrix[3 * 2 + 1]; - z = _x * matrix.matrix[3 * 0 + 2] + _y * matrix.matrix[3 * 1 + 2] + z * matrix.matrix[3 * 2 + 2]; + const float _x = x, _y = y, _z = z; + *this = matrix.vectors[0] * _x + matrix.vectors[1] * _y + matrix.vectors[2] * _z; } void vector_3::debug(PGM_P const title) { serialprintPGM(title); - SERIAL_ECHOPAIR_F(" x: ", x, 6); - SERIAL_ECHOPAIR_F(" y: ", y, 6); - SERIAL_ECHOLNPAIR_F(" z: ", z, 6); + SERIAL_ECHOPAIR_F(" X", x, 6); + SERIAL_ECHOPAIR_F(" Y", y, 6); + SERIAL_ECHOLNPAIR_F(" Z", z, 6); } -void apply_rotation_xyz(const matrix_3x3 &matrix, float &x, float &y, float &z) { - vector_3 vector = vector_3(x, y, z); - vector.apply_rotation(matrix); - x = vector.x; - y = vector.y; - z = vector.z; +/** + * matrix_3x3 + */ + +void apply_rotation_xyz(const matrix_3x3 &matrix, float &_x, float &_y, float &_z) { + vector_3 vec = vector_3(_x, _y, _z); vec.apply_rotation(matrix); + _x = vec.x; _y = vec.y; _z = vec.z; +} + +// Reset to identity. No rotate or translate. +void matrix_3x3::set_to_identity() { + for (uint8_t i = 0; i < 3; i++) + for (uint8_t j = 0; j < 3; j++) + vectors[i][j] = float(i == j); } +// Create a matrix from 3 vector_3 inputs matrix_3x3 matrix_3x3::create_from_rows(const vector_3 &row_0, const vector_3 &row_1, const vector_3 &row_2) { //row_0.debug(PSTR("row_0")); //row_1.debug(PSTR("row_1")); //row_2.debug(PSTR("row_2")); matrix_3x3 new_matrix; - new_matrix.matrix[0] = row_0.x; new_matrix.matrix[1] = row_0.y; new_matrix.matrix[2] = row_0.z; - new_matrix.matrix[3] = row_1.x; new_matrix.matrix[4] = row_1.y; new_matrix.matrix[5] = row_1.z; - new_matrix.matrix[6] = row_2.x; new_matrix.matrix[7] = row_2.y; new_matrix.matrix[8] = row_2.z; + new_matrix.vectors[0] = row_0; + new_matrix.vectors[1] = row_1; + new_matrix.vectors[2] = row_2; //new_matrix.debug(PSTR("new_matrix")); return new_matrix; } -void matrix_3x3::set_to_identity() { - matrix[0] = 1; matrix[1] = 0; matrix[2] = 0; - matrix[3] = 0; matrix[4] = 1; matrix[5] = 0; - matrix[6] = 0; matrix[7] = 0; matrix[8] = 1; -} - +// Create a matrix rotated to point towards a target matrix_3x3 matrix_3x3::create_look_at(const vector_3 &target) { - vector_3 z_row = target.get_normal(), - x_row = vector_3(1, 0, -target.x / target.z).get_normal(), - y_row = vector_3::cross(z_row, x_row).get_normal(); + const vector_3 z_row = target.get_normal(), + x_row = vector_3(1, 0, -target.x / target.z).get_normal(), + y_row = vector_3::cross(z_row, x_row).get_normal(); // x_row.debug(PSTR("x_row")); // y_row.debug(PSTR("y_row")); @@ -134,11 +127,12 @@ matrix_3x3 matrix_3x3::create_look_at(const vector_3 &target) { return rot; } +// Get a transposed copy of the matrix matrix_3x3 matrix_3x3::transpose(const matrix_3x3 &original) { matrix_3x3 new_matrix; - new_matrix.matrix[0] = original.matrix[0]; new_matrix.matrix[1] = original.matrix[3]; new_matrix.matrix[2] = original.matrix[6]; - new_matrix.matrix[3] = original.matrix[1]; new_matrix.matrix[4] = original.matrix[4]; new_matrix.matrix[5] = original.matrix[7]; - new_matrix.matrix[6] = original.matrix[2]; new_matrix.matrix[7] = original.matrix[5]; new_matrix.matrix[8] = original.matrix[8]; + for (uint8_t i = 0; i < 3; i++) + for (uint8_t j = 0; j < 3; j++) + new_matrix.vectors[i][j] = original.vectors[j][i]; return new_matrix; } @@ -147,13 +141,11 @@ void matrix_3x3::debug(PGM_P const title) { serialprintPGM(title); SERIAL_EOL(); } - uint8_t count = 0; for (uint8_t i = 0; i < 3; i++) { for (uint8_t j = 0; j < 3; j++) { - if (matrix[count] >= 0.0) SERIAL_CHAR('+'); - SERIAL_ECHO_F(matrix[count], 6); + if (vectors[i][j] >= 0.0) SERIAL_CHAR('+'); + SERIAL_ECHO_F(vectors[i][j], 6); SERIAL_CHAR(' '); - count++; } SERIAL_EOL(); } diff --git a/Marlin/src/libs/vector_3.h b/Marlin/src/libs/vector_3.h index 6f9153817..fe95cfa85 100644 --- a/Marlin/src/libs/vector_3.h +++ b/Marlin/src/libs/vector_3.h @@ -40,33 +40,40 @@ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA */ +#include "../core/types.h" + class matrix_3x3; -struct vector_3 { - float x, y, z; +struct vector_3 : xyz_float_t { - vector_3(); - vector_3(float x, float y, float z); + vector_3(const float &_x, const float &_y, const float &_z) { set(_x, _y, _z); } + vector_3(const xy_float_t &in) { set(in.x, in.y); } + vector_3(const xyz_float_t &in) { set(in.x, in.y, in.z); } + vector_3(const xyze_float_t &in) { set(in.x, in.y, in.z); } + // Factory method static vector_3 cross(const vector_3 &a, const vector_3 &b); - vector_3 operator+(const vector_3 &v); - vector_3 operator-(const vector_3 &v); - - vector_3 operator* (const float &v); - vector_3& operator*=(const float &v); - + // Modifiers void normalize(); + void apply_rotation(const matrix_3x3 &matrix); + + // Accessors float get_length() const; vector_3 get_normal() const; + // Operators + FORCE_INLINE vector_3 operator+(const vector_3 &v) const { vector_3 o = *this; o += v; return o; } + FORCE_INLINE vector_3 operator-(const vector_3 &v) const { vector_3 o = *this; o -= v; return o; } + FORCE_INLINE vector_3 operator*(const float &v) const { vector_3 o = *this; o *= v; return o; } + void debug(PGM_P const title); - void apply_rotation(const matrix_3x3 &matrix); }; struct matrix_3x3 { - float matrix[9]; + abc_float_t vectors[3]; + // Factory methods static matrix_3x3 create_from_rows(const vector_3 &row_0, const vector_3 &row_1, const vector_3 &row_2); static matrix_3x3 create_look_at(const vector_3 &target); static matrix_3x3 transpose(const matrix_3x3 &original); @@ -76,5 +83,7 @@ struct matrix_3x3 { void debug(PGM_P const title); }; - void apply_rotation_xyz(const matrix_3x3 &rotationMatrix, float &x, float &y, float &z); +FORCE_INLINE void apply_rotation_xyz(const matrix_3x3 &rotationMatrix, xyz_pos_t &pos) { + apply_rotation_xyz(rotationMatrix, pos.x, pos.y, pos.z); +} diff --git a/Marlin/src/module/configuration_store.cpp b/Marlin/src/module/configuration_store.cpp index 3d723909b..699b44cdb 100644 --- a/Marlin/src/module/configuration_store.cpp +++ b/Marlin/src/module/configuration_store.cpp @@ -52,7 +52,7 @@ #include "temperature.h" #include "../lcd/ultralcd.h" #include "../core/language.h" -#include "../libs/vector_3.h" +#include "../libs/vector_3.h" // for matrix_3x3 #include "../gcode/gcode.h" #include "../Marlin.h" @@ -146,13 +146,13 @@ typedef struct SettingsDataStruct { planner_settings_t planner_settings; - float planner_max_jerk[XYZE], // M205 XYZE planner.max_jerk[XYZE] - planner_junction_deviation_mm; // M205 J planner.junction_deviation_mm + xyze_float_t planner_max_jerk; // M205 XYZE planner.max_jerk + float planner_junction_deviation_mm; // M205 J planner.junction_deviation_mm - float home_offset[XYZ]; // M206 XYZ / M665 TPZ + xyz_pos_t home_offset; // M206 XYZ / M665 TPZ #if HAS_HOTEND_OFFSET - float hotend_offset[XYZ][HOTENDS - 1]; // M218 XYZ + xyz_pos_t hotend_offset[HOTENDS - 1]; // M218 XYZ #endif // @@ -181,7 +181,7 @@ typedef struct SettingsDataStruct { // HAS_BED_PROBE // - float probe_offset[XYZ]; + xyz_pos_t probe_offset; // // ABL_PLANAR @@ -192,10 +192,9 @@ typedef struct SettingsDataStruct { // AUTO_BED_LEVELING_BILINEAR // uint8_t grid_max_x, grid_max_y; // GRID_MAX_POINTS_X, GRID_MAX_POINTS_Y - int bilinear_grid_spacing[2], - bilinear_start[2]; // G29 L F + xy_int_t bilinear_grid_spacing, bilinear_start; // G29 L F #if ENABLED(AUTO_BED_LEVELING_BILINEAR) - float z_values[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y]; // G29 + bed_mesh_t z_values; // G29 #else float z_values[3][3]; #endif @@ -220,13 +219,13 @@ typedef struct SettingsDataStruct { // DELTA / [XYZ]_DUAL_ENDSTOPS // #if ENABLED(DELTA) - float delta_height, // M666 H - delta_endstop_adj[ABC], // M666 XYZ - delta_radius, // M665 R + float delta_height; // M666 H + abc_float_t delta_endstop_adj; // M666 XYZ + float delta_radius, // M665 R delta_diagonal_rod, // M665 L delta_segments_per_second, // M665 S - delta_calibration_radius, // M665 B - delta_tower_angle_trim[ABC]; // M665 XYZ + delta_calibration_radius; // M665 B + abc_float_t delta_tower_angle_trim; // M665 XYZ #elif EITHER(X_DUAL_ENDSTOPS, Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS float x2_endstop_adj, // M666 X y2_endstop_adj, // M666 Y @@ -302,7 +301,7 @@ typedef struct SettingsDataStruct { // // CNC_COORDINATE_SYSTEMS // - float coordinate_system[MAX_COORDINATE_SYSTEMS][XYZ]; // G54-G59.3 + xyz_pos_t coordinate_system[MAX_COORDINATE_SYSTEMS]; // G54-G59.3 // // SKEW_CORRECTION @@ -326,7 +325,7 @@ typedef struct SettingsDataStruct { // // BACKLASH_COMPENSATION // - float backlash_distance_mm[XYZ]; // M425 X Y Z + xyz_float_t backlash_distance_mm; // M425 X Y Z uint8_t backlash_correction; // M425 F float backlash_smoothing_mm; // M425 S @@ -355,7 +354,7 @@ uint16_t MarlinSettings::datasize() { return sizeof(SettingsData); } #endif void MarlinSettings::postprocess() { - const float oldpos[XYZE] = { current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS] }; + xyze_pos_t oldpos = current_position; // steps per s2 needs to be updated to agree with units per s2 planner.reset_acceleration_rates(); @@ -408,7 +407,7 @@ void MarlinSettings::postprocess() { planner.refresh_positioning(); // Various factors can change the current position - if (memcmp(oldpos, current_position, sizeof(oldpos))) + if (oldpos != current_position) report_current_position(); } @@ -522,7 +521,7 @@ void MarlinSettings::postprocess() { EEPROM_WRITE(dummy); #endif #else - const float planner_max_jerk[XYZE] = { float(DEFAULT_EJERK) }; + const xyze_pos_t planner_max_jerk = { 10, 10, 0.4, float(DEFAULT_EJERK) }; EEPROM_WRITE(planner_max_jerk); #endif @@ -544,7 +543,7 @@ void MarlinSettings::postprocess() { EEPROM_WRITE(scara_home_offset); #else #if !HAS_HOME_OFFSET - const float home_offset[XYZ] = { 0 }; + const xyz_pos_t home_offset{0}; #endif EEPROM_WRITE(home_offset); #endif @@ -552,7 +551,7 @@ void MarlinSettings::postprocess() { #if HAS_HOTEND_OFFSET // Skip hotend 0 which must be 0 for (uint8_t e = 1; e < HOTENDS; e++) - LOOP_XYZ(i) EEPROM_WRITE(hotend_offset[i][e]); + EEPROM_WRITE(hotend_offset[e]); #endif } @@ -618,7 +617,7 @@ void MarlinSettings::postprocess() { // Probe Z Offset // { - _FIELD_TEST(probe_offset[Z_AXIS]); + _FIELD_TEST(probe_offset.z); EEPROM_WRITE(probe_offset); } @@ -653,7 +652,7 @@ void MarlinSettings::postprocess() { #else // For disabled Bilinear Grid write an empty 3x3 grid const uint8_t grid_max_x = 3, grid_max_y = 3; - const int bilinear_start[2] = { 0 }, bilinear_grid_spacing[2] = { 0 }; + const xy_int_t bilinear_start{0}, bilinear_grid_spacing{0}; dummy = 0; EEPROM_WRITE(grid_max_x); EEPROM_WRITE(grid_max_y); @@ -1033,7 +1032,7 @@ void MarlinSettings::postprocess() { // TMC StallGuard threshold // { - tmc_sgt_t tmc_sgt = { 0 }; + tmc_sgt_t tmc_sgt{0}; #if USE_SENSORLESS #if X_SENSORLESS tmc_sgt.X = stepperX.homing_threshold(); @@ -1138,8 +1137,8 @@ void MarlinSettings::postprocess() { #if HAS_MOTOR_CURRENT_PWM EEPROM_WRITE(stepper.motor_current_setting); #else - const uint32_t dummyui32[XYZ] = { 0 }; - EEPROM_WRITE(dummyui32); + const xyz_ulong_t no_current{0}; + EEPROM_WRITE(no_current); #endif } @@ -1152,7 +1151,7 @@ void MarlinSettings::postprocess() { #if ENABLED(CNC_COORDINATE_SYSTEMS) EEPROM_WRITE(gcode.coordinate_system); #else - const float coordinate_system[MAX_COORDINATE_SYSTEMS][XYZ] = { { 0 } }; + const xyz_pos_t coordinate_system[MAX_COORDINATE_SYSTEMS] = { { 0 } }; EEPROM_WRITE(coordinate_system); #endif @@ -1189,10 +1188,10 @@ void MarlinSettings::postprocess() { // { #if ENABLED(BACKLASH_GCODE) - const float (&backlash_distance_mm)[XYZ] = backlash.distance_mm; + const xyz_float_t &backlash_distance_mm = backlash.distance_mm; const uint8_t &backlash_correction = backlash.correction; #else - const float backlash_distance_mm[XYZ] = { 0 }; + const xyz_float_t backlash_distance_mm{0}; const uint8_t backlash_correction = 0; #endif #if ENABLED(BACKLASH_GCODE) && defined(BACKLASH_SMOOTHING_MM) @@ -1341,7 +1340,7 @@ void MarlinSettings::postprocess() { EEPROM_READ(scara_home_offset); #else #if !HAS_HOME_OFFSET - float home_offset[XYZ]; + xyz_pos_t home_offset; #endif EEPROM_READ(home_offset); #endif @@ -1354,7 +1353,7 @@ void MarlinSettings::postprocess() { #if HAS_HOTEND_OFFSET // Skip hotend 0 which must be 0 for (uint8_t e = 1; e < HOTENDS; e++) - LOOP_XYZ(i) EEPROM_READ(hotend_offset[i][e]); + EEPROM_READ(hotend_offset[e]); #endif } @@ -1418,12 +1417,11 @@ void MarlinSettings::postprocess() { // Probe Z Offset // { - _FIELD_TEST(probe_offset[Z_AXIS]); - + _FIELD_TEST(probe_offset); #if HAS_BED_PROBE - float (&zpo)[XYZ] = probe_offset; + xyz_pos_t &zpo = probe_offset; #else - float zpo[XYZ]; + xyz_pos_t zpo; #endif EEPROM_READ(zpo); } @@ -1457,7 +1455,7 @@ void MarlinSettings::postprocess() { #endif // AUTO_BED_LEVELING_BILINEAR { // Skip past disabled (or stale) Bilinear Grid data - int bgs[2], bs[2]; + xy_int_t bgs, bs; EEPROM_READ(bgs); EEPROM_READ(bs); for (uint16_t q = grid_max_x * grid_max_y; q--;) EEPROM_READ(dummy); @@ -1940,7 +1938,7 @@ void MarlinSettings::postprocess() { if (!validating) (void)gcode.select_coordinate_system(-1); // Go back to machine space EEPROM_READ(gcode.coordinate_system); #else - float coordinate_system[MAX_COORDINATE_SYSTEMS][XYZ]; + xyz_pos_t coordinate_system[MAX_COORDINATE_SYSTEMS]; EEPROM_READ(coordinate_system); #endif } @@ -1989,7 +1987,7 @@ void MarlinSettings::postprocess() { // { #if ENABLED(BACKLASH_GCODE) - float (&backlash_distance_mm)[XYZ] = backlash.distance_mm; + xyz_float_t &backlash_distance_mm = backlash.distance_mm; uint8_t &backlash_correction = backlash.correction; #else float backlash_distance_mm[XYZ]; @@ -2231,11 +2229,9 @@ void MarlinSettings::reset() { #ifndef DEFAULT_ZJERK #define DEFAULT_ZJERK 0 #endif - planner.max_jerk[X_AXIS] = DEFAULT_XJERK; - planner.max_jerk[Y_AXIS] = DEFAULT_YJERK; - planner.max_jerk[Z_AXIS] = DEFAULT_ZJERK; + planner.max_jerk.set(DEFAULT_XJERK, DEFAULT_YJERK, DEFAULT_ZJERK); #if !BOTH(JUNCTION_DEVIATION, LIN_ADVANCE) - planner.max_jerk[E_AXIS] = DEFAULT_EJERK; + planner.max_jerk.e = DEFAULT_EJERK; #endif #endif @@ -2244,9 +2240,9 @@ void MarlinSettings::reset() { #endif #if HAS_SCARA_OFFSET - ZERO(scara_home_offset); + scara_home_offset.reset(); #elif HAS_HOME_OFFSET - ZERO(home_offset); + home_offset.reset(); #endif #if HAS_HOTEND_OFFSET @@ -2277,17 +2273,16 @@ void MarlinSettings::reset() { toolchange_settings.retract_speed = TOOLCHANGE_FIL_SWAP_RETRACT_SPEED; #endif #if ENABLED(TOOLCHANGE_PARK) - toolchange_settings.change_point = TOOLCHANGE_PARK_XY; + constexpr xyz_pos_t tpxy = TOOLCHANGE_PARK_XY; + toolchange_settings.change_point = tpxy; #endif toolchange_settings.z_raise = TOOLCHANGE_ZRAISE; #endif #if ENABLED(BACKLASH_GCODE) backlash.correction = (BACKLASH_CORRECTION) * 255; - constexpr float tmp[XYZ] = BACKLASH_DISTANCE_MM; - backlash.distance_mm[X_AXIS] = tmp[X_AXIS]; - backlash.distance_mm[Y_AXIS] = tmp[Y_AXIS]; - backlash.distance_mm[Z_AXIS] = tmp[Z_AXIS]; + constexpr xyz_float_t tmp = BACKLASH_DISTANCE_MM; + backlash.distance_mm = tmp; #ifdef BACKLASH_SMOOTHING_MM backlash.smoothing_mm = BACKLASH_SMOOTHING_MM; #endif @@ -2346,14 +2341,14 @@ void MarlinSettings::reset() { // #if ENABLED(DELTA) - const float adj[ABC] = DELTA_ENDSTOP_ADJ, dta[ABC] = DELTA_TOWER_ANGLE_TRIM; + const abc_float_t adj = DELTA_ENDSTOP_ADJ, dta = DELTA_TOWER_ANGLE_TRIM; delta_height = DELTA_HEIGHT; - COPY(delta_endstop_adj, adj); + delta_endstop_adj = adj; delta_radius = DELTA_RADIUS; delta_diagonal_rod = DELTA_DIAGONAL_ROD; delta_segments_per_second = DELTA_SEGMENTS_PER_SECOND; delta_calibration_radius = DELTA_CALIBRATION_RADIUS; - COPY(delta_tower_angle_trim, dta); + delta_tower_angle_trim = dta; #elif EITHER(X_DUAL_ENDSTOPS, Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS @@ -2769,11 +2764,11 @@ void MarlinSettings::reset() { , " J", LINEAR_UNIT(planner.junction_deviation_mm) #endif #if HAS_CLASSIC_JERK - , " X", LINEAR_UNIT(planner.max_jerk[X_AXIS]) - , " Y", LINEAR_UNIT(planner.max_jerk[Y_AXIS]) - , " Z", LINEAR_UNIT(planner.max_jerk[Z_AXIS]) + , " X", LINEAR_UNIT(planner.max_jerk.x) + , " Y", LINEAR_UNIT(planner.max_jerk.y) + , " Z", LINEAR_UNIT(planner.max_jerk.z) #if !BOTH(JUNCTION_DEVIATION, LIN_ADVANCE) - , " E", LINEAR_UNIT(planner.max_jerk[E_AXIS]) + , " E", LINEAR_UNIT(planner.max_jerk.e) #endif #endif ); @@ -2783,10 +2778,10 @@ void MarlinSettings::reset() { CONFIG_ECHO_START(); SERIAL_ECHOLNPAIR(" M206" #if IS_CARTESIAN - " X", LINEAR_UNIT(home_offset[X_AXIS]), - " Y", LINEAR_UNIT(home_offset[Y_AXIS]), + " X", LINEAR_UNIT(home_offset.x), + " Y", LINEAR_UNIT(home_offset.y), #endif - " Z", LINEAR_UNIT(home_offset[Z_AXIS]) + " Z", LINEAR_UNIT(home_offset.z) ); #endif @@ -2796,9 +2791,9 @@ void MarlinSettings::reset() { for (uint8_t e = 1; e < HOTENDS; e++) { SERIAL_ECHOPAIR( " M218 T", (int)e, - " X", LINEAR_UNIT(hotend_offset[X_AXIS][e]), " Y", LINEAR_UNIT(hotend_offset[Y_AXIS][e]) + " X", LINEAR_UNIT(hotend_offset[e].x), " Y", LINEAR_UNIT(hotend_offset[e].y) ); - SERIAL_ECHOLNPAIR_F(" Z", LINEAR_UNIT(hotend_offset[Z_AXIS][e]), 3); + SERIAL_ECHOLNPAIR_F(" Z", LINEAR_UNIT(hotend_offset[e].z), 3); } #endif @@ -2901,9 +2896,9 @@ void MarlinSettings::reset() { CONFIG_ECHO_START(); SERIAL_ECHOLNPAIR( " M665 S", delta_segments_per_second - , " P", scara_home_offset[A_AXIS] - , " T", scara_home_offset[B_AXIS] - , " Z", LINEAR_UNIT(scara_home_offset[Z_AXIS]) + , " P", scara_home_offset.a + , " T", scara_home_offset.b + , " Z", LINEAR_UNIT(scara_home_offset.z) ); #elif ENABLED(DELTA) @@ -2911,9 +2906,9 @@ void MarlinSettings::reset() { CONFIG_ECHO_HEADING("Endstop adjustment:"); CONFIG_ECHO_START(); SERIAL_ECHOLNPAIR( - " M666 X", LINEAR_UNIT(delta_endstop_adj[A_AXIS]) - , " Y", LINEAR_UNIT(delta_endstop_adj[B_AXIS]) - , " Z", LINEAR_UNIT(delta_endstop_adj[C_AXIS]) + " M666 X", LINEAR_UNIT(delta_endstop_adj.a) + , " Y", LINEAR_UNIT(delta_endstop_adj.b) + , " Z", LINEAR_UNIT(delta_endstop_adj.c) ); CONFIG_ECHO_HEADING("Delta settings: L R H S B XYZ"); @@ -2924,9 +2919,9 @@ void MarlinSettings::reset() { , " H", LINEAR_UNIT(delta_height) , " S", delta_segments_per_second , " B", LINEAR_UNIT(delta_calibration_radius) - , " X", LINEAR_UNIT(delta_tower_angle_trim[A_AXIS]) - , " Y", LINEAR_UNIT(delta_tower_angle_trim[B_AXIS]) - , " Z", LINEAR_UNIT(delta_tower_angle_trim[C_AXIS]) + , " X", LINEAR_UNIT(delta_tower_angle_trim.a) + , " Y", LINEAR_UNIT(delta_tower_angle_trim.b) + , " Z", LINEAR_UNIT(delta_tower_angle_trim.c) ); #elif EITHER(X_DUAL_ENDSTOPS, Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS @@ -3072,9 +3067,9 @@ void MarlinSettings::reset() { say_units(true); } CONFIG_ECHO_START(); - SERIAL_ECHOLNPAIR(" M851 X", LINEAR_UNIT(probe_offset[X_AXIS]), - " Y", LINEAR_UNIT(probe_offset[Y_AXIS]), - " Z", LINEAR_UNIT(probe_offset[Z_AXIS])); + SERIAL_ECHOLNPAIR(" M851 X", LINEAR_UNIT(probe_offset.x), + " Y", LINEAR_UNIT(probe_offset.y), + " Z", LINEAR_UNIT(probe_offset.z)); #endif /** @@ -3421,9 +3416,9 @@ void MarlinSettings::reset() { CONFIG_ECHO_START(); SERIAL_ECHOLNPAIR( " M425 F", backlash.get_correction(), - " X", LINEAR_UNIT(backlash.distance_mm[X_AXIS]), - " Y", LINEAR_UNIT(backlash.distance_mm[Y_AXIS]), - " Z", LINEAR_UNIT(backlash.distance_mm[Z_AXIS]) + " X", LINEAR_UNIT(backlash.distance_mm.x), + " Y", LINEAR_UNIT(backlash.distance_mm.y), + " Z", LINEAR_UNIT(backlash.distance_mm.z) #ifdef BACKLASH_SMOOTHING_MM , " S", LINEAR_UNIT(backlash.smoothing_mm) #endif diff --git a/Marlin/src/module/delta.cpp b/Marlin/src/module/delta.cpp index b1b943b94..8ef64b09a 100644 --- a/Marlin/src/module/delta.cpp +++ b/Marlin/src/module/delta.cpp @@ -50,17 +50,16 @@ #include "../core/debug_out.h" // Initialized by settings.load() -float delta_height, - delta_endstop_adj[ABC] = { 0 }, - delta_radius, +float delta_height; +abc_float_t delta_endstop_adj{0}; +float delta_radius, delta_diagonal_rod, delta_segments_per_second, - delta_calibration_radius, - delta_tower_angle_trim[ABC]; - -float delta_tower[ABC][2], - delta_diagonal_rod_2_tower[ABC], - delta_clip_start_height = Z_MAX_POS; + delta_calibration_radius; +abc_float_t delta_tower_angle_trim; +xy_float_t delta_tower[ABC]; +abc_float_t delta_diagonal_rod_2_tower; +float delta_clip_start_height = Z_MAX_POS; float delta_safe_distance_from_top(); @@ -69,17 +68,17 @@ float delta_safe_distance_from_top(); * settings have been changed (e.g., by M665). */ void recalc_delta_settings() { - const float trt[ABC] = DELTA_RADIUS_TRIM_TOWER, - drt[ABC] = DELTA_DIAGONAL_ROD_TRIM_TOWER; - delta_tower[A_AXIS][X_AXIS] = cos(RADIANS(210 + delta_tower_angle_trim[A_AXIS])) * (delta_radius + trt[A_AXIS]); // front left tower - delta_tower[A_AXIS][Y_AXIS] = sin(RADIANS(210 + delta_tower_angle_trim[A_AXIS])) * (delta_radius + trt[A_AXIS]); - delta_tower[B_AXIS][X_AXIS] = cos(RADIANS(330 + delta_tower_angle_trim[B_AXIS])) * (delta_radius + trt[B_AXIS]); // front right tower - delta_tower[B_AXIS][Y_AXIS] = sin(RADIANS(330 + delta_tower_angle_trim[B_AXIS])) * (delta_radius + trt[B_AXIS]); - delta_tower[C_AXIS][X_AXIS] = cos(RADIANS( 90 + delta_tower_angle_trim[C_AXIS])) * (delta_radius + trt[C_AXIS]); // back middle tower - delta_tower[C_AXIS][Y_AXIS] = sin(RADIANS( 90 + delta_tower_angle_trim[C_AXIS])) * (delta_radius + trt[C_AXIS]); - delta_diagonal_rod_2_tower[A_AXIS] = sq(delta_diagonal_rod + drt[A_AXIS]); - delta_diagonal_rod_2_tower[B_AXIS] = sq(delta_diagonal_rod + drt[B_AXIS]); - delta_diagonal_rod_2_tower[C_AXIS] = sq(delta_diagonal_rod + drt[C_AXIS]); + constexpr abc_float_t trt = DELTA_RADIUS_TRIM_TOWER, + drt = DELTA_DIAGONAL_ROD_TRIM_TOWER; + delta_tower[A_AXIS].set(cos(RADIANS(210 + delta_tower_angle_trim.a)) * (delta_radius + trt.a), // front left tower + sin(RADIANS(210 + delta_tower_angle_trim.a)) * (delta_radius + trt.a)); + delta_tower[B_AXIS].set(cos(RADIANS(330 + delta_tower_angle_trim.b)) * (delta_radius + trt.b), // front right tower + sin(RADIANS(330 + delta_tower_angle_trim.b)) * (delta_radius + trt.b)); + delta_tower[C_AXIS].set(cos(RADIANS( 90 + delta_tower_angle_trim.c)) * (delta_radius + trt.c), // back middle tower + sin(RADIANS( 90 + delta_tower_angle_trim.c)) * (delta_radius + trt.c)); + delta_diagonal_rod_2_tower.set(sq(delta_diagonal_rod + drt.a), + sq(delta_diagonal_rod + drt.b), + sq(delta_diagonal_rod + drt.c)); update_software_endstops(Z_AXIS); set_all_unhomed(); } @@ -101,18 +100,16 @@ void recalc_delta_settings() { */ #define DELTA_DEBUG(VAR) do { \ - SERIAL_ECHOLNPAIR("Cartesian X", VAR[X_AXIS], " Y", VAR[Y_AXIS], " Z", VAR[Z_AXIS]); \ - SERIAL_ECHOLNPAIR("Delta A", delta[A_AXIS], " B", delta[B_AXIS], " C", delta[C_AXIS]); \ + SERIAL_ECHOLNPAIR("Cartesian X", VAR.x, " Y", VAR.y, " Z", VAR.z); \ + SERIAL_ECHOLNPAIR("Delta A", delta.a, " B", delta.b, " C", delta.c); \ }while(0) -void inverse_kinematics(const float (&raw)[XYZ]) { +void inverse_kinematics(const xyz_pos_t &raw) { #if HAS_HOTEND_OFFSET // Delta hotend offsets must be applied in Cartesian space with no "spoofing" - const float pos[XYZ] = { - raw[X_AXIS] - hotend_offset[X_AXIS][active_extruder], - raw[Y_AXIS] - hotend_offset[Y_AXIS][active_extruder], - raw[Z_AXIS] - }; + xyz_pos_t pos = { raw.x - hotend_offset[active_extruder].x, + raw.y - hotend_offset[active_extruder].y, + raw.z }; DELTA_IK(pos); //DELTA_DEBUG(pos); #else @@ -126,12 +123,12 @@ void inverse_kinematics(const float (&raw)[XYZ]) { * effector has the full range of XY motion. */ float delta_safe_distance_from_top() { - float cartesian[XYZ] = { 0, 0, 0 }; + xyz_pos_t cartesian{0}; inverse_kinematics(cartesian); - float centered_extent = delta[A_AXIS]; - cartesian[Y_AXIS] = DELTA_PRINTABLE_RADIUS; + const float centered_extent = delta.a; + cartesian.y = DELTA_PRINTABLE_RADIUS; inverse_kinematics(cartesian); - return ABS(centered_extent - delta[A_AXIS]); + return ABS(centered_extent - delta.a); } /** @@ -161,7 +158,7 @@ float delta_safe_distance_from_top() { */ void forward_kinematics_DELTA(const float &z1, const float &z2, const float &z3) { // Create a vector in old coordinates along x axis of new coordinate - const float p12[3] = { delta_tower[B_AXIS][X_AXIS] - delta_tower[A_AXIS][X_AXIS], delta_tower[B_AXIS][Y_AXIS] - delta_tower[A_AXIS][Y_AXIS], z2 - z1 }, + const float p12[3] = { delta_tower[B_AXIS].x - delta_tower[A_AXIS].x, delta_tower[B_AXIS].y - delta_tower[A_AXIS].y, z2 - z1 }, // Get the reciprocal of Magnitude of vector. d2 = sq(p12[0]) + sq(p12[1]) + sq(p12[2]), inv_d = RSQRT(d2), @@ -170,7 +167,7 @@ void forward_kinematics_DELTA(const float &z1, const float &z2, const float &z3) ex[3] = { p12[0] * inv_d, p12[1] * inv_d, p12[2] * inv_d }, // Get the vector from the origin of the new system to the third point. - p13[3] = { delta_tower[C_AXIS][X_AXIS] - delta_tower[A_AXIS][X_AXIS], delta_tower[C_AXIS][Y_AXIS] - delta_tower[A_AXIS][Y_AXIS], z3 - z1 }, + p13[3] = { delta_tower[C_AXIS].x - delta_tower[A_AXIS].x, delta_tower[C_AXIS].y - delta_tower[A_AXIS].y, z3 - z1 }, // Use the dot product to find the component of this vector on the X axis. i = ex[0] * p13[0] + ex[1] * p13[1] + ex[2] * p13[2], @@ -198,16 +195,16 @@ void forward_kinematics_DELTA(const float &z1, const float &z2, const float &z3) // We now have the d, i and j values defined in Wikipedia. // Plug them into the equations defined in Wikipedia for Xnew, Ynew and Znew - Xnew = (delta_diagonal_rod_2_tower[A_AXIS] - delta_diagonal_rod_2_tower[B_AXIS] + d2) * inv_d * 0.5, - Ynew = ((delta_diagonal_rod_2_tower[A_AXIS] - delta_diagonal_rod_2_tower[C_AXIS] + sq(i) + j2) * 0.5 - i * Xnew) * inv_j, - Znew = SQRT(delta_diagonal_rod_2_tower[A_AXIS] - HYPOT2(Xnew, Ynew)); + Xnew = (delta_diagonal_rod_2_tower.a - delta_diagonal_rod_2_tower.b + d2) * inv_d * 0.5, + Ynew = ((delta_diagonal_rod_2_tower.a - delta_diagonal_rod_2_tower.c + sq(i) + j2) * 0.5 - i * Xnew) * inv_j, + Znew = SQRT(delta_diagonal_rod_2_tower.a - HYPOT2(Xnew, Ynew)); // Start from the origin of the old coordinates and add vectors in the // old coords that represent the Xnew, Ynew and Znew to find the point // in the old system. - cartes[X_AXIS] = delta_tower[A_AXIS][X_AXIS] + ex[0] * Xnew + ey[0] * Ynew - ez[0] * Znew; - cartes[Y_AXIS] = delta_tower[A_AXIS][Y_AXIS] + ex[1] * Xnew + ey[1] * Ynew - ez[1] * Znew; - cartes[Z_AXIS] = z1 + ex[2] * Xnew + ey[2] * Ynew - ez[2] * Znew; + cartes.set(delta_tower[A_AXIS].x + ex[0] * Xnew + ey[0] * Ynew - ez[0] * Znew, + delta_tower[A_AXIS].y + ex[1] * Xnew + ey[1] * Ynew - ez[1] * Znew, + z1 + ex[2] * Xnew + ey[2] * Ynew - ez[2] * Znew); } /** @@ -217,8 +214,8 @@ void forward_kinematics_DELTA(const float &z1, const float &z2, const float &z3) void home_delta() { if (DEBUGGING(LEVELING)) DEBUG_POS(">>> home_delta", current_position); // Init the current position of all carriages to 0,0,0 - ZERO(current_position); - ZERO(destination); + current_position.reset(); + destination.reset(); sync_plan_position(); // Disable stealthChop if used. Enable diag1 pin on driver. @@ -231,9 +228,9 @@ void home_delta() { #endif // Move all carriages together linearly until an endstop is hit. - current_position[Z_AXIS] = (delta_height + 10 + current_position.z = (delta_height + 10 #if HAS_BED_PROBE - - probe_offset[Z_AXIS] + - probe_offset.z #endif ); line_to_current_position(homing_feedrate(X_AXIS)); diff --git a/Marlin/src/module/delta.h b/Marlin/src/module/delta.h index 24af5daa3..f2e602fe1 100644 --- a/Marlin/src/module/delta.h +++ b/Marlin/src/module/delta.h @@ -25,17 +25,18 @@ * delta.h - Delta-specific functions */ -extern float delta_height, - delta_endstop_adj[ABC], - delta_radius, +#include "../core/types.h" + +extern float delta_height; +extern abc_float_t delta_endstop_adj; +extern float delta_radius, delta_diagonal_rod, delta_segments_per_second, - delta_calibration_radius, - delta_tower_angle_trim[ABC]; - -extern float delta_tower[ABC][2], - delta_diagonal_rod_2_tower[ABC], - delta_clip_start_height; + delta_calibration_radius; +extern abc_float_t delta_tower_angle_trim; +extern xy_float_t delta_tower[ABC]; +extern abc_float_t delta_diagonal_rod_2_tower; +extern float delta_clip_start_height; /** * Recalculate factors used for delta kinematics whenever @@ -63,24 +64,16 @@ void recalc_delta_settings(); */ // Macro to obtain the Z position of an individual tower -#define DELTA_Z(V,T) V[Z_AXIS] + SQRT( \ +#define DELTA_Z(V,T) V.z + SQRT( \ delta_diagonal_rod_2_tower[T] - HYPOT2( \ - delta_tower[T][X_AXIS] - V[X_AXIS], \ - delta_tower[T][Y_AXIS] - V[Y_AXIS] \ + delta_tower[T].x - V.x, \ + delta_tower[T].y - V.y \ ) \ ) -#define DELTA_IK(V) do { \ - delta[A_AXIS] = DELTA_Z(V, A_AXIS); \ - delta[B_AXIS] = DELTA_Z(V, B_AXIS); \ - delta[C_AXIS] = DELTA_Z(V, C_AXIS); \ -}while(0) +#define DELTA_IK(V) delta.set(DELTA_Z(V, A_AXIS), DELTA_Z(V, B_AXIS), DELTA_Z(V, C_AXIS)) -void inverse_kinematics(const float (&raw)[XYZ]); -FORCE_INLINE void inverse_kinematics(const float (&raw)[XYZE]) { - const float raw_xyz[XYZ] = { raw[X_AXIS], raw[Y_AXIS], raw[Z_AXIS] }; - inverse_kinematics(raw_xyz); -} +void inverse_kinematics(const xyz_pos_t &raw); /** * Calculate the highest Z position where the @@ -115,8 +108,8 @@ float delta_safe_distance_from_top(); */ void forward_kinematics_DELTA(const float &z1, const float &z2, const float &z3); -FORCE_INLINE void forward_kinematics_DELTA(const float (&point)[ABC]) { - forward_kinematics_DELTA(point[A_AXIS], point[B_AXIS], point[C_AXIS]); +FORCE_INLINE void forward_kinematics_DELTA(const abc_float_t &point) { + forward_kinematics_DELTA(point.a, point.b, point.c); } void home_delta(); diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index e2351150b..e93f4f528 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -70,7 +70,7 @@ #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) #include "../core/debug_out.h" -#define XYZ_CONSTS(type, array, CONFIG) const PROGMEM type array##_P[XYZ] = { X_##CONFIG, Y_##CONFIG, Z_##CONFIG } +#define XYZ_CONSTS(T, NAME, OPT) const PROGMEM XYZval NAME##_P = { X_##OPT, Y_##OPT, Z_##OPT } XYZ_CONSTS(float, base_min_pos, MIN_POS); XYZ_CONSTS(float, base_max_pos, MAX_POS); @@ -99,7 +99,7 @@ bool relative_mode; // = false; * Used by 'line_to_current_position' to do a move after changing it. * Used by 'sync_plan_position' to update 'planner.position'. */ -float current_position[XYZE] = { X_HOME_POS, Y_HOME_POS, Z_HOME_POS }; +xyze_pos_t current_position = { X_HOME_POS, Y_HOME_POS, Z_HOME_POS }; /** * Cartesian Destination @@ -107,7 +107,7 @@ float current_position[XYZE] = { X_HOME_POS, Y_HOME_POS, Z_HOME_POS }; * and expected by functions like 'prepare_move_to_destination'. * G-codes can set destination using 'get_destination_from_command' */ -float destination[XYZE]; // = { 0 } +xyze_pos_t destination; // {0} // The active extruder (tool). Set with T command. #if EXTRUDERS > 1 @@ -116,16 +116,17 @@ float destination[XYZE]; // = { 0 } // Extruder offsets #if HAS_HOTEND_OFFSET - float hotend_offset[XYZ][HOTENDS]; // Initialized by settings.load() + xyz_pos_t hotend_offset[HOTENDS]; // Initialized by settings.load() void reset_hotend_offsets() { constexpr float tmp[XYZ][HOTENDS] = { HOTEND_OFFSET_X, HOTEND_OFFSET_Y, HOTEND_OFFSET_Z }; static_assert( - tmp[X_AXIS][0] == 0 && tmp[Y_AXIS][0] == 0 && tmp[Z_AXIS][0] == 0, + !tmp[X_AXIS][0] && !tmp[Y_AXIS][0] && !tmp[Z_AXIS][0], "Offsets for the first hotend must be 0.0." ); - LOOP_XYZ(i) HOTEND_LOOP() hotend_offset[i][e] = tmp[i][e]; + // Transpose from [XYZ][HOTENDS] to [HOTENDS][XYZ] + HOTEND_LOOP() LOOP_XYZ(a) hotend_offset[e][a] = tmp[a][e]; #if ENABLED(DUAL_X_CARRIAGE) - hotend_offset[X_AXIS][1] = _MAX(X2_HOME_POS, X2_MAX_POS); + hotend_offset[1].x = _MAX(X2_HOME_POS, X2_MAX_POS); #endif } #endif @@ -148,14 +149,14 @@ const feedRate_t homing_feedrate_mm_s[XYZ] PROGMEM = { }; // Cartesian conversion result goes here: -float cartes[XYZ]; +xyz_pos_t cartes; #if IS_KINEMATIC - float delta[ABC]; + abc_pos_t delta; #if HAS_SCARA_OFFSET - float scara_home_offset[ABC]; + abc_pos_t scara_home_offset; #endif #if HAS_SOFTWARE_ENDSTOPS @@ -176,16 +177,16 @@ float cartes[XYZ]; */ #if HAS_POSITION_SHIFT // The distance that XYZ has been offset by G92. Reset by G28. - float position_shift[XYZ] = { 0 }; + xyz_pos_t position_shift{0}; #endif #if HAS_HOME_OFFSET // This offset is added to the configured home position. // Set by M206, M428, or menu item. Saved to EEPROM. - float home_offset[XYZ] = { 0 }; + xyz_pos_t home_offset{0}; #endif #if HAS_HOME_OFFSET && HAS_POSITION_SHIFT // The above two are combined to save on computes - float workspace_offset[XYZ] = { 0 }; + xyz_pos_t workspace_offset{0}; #endif #if HAS_ABL_NOT_UBL @@ -196,10 +197,8 @@ float cartes[XYZ]; * Output the current position to serial */ void report_current_position() { - SERIAL_ECHOPAIR("X:", LOGICAL_X_POSITION(current_position[X_AXIS])); - SERIAL_ECHOPAIR(" Y:", LOGICAL_Y_POSITION(current_position[Y_AXIS])); - SERIAL_ECHOPAIR(" Z:", LOGICAL_Z_POSITION(current_position[Z_AXIS])); - SERIAL_ECHOPAIR(" E:", current_position[E_AXIS]); + const xyz_pos_t lpos = current_position.asLogical(); + SERIAL_ECHOPAIR("X:", lpos.x, " Y:", lpos.y, " Z:", lpos.z, " E:", current_position.e); stepper.report_positions(); @@ -216,10 +215,10 @@ void report_current_position() { */ void sync_plan_position() { if (DEBUGGING(LEVELING)) DEBUG_POS("sync_plan_position", current_position); - planner.set_position_mm(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); + planner.set_position_mm(current_position); } -void sync_plan_position_e() { planner.set_e_position_mm(current_position[E_AXIS]); } +void sync_plan_position_e() { planner.set_e_position_mm(current_position.e); } /** * Get the stepper positions in the cartes[] array. @@ -244,10 +243,9 @@ void get_cartesian_from_steppers() { planner.get_axis_position_degrees(B_AXIS) ); #else - cartes[X_AXIS] = planner.get_axis_position_mm(X_AXIS); - cartes[Y_AXIS] = planner.get_axis_position_mm(Y_AXIS); + cartes.set(planner.get_axis_position_mm(X_AXIS), planner.get_axis_position_mm(Y_AXIS)); #endif - cartes[Z_AXIS] = planner.get_axis_position_mm(Z_AXIS); + cartes.z = planner.get_axis_position_mm(Z_AXIS); #endif } @@ -266,16 +264,16 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) { get_cartesian_from_steppers(); #if HAS_POSITION_MODIFIERS - float pos[XYZE] = { cartes[X_AXIS], cartes[Y_AXIS], cartes[Z_AXIS], current_position[E_AXIS] }; + xyze_pos_t pos = { cartes.x, cartes.y, cartes.z, current_position.e }; planner.unapply_modifiers(pos #if HAS_LEVELING , true #endif ); - const float (&cartes)[XYZE] = pos; + xyze_pos_t &cartes = pos; #endif if (axis == ALL_AXES) - COPY(current_position, cartes); + current_position = cartes; else current_position[axis] = cartes[axis]; } @@ -300,16 +298,12 @@ void line_to_current_position(const feedRate_t &fr_mm_s/*=feedrate_mm_s*/) { // UBL segmented line will do Z-only moves in single segment ubl.line_to_destination_segmented(scaled_fr_mm_s); #else - if ( current_position[X_AXIS] == destination[X_AXIS] - && current_position[Y_AXIS] == destination[Y_AXIS] - && current_position[Z_AXIS] == destination[Z_AXIS] - && current_position[E_AXIS] == destination[E_AXIS] - ) return; + if (current_position == destination) return; planner.buffer_line(destination, scaled_fr_mm_s, active_extruder); #endif - set_current_from_destination(); + current_position = destination; } #endif // IS_KINEMATIC @@ -355,39 +349,36 @@ void do_blocking_move_to(const float rx, const float ry, const float rz, const f REMEMBER(fr, feedrate_mm_s, xy_feedrate); - set_destination_from_current(); // sync destination at the start + destination = current_position; // sync destination at the start - if (DEBUGGING(LEVELING)) DEBUG_POS("set_destination_from_current", destination); + if (DEBUGGING(LEVELING)) DEBUG_POS("destination = current_position", destination); // when in the danger zone - if (current_position[Z_AXIS] > delta_clip_start_height) { - if (rz > delta_clip_start_height) { // staying in the danger zone - destination[X_AXIS] = rx; // move directly (uninterpolated) - destination[Y_AXIS] = ry; - destination[Z_AXIS] = rz; - prepare_internal_fast_move_to_destination(); // set_current_from_destination() + if (current_position.z > delta_clip_start_height) { + if (rz > delta_clip_start_height) { // staying in the danger zone + destination.set(rx, ry, rz); // move directly (uninterpolated) + prepare_internal_fast_move_to_destination(); // set current_position from destination if (DEBUGGING(LEVELING)) DEBUG_POS("danger zone move", current_position); return; } - destination[Z_AXIS] = delta_clip_start_height; - prepare_internal_fast_move_to_destination(); // set_current_from_destination() + destination.z = delta_clip_start_height; + prepare_internal_fast_move_to_destination(); // set current_position from destination if (DEBUGGING(LEVELING)) DEBUG_POS("zone border move", current_position); } - if (rz > current_position[Z_AXIS]) { // raising? - destination[Z_AXIS] = rz; - prepare_internal_fast_move_to_destination(z_feedrate); // set_current_from_destination() + if (rz > current_position.z) { // raising? + destination.z = rz; + prepare_internal_fast_move_to_destination(z_feedrate); // set current_position from destination if (DEBUGGING(LEVELING)) DEBUG_POS("z raise move", current_position); } - destination[X_AXIS] = rx; - destination[Y_AXIS] = ry; - prepare_internal_move_to_destination(); // set_current_from_destination() + destination.set(rx, ry); + prepare_internal_move_to_destination(); // set current_position from destination if (DEBUGGING(LEVELING)) DEBUG_POS("xy move", current_position); - if (rz < current_position[Z_AXIS]) { // lowering? - destination[Z_AXIS] = rz; - prepare_fast_move_to_destination(z_feedrate); // set_current_from_destination() + if (rz < current_position.z) { // lowering? + destination.z = rz; + prepare_internal_fast_move_to_destination(z_feedrate); // set current_position from destination if (DEBUGGING(LEVELING)) DEBUG_POS("z lower move", current_position); } @@ -395,39 +386,37 @@ void do_blocking_move_to(const float rx, const float ry, const float rz, const f if (!position_is_reachable(rx, ry)) return; - set_destination_from_current(); + destination = current_position; // If Z needs to raise, do it before moving XY - if (destination[Z_AXIS] < rz) { - destination[Z_AXIS] = rz; + if (destination.z < rz) { + destination.z = rz; prepare_internal_fast_move_to_destination(z_feedrate); } - destination[X_AXIS] = rx; - destination[Y_AXIS] = ry; + destination.set(rx, ry); prepare_internal_fast_move_to_destination(xy_feedrate); // If Z needs to lower, do it after moving XY - if (destination[Z_AXIS] > rz) { - destination[Z_AXIS] = rz; + if (destination.z > rz) { + destination.z = rz; prepare_internal_fast_move_to_destination(z_feedrate); } #else // If Z needs to raise, do it before moving XY - if (current_position[Z_AXIS] < rz) { - current_position[Z_AXIS] = rz; + if (current_position.z < rz) { + current_position.z = rz; line_to_current_position(z_feedrate); } - current_position[X_AXIS] = rx; - current_position[Y_AXIS] = ry; + current_position.set(rx, ry); line_to_current_position(xy_feedrate); // If Z needs to lower, do it after moving XY - if (current_position[Z_AXIS] > rz) { - current_position[Z_AXIS] = rz; + if (current_position.z > rz) { + current_position.z = rz; line_to_current_position(z_feedrate); } @@ -438,16 +427,16 @@ void do_blocking_move_to(const float rx, const float ry, const float rz, const f planner.synchronize(); } void do_blocking_move_to_x(const float &rx, const feedRate_t &fr_mm_s/*=0.0*/) { - do_blocking_move_to(rx, current_position[Y_AXIS], current_position[Z_AXIS], fr_mm_s); + do_blocking_move_to(rx, current_position.y, current_position.z, fr_mm_s); } void do_blocking_move_to_y(const float &ry, const feedRate_t &fr_mm_s/*=0.0*/) { - do_blocking_move_to(current_position[X_AXIS], ry, current_position[Z_AXIS], fr_mm_s); + do_blocking_move_to(current_position.x, ry, current_position.z, fr_mm_s); } void do_blocking_move_to_z(const float &rz, const feedRate_t &fr_mm_s/*=0.0*/) { - do_blocking_move_to(current_position[X_AXIS], current_position[Y_AXIS], rz, fr_mm_s); + do_blocking_move_to(current_position.x, current_position.y, rz, fr_mm_s); } void do_blocking_move_to_xy(const float &rx, const float &ry, const feedRate_t &fr_mm_s/*=0.0*/) { - do_blocking_move_to(rx, ry, current_position[Z_AXIS], fr_mm_s); + do_blocking_move_to(rx, ry, current_position.z, fr_mm_s); } // @@ -474,7 +463,10 @@ void restore_feedrate_and_scaling() { bool soft_endstops_enabled = true; // Software Endstops are based on the configured limits. - axis_limits_t soft_endstop[XYZ] = { { X_MIN_BED, X_MAX_BED }, { Y_MIN_BED, Y_MAX_BED }, { Z_MIN_POS, Z_MAX_POS } }; + axis_limits_t soft_endstop = { + { X_MIN_POS, Y_MIN_POS, Z_MIN_POS }, + { X_MAX_POS, Y_MAX_POS, Z_MAX_POS } + }; /** * Software endstops can be used to monitor the open end of @@ -496,33 +488,33 @@ void restore_feedrate_and_scaling() { if (axis == X_AXIS) { // In Dual X mode hotend_offset[X] is T1's home position - const float dual_max_x = _MAX(hotend_offset[X_AXIS][1], X2_MAX_POS); + const float dual_max_x = _MAX(hotend_offset[1].x, X2_MAX_POS); if (new_tool_index != 0) { // T1 can move from X2_MIN_POS to X2_MAX_POS or X2 home position (whichever is larger) - soft_endstop[X_AXIS].min = X2_MIN_POS; - soft_endstop[X_AXIS].max = dual_max_x; + soft_endstop.min.x = X2_MIN_POS; + soft_endstop.max.x = dual_max_x; } else if (dxc_is_duplicating()) { // In Duplication Mode, T0 can move as far left as X1_MIN_POS // but not so far to the right that T1 would move past the end - soft_endstop[X_AXIS].min = X1_MIN_POS; - soft_endstop[X_AXIS].max = _MIN(X1_MAX_POS, dual_max_x - duplicate_extruder_x_offset); + soft_endstop.min.x = X1_MIN_POS; + soft_endstop.max.x = _MIN(X1_MAX_POS, dual_max_x - duplicate_extruder_x_offset); } else { // In other modes, T0 can move from X1_MIN_POS to X1_MAX_POS - soft_endstop[X_AXIS].min = X1_MIN_POS; - soft_endstop[X_AXIS].max = X1_MAX_POS; + soft_endstop.min.x = X1_MIN_POS; + soft_endstop.max.x = X1_MAX_POS; } } #elif ENABLED(DELTA) - soft_endstop[axis].min = base_min_pos(axis); - soft_endstop[axis].max = (axis == Z_AXIS ? delta_height + soft_endstop.min[axis] = base_min_pos(axis); + soft_endstop.max[axis] = (axis == Z_AXIS ? delta_height #if HAS_BED_PROBE - - probe_offset[Z_AXIS] + - probe_offset.z #endif : base_max_pos(axis)); @@ -530,11 +522,11 @@ void restore_feedrate_and_scaling() { case X_AXIS: case Y_AXIS: // Get a minimum radius for clamping - delta_max_radius = _MIN(ABS(_MAX(soft_endstop[X_AXIS].min, soft_endstop[Y_AXIS].min)), soft_endstop[X_AXIS].max, soft_endstop[Y_AXIS].max); + delta_max_radius = _MIN(ABS(_MAX(soft_endstop.min.x, soft_endstop.min.y)), soft_endstop.max.x, soft_endstop.max.y); delta_max_radius_2 = sq(delta_max_radius); break; case Z_AXIS: - delta_clip_start_height = soft_endstop[axis].max - delta_safe_distance_from_top(); + delta_clip_start_height = soft_endstop.max[axis] - delta_safe_distance_from_top(); default: break; } @@ -544,25 +536,25 @@ void restore_feedrate_and_scaling() { // the movement limits must be shifted by the tool offset to // retain the same physical limit when other tools are selected. if (old_tool_index != new_tool_index) { - const float offs = hotend_offset[axis][new_tool_index] - hotend_offset[axis][old_tool_index]; - soft_endstop[axis].min += offs; - soft_endstop[axis].max += offs; + const float offs = hotend_offset[new_tool_index][axis] - hotend_offset[old_tool_index][axis]; + soft_endstop.min[axis] += offs; + soft_endstop.max[axis] += offs; } else { - const float offs = hotend_offset[axis][active_extruder]; - soft_endstop[axis].min = base_min_pos(axis) + offs; - soft_endstop[axis].max = base_max_pos(axis) + offs; + const float offs = hotend_offset[active_extruder][axis]; + soft_endstop.min[axis] = base_min_pos(axis) + offs; + soft_endstop.max[axis] = base_max_pos(axis) + offs; } #else - soft_endstop[axis].min = base_min_pos(axis); - soft_endstop[axis].max = base_max_pos(axis); + soft_endstop.min[axis] = base_min_pos(axis); + soft_endstop.max[axis] = base_max_pos(axis); #endif if (DEBUGGING(LEVELING)) - SERIAL_ECHOLNPAIR("Axis ", axis_codes[axis], " min:", soft_endstop[axis].min, " max:", soft_endstop[axis].max); + SERIAL_ECHOLNPAIR("Axis ", axis_codes[axis], " min:", soft_endstop.min[axis], " max:", soft_endstop.max[axis]); } /** @@ -571,7 +563,7 @@ void restore_feedrate_and_scaling() { * For DELTA/SCARA the XY constraint is based on the smallest * radius within the set software endstops. */ - void apply_motion_limits(float target[XYZ]) { + void apply_motion_limits(xyz_pos_t &target) { if (!soft_endstops_enabled || !all_axes_homed()) return; @@ -579,41 +571,38 @@ void restore_feedrate_and_scaling() { #if HAS_HOTEND_OFFSET && ENABLED(DELTA) // The effector center position will be the target minus the hotend offset. - const float offx = hotend_offset[X_AXIS][active_extruder], offy = hotend_offset[Y_AXIS][active_extruder]; + const xy_pos_t offs = hotend_offset[active_extruder]; #else // SCARA needs to consider the angle of the arm through the entire move, so for now use no tool offset. - constexpr float offx = 0, offy = 0; + constexpr xy_pos_t offs{0}; #endif - const float dist_2 = HYPOT2(target[X_AXIS] - offx, target[Y_AXIS] - offy); - if (dist_2 > delta_max_radius_2) { - const float ratio = (delta_max_radius) / SQRT(dist_2); // 200 / 300 = 0.66 - target[X_AXIS] *= ratio; - target[Y_AXIS] *= ratio; - } + const float dist_2 = HYPOT2(target.x - offs.x, target.y - offs.y); + if (dist_2 > delta_max_radius_2) + target *= delta_max_radius / SQRT(dist_2); // 200 / 300 = 0.66 #else #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_X) - NOLESS(target[X_AXIS], soft_endstop[X_AXIS].min); + NOLESS(target.x, soft_endstop.min.x); #endif #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_X) - NOMORE(target[X_AXIS], soft_endstop[X_AXIS].max); + NOMORE(target.x, soft_endstop.max.x); #endif #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_Y) - NOLESS(target[Y_AXIS], soft_endstop[Y_AXIS].min); + NOLESS(target.y, soft_endstop.min.y); #endif #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_Y) - NOMORE(target[Y_AXIS], soft_endstop[Y_AXIS].max); + NOMORE(target.y, soft_endstop.max.y); #endif #endif #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_Z) - NOLESS(target[Z_AXIS], soft_endstop[Z_AXIS].min); + NOLESS(target.z, soft_endstop.min.z); #endif #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_Z) - NOMORE(target[Z_AXIS], soft_endstop[Z_AXIS].max); + NOMORE(target.z, soft_endstop.max.z); #endif } @@ -656,27 +645,22 @@ void restore_feedrate_and_scaling() { // Get the top feedrate of the move in the XY plane const float scaled_fr_mm_s = MMS_SCALED(feedrate_mm_s); - const float xdiff = destination[X_AXIS] - current_position[X_AXIS], - ydiff = destination[Y_AXIS] - current_position[Y_AXIS]; + const xyze_float_t diff = destination - current_position; // If the move is only in Z/E don't split up the move - if (!xdiff && !ydiff) { + if (!diff.x && !diff.y) { planner.buffer_line(destination, scaled_fr_mm_s, active_extruder); return false; // caller will update current_position } // Fail if attempting move outside printable radius - if (!position_is_reachable(destination[X_AXIS], destination[Y_AXIS])) return true; - - // Remaining cartesian distances - const float zdiff = destination[Z_AXIS] - current_position[Z_AXIS], - ediff = destination[E_AXIS] - current_position[E_AXIS]; + if (!position_is_reachable(destination)) return true; // Get the linear distance in XYZ - float cartesian_mm = SQRT(sq(xdiff) + sq(ydiff) + sq(zdiff)); + float cartesian_mm = diff.magnitude(); // If the move is very short, check the E move distance - if (UNEAR_ZERO(cartesian_mm)) cartesian_mm = ABS(ediff); + if (UNEAR_ZERO(cartesian_mm)) cartesian_mm = ABS(diff.e); // No E move either? Game over. if (UNEAR_ZERO(cartesian_mm)) return true; @@ -698,13 +682,8 @@ void restore_feedrate_and_scaling() { // The approximate length of each segment const float inv_segments = 1.0f / float(segments), - segment_distance[XYZE] = { - xdiff * inv_segments, - ydiff * inv_segments, - zdiff * inv_segments, - ediff * inv_segments - }, cartesian_segment_mm = cartesian_mm * inv_segments; + const xyze_float_t segment_distance = diff * inv_segments; #if ENABLED(SCARA_FEEDRATE_SCALING) const float inv_duration = scaled_fr_mm_s / cartesian_segment_mm; @@ -719,8 +698,7 @@ void restore_feedrate_and_scaling() { //*/ // Get the current position as starting point - float raw[XYZE]; - COPY(raw, current_position); + xyze_pos_t raw = current_position; // Calculate and execute the segments while (--segments) { @@ -732,7 +710,7 @@ void restore_feedrate_and_scaling() { idle(); } - LOOP_XYZE(i) raw[i] += segment_distance[i]; + raw += segment_distance; if (!planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, cartesian_segment_mm #if ENABLED(SCARA_FEEDRATE_SCALING) @@ -765,24 +743,19 @@ void restore_feedrate_and_scaling() { */ inline void segmented_line_to_destination(const feedRate_t &fr_mm_s, const float segment_size=LEVELED_SEGMENT_LENGTH) { - const float xdiff = destination[X_AXIS] - current_position[X_AXIS], - ydiff = destination[Y_AXIS] - current_position[Y_AXIS]; + const xyze_float_t diff = destination - current_position; // If the move is only in Z/E don't split up the move - if (!xdiff && !ydiff) { + if (!diff.x && !diff.y) { planner.buffer_line(destination, fr_mm_s, active_extruder); return; } - // Remaining cartesian distances - const float zdiff = destination[Z_AXIS] - current_position[Z_AXIS], - ediff = destination[E_AXIS] - current_position[E_AXIS]; - // Get the linear distance in XYZ // If the move is very short, check the E move distance // No E move either? Game over. - float cartesian_mm = SQRT(sq(xdiff) + sq(ydiff) + sq(zdiff)); - if (UNEAR_ZERO(cartesian_mm)) cartesian_mm = ABS(ediff); + float cartesian_mm = diff.magnitude(); + if (UNEAR_ZERO(cartesian_mm)) cartesian_mm = ABS(diff.e); if (UNEAR_ZERO(cartesian_mm)) return; // The length divided by the segment size @@ -792,13 +765,8 @@ void restore_feedrate_and_scaling() { // The approximate length of each segment const float inv_segments = 1.0f / float(segments), - cartesian_segment_mm = cartesian_mm * inv_segments, - segment_distance[XYZE] = { - xdiff * inv_segments, - ydiff * inv_segments, - zdiff * inv_segments, - ediff * inv_segments - }; + cartesian_segment_mm = cartesian_mm * inv_segments; + const xyze_float_t segment_distance = diff * inv_segments; #if ENABLED(SCARA_FEEDRATE_SCALING) const float inv_duration = scaled_fr_mm_s / cartesian_segment_mm; @@ -809,8 +777,7 @@ void restore_feedrate_and_scaling() { // SERIAL_ECHOLNPAIR(" segment_mm=", cartesian_segment_mm); // Get the raw current position as starting point - float raw[XYZE]; - COPY(raw, current_position); + xyze_pos_t raw = current_position; // Calculate and execute the segments while (--segments) { @@ -820,7 +787,7 @@ void restore_feedrate_and_scaling() { next_idle_ms = millis() + 200UL; idle(); } - LOOP_XYZE(i) raw[i] += segment_distance[i]; + raw += segment_distance; if (!planner.buffer_line(raw, fr_mm_s, active_extruder, cartesian_segment_mm #if ENABLED(SCARA_FEEDRATE_SCALING) , inv_duration @@ -846,12 +813,12 @@ void restore_feedrate_and_scaling() { * When a mesh-based leveling system is active, moves are segmented * according to the configuration of the leveling system. * - * Returns true if current_position[] was set to destination[] + * Return true if 'current_position' was set to 'destination' */ inline bool prepare_move_to_destination_cartesian() { const float scaled_fr_mm_s = MMS_SCALED(feedrate_mm_s); #if HAS_MESH - if (planner.leveling_active && planner.leveling_active_at_z(destination[Z_AXIS])) { + if (planner.leveling_active && planner.leveling_active_at_z(destination.z)) { #if ENABLED(AUTO_BED_LEVELING_UBL) ubl.line_to_destination_cartesian(scaled_fr_mm_s, active_extruder); // UBL's motion routine needs to know about return true; // all moves, including Z-only moves. @@ -863,7 +830,7 @@ void restore_feedrate_and_scaling() { * For MBL and ABL-BILINEAR only segment moves when X or Y are involved. * Otherwise fall through to do a direct single move. */ - if (current_position[X_AXIS] != destination[X_AXIS] || current_position[Y_AXIS] != destination[Y_AXIS]) { + if (xy_pos_t(current_position) != xy_pos_t(destination)) { #if ENABLED(MESH_BED_LEVELING) mbl.line_to_destination(scaled_fr_mm_s); #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) @@ -894,8 +861,8 @@ void restore_feedrate_and_scaling() { DualXMode dual_x_carriage_mode = DEFAULT_DUAL_X_CARRIAGE_MODE; float inactive_extruder_x_pos = X2_MAX_POS, // used in mode 0 & 1 - raised_parked_position[XYZE], // used in mode 1 duplicate_extruder_x_offset = DEFAULT_DUPLICATION_X_OFFSET; // used in mode 2 + xyz_pos_t raised_parked_position; // used in mode 1 bool active_extruder_parked = false; // used in mode 1 & 2 millis_t delayed_move_time = 0; // used in mode 1 int16_t duplicate_extruder_temp_offset = 0; // used in mode 2 @@ -910,7 +877,7 @@ void restore_feedrate_and_scaling() { * This allows soft recalibration of the second extruder home position * without firmware reflash (through the M218 command). */ - return hotend_offset[X_AXIS][1] > 0 ? hotend_offset[X_AXIS][1] : X2_HOME_POS; + return hotend_offset[1].x > 0 ? hotend_offset[1].x : X2_HOME_POS; } /** @@ -924,30 +891,30 @@ void restore_feedrate_and_scaling() { case DXC_FULL_CONTROL_MODE: break; case DXC_AUTO_PARK_MODE: - if (current_position[E_AXIS] == destination[E_AXIS]) { + if (current_position.e == destination.e) { // This is a travel move (with no extrusion) // Skip it, but keep track of the current position // (so it can be used as the start of the next non-travel move) if (delayed_move_time != 0xFFFFFFFFUL) { - set_current_from_destination(); - NOLESS(raised_parked_position[Z_AXIS], destination[Z_AXIS]); + current_position = destination; + NOLESS(raised_parked_position.z, destination.z); delayed_move_time = millis(); return true; } } // unpark extruder: 1) raise, 2) move into starting XY position, 3) lower - #define CUR_X current_position[X_AXIS] - #define CUR_Y current_position[Y_AXIS] - #define CUR_Z current_position[Z_AXIS] - #define CUR_E current_position[E_AXIS] - #define RAISED_X raised_parked_position[X_AXIS] - #define RAISED_Y raised_parked_position[Y_AXIS] - #define RAISED_Z raised_parked_position[Z_AXIS] + #define CUR_X current_position.x + #define CUR_Y current_position.y + #define CUR_Z current_position.z + #define CUR_E current_position.e + #define RAISED_X raised_parked_position.x + #define RAISED_Y raised_parked_position.y + #define RAISED_Z raised_parked_position.z if ( planner.buffer_line(RAISED_X, RAISED_Y, RAISED_Z, CUR_E, planner.settings.max_feedrate_mm_s[Z_AXIS], active_extruder)) if (planner.buffer_line( CUR_X, CUR_Y, RAISED_Z, CUR_E, PLANNER_XY_FEEDRATE(), active_extruder)) - planner.buffer_line( CUR_X, CUR_Y, CUR_Z, CUR_E, planner.settings.max_feedrate_mm_s[Z_AXIS], active_extruder); + line_to_current_position(planner.settings.max_feedrate_mm_s[Z_AXIS]); delayed_move_time = 0; active_extruder_parked = false; if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Clear active_extruder_parked"); @@ -955,16 +922,15 @@ void restore_feedrate_and_scaling() { case DXC_MIRRORED_MODE: case DXC_DUPLICATION_MODE: if (active_extruder == 0) { - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Set planner X", inactive_extruder_x_pos, " ... Line to X", current_position[X_AXIS] + duplicate_extruder_x_offset); + xyze_pos_t new_pos = current_position; + if (dual_x_carriage_mode == DXC_DUPLICATION_MODE) + new_pos.x += duplicate_extruder_x_offset; + else + new_pos.x = inactive_extruder_x_pos; // move duplicate extruder into correct duplication position. - planner.set_position_mm(inactive_extruder_x_pos, current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); - - if (!planner.buffer_line( - dual_x_carriage_mode == DXC_DUPLICATION_MODE ? duplicate_extruder_x_offset + current_position[X_AXIS] : inactive_extruder_x_pos, - current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], - planner.settings.max_feedrate_mm_s[X_AXIS], 1 - ) - ) break; + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Set planner X", inactive_extruder_x_pos, " ... Line to X", new_pos.x); + planner.set_position_mm(inactive_extruder_x_pos, current_position.y, current_position.z, current_position.e); + if (!planner.buffer_line(new_pos, planner.settings.max_feedrate_mm_s[X_AXIS], 1)) break; planner.synchronize(); sync_plan_position(); extruder_duplication_enabled = true; @@ -987,7 +953,7 @@ void restore_feedrate_and_scaling() { * This may result in several calls to planner.buffer_line to * do smaller moves for DELTA, SCARA, mesh moves, etc. * - * Make sure current_position[E] and destination[E] are good + * Make sure current_position.e and destination.e are good * before calling or cold/lengthy extrusion may get missed. * * Before exit, current_position is set to destination. @@ -998,15 +964,15 @@ void prepare_move_to_destination() { #if EITHER(PREVENT_COLD_EXTRUSION, PREVENT_LENGTHY_EXTRUDE) if (!DEBUGGING(DRYRUN)) { - if (destination[E_AXIS] != current_position[E_AXIS]) { + if (destination.e != current_position.e) { #if ENABLED(PREVENT_COLD_EXTRUSION) if (thermalManager.tooColdToExtrude(active_extruder)) { - current_position[E_AXIS] = destination[E_AXIS]; // Behave as if the move really took place, but ignore E part + current_position.e = destination.e; // Behave as if the move really took place, but ignore E part SERIAL_ECHO_MSG(MSG_ERR_COLD_EXTRUDE_STOP); } #endif // PREVENT_COLD_EXTRUSION #if ENABLED(PREVENT_LENGTHY_EXTRUDE) - const float e_delta = ABS(destination[E_AXIS] - current_position[E_AXIS]) * planner.e_factor[active_extruder]; + const float e_delta = ABS(destination.e - current_position.e) * planner.e_factor[active_extruder]; if (e_delta > (EXTRUDE_MAXLENGTH)) { #if ENABLED(MIXING_EXTRUDER) bool ignore_e = false; @@ -1018,7 +984,7 @@ void prepare_move_to_destination() { constexpr bool ignore_e = true; #endif if (ignore_e) { - current_position[E_AXIS] = destination[E_AXIS]; // Behave as if the move really took place, but ignore E part + current_position.e = destination.e; // Behave as if the move really took place, but ignore E part SERIAL_ECHO_MSG(MSG_ERR_LONG_EXTRUDE_STOP); } } @@ -1046,7 +1012,7 @@ void prepare_move_to_destination() { #endif ) return; - set_current_from_destination(); + current_position = destination; } uint8_t axes_need_homing(uint8_t axis_bits/*=0x07*/) { @@ -1293,13 +1259,13 @@ void do_homing_move(const AxisEnum axis, const float distance, const feedRate_t current_position[axis] = distance; line_to_current_position(real_fr_mm_s); #else - float target[ABCE] = { planner.get_axis_position_mm(A_AXIS), planner.get_axis_position_mm(B_AXIS), planner.get_axis_position_mm(C_AXIS), planner.get_axis_position_mm(E_AXIS) }; + abce_pos_t target = { planner.get_axis_position_mm(A_AXIS), planner.get_axis_position_mm(B_AXIS), planner.get_axis_position_mm(C_AXIS), planner.get_axis_position_mm(E_AXIS) }; target[axis] = 0; planner.set_machine_position_mm(target); target[axis] = distance; #if IS_KINEMATIC && ENABLED(JUNCTION_DEVIATION) - const float delta_mm_cart[XYZE] = {0, 0, 0, 0}; + const xyze_float_t delta_mm_cart{0}; #endif // Set delta/cartesian axes directly @@ -1356,7 +1322,7 @@ void set_axis_is_at_home(const AxisEnum axis) { #if ENABLED(DUAL_X_CARRIAGE) if (axis == X_AXIS && (active_extruder == 1 || dual_x_carriage_mode == DXC_DUPLICATION_MODE)) { - current_position[X_AXIS] = x_home_pos(active_extruder); + current_position.x = x_home_pos(active_extruder); return; } #endif @@ -1366,7 +1332,7 @@ void set_axis_is_at_home(const AxisEnum axis) { #elif ENABLED(DELTA) current_position[axis] = (axis == Z_AXIS ? delta_height #if HAS_BED_PROBE - - probe_offset[Z_AXIS] + - probe_offset.z #endif : base_home_pos(axis)); #else @@ -1380,9 +1346,9 @@ void set_axis_is_at_home(const AxisEnum axis) { if (axis == Z_AXIS) { #if HOMING_Z_WITH_PROBE - current_position[Z_AXIS] -= probe_offset[Z_AXIS]; + current_position.z -= probe_offset.z; - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("*** Z HOMED WITH PROBE (Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) ***\n> probe_offset[Z_AXIS] = ", probe_offset[Z_AXIS]); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("*** Z HOMED WITH PROBE (Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) ***\n> probe_offset.z = ", probe_offset.z); #else @@ -1677,7 +1643,7 @@ void homeaxis(const AxisEnum axis) { #endif #ifdef HOMING_BACKOFF_MM - constexpr float endstop_backoff[XYZ] = HOMING_BACKOFF_MM; + constexpr xyz_float_t endstop_backoff = HOMING_BACKOFF_MM; const float backoff_mm = endstop_backoff[ #if ENABLED(DELTA) Z_AXIS diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index 9c465a1d5..9ea2ebe52 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -61,15 +61,15 @@ constexpr float slop = 0.0001; extern bool relative_mode; -extern float current_position[XYZE], // High-level current tool position - destination[XYZE]; // Destination for a move +extern xyze_pos_t current_position, // High-level current tool position + destination; // Destination for a move // Scratch space for a cartesian result -extern float cartes[XYZ]; +extern xyz_pos_t cartes; // Until kinematics.cpp is created, declare this here #if IS_KINEMATIC - extern float delta[ABC]; + extern abc_pos_t delta; #endif #if HAS_ABL_NOT_UBL @@ -81,6 +81,10 @@ extern float cartes[XYZ]; #define XY_PROBE_FEEDRATE_MM_S PLANNER_XY_FEEDRATE() #endif +#if ENABLED(Z_SAFE_HOMING) + constexpr xy_float_t safe_homing_xy = { Z_SAFE_HOMING_X_POINT, Z_SAFE_HOMING_Y_POINT }; +#endif + /** * Feed rates are often configured with mm/m * but the planner and stepper like mm/s units. @@ -106,10 +110,10 @@ extern int16_t feedrate_percentage; FORCE_INLINE float pgm_read_any(const float *p) { return pgm_read_float(p); } FORCE_INLINE signed char pgm_read_any(const signed char *p) { return pgm_read_byte(p); } -#define XYZ_DEFS(type, array, CONFIG) \ - extern const type array##_P[XYZ]; \ - FORCE_INLINE type array(AxisEnum axis) { return pgm_read_any(&array##_P[axis]); } \ - typedef void __void_##CONFIG##__ +#define XYZ_DEFS(T, NAME, OPT) \ + extern const XYZval NAME##_P; \ + FORCE_INLINE T NAME(AxisEnum axis) { return pgm_read_any(&NAME##_P[axis]); } \ + typedef void __void_##OPT##__ XYZ_DEFS(float, base_min_pos, MIN_POS); XYZ_DEFS(float, base_max_pos, MAX_POS); @@ -125,19 +129,19 @@ XYZ_DEFS(signed char, home_dir, HOME_DIR); #endif #if HAS_HOTEND_OFFSET - extern float hotend_offset[XYZ][HOTENDS]; + extern xyz_pos_t hotend_offset[HOTENDS]; void reset_hotend_offsets(); -#elif HOTENDS > 0 - constexpr float hotend_offset[XYZ][HOTENDS] = { { 0 }, { 0 }, { 0 } }; +#elif HOTENDS + constexpr xyz_pos_t hotend_offset[HOTENDS] = { { 0 } }; #else - constexpr float hotend_offset[XYZ][1] = { { 0 }, { 0 }, { 0 } }; + constexpr xyz_pos_t hotend_offset[1] = { { 0 } }; #endif -typedef struct { float min, max; } axis_limits_t; +typedef struct { xyz_pos_t min, max; } axis_limits_t; #if HAS_SOFTWARE_ENDSTOPS extern bool soft_endstops_enabled; - extern axis_limits_t soft_endstop[XYZ]; - void apply_motion_limits(float target[XYZ]); + extern axis_limits_t soft_endstop; + void apply_motion_limits(xyz_pos_t &target); void update_software_endstops(const AxisEnum axis #if HAS_HOTEND_OFFSET , const uint8_t old_tool_index=0, const uint8_t new_tool_index=0 @@ -145,16 +149,15 @@ typedef struct { float min, max; } axis_limits_t; ); #else constexpr bool soft_endstops_enabled = false; - //constexpr axis_limits_t soft_endstop[XYZ] = { { X_MIN_POS, X_MAX_POS }, { Y_MIN_POS, Y_MAX_POS }, { Z_MIN_POS, Z_MAX_POS } }; + //constexpr axis_limits_t soft_endstop = { + // { X_MIN_POS, Y_MIN_POS, Z_MIN_POS }, + // { X_MAX_POS, Y_MAX_POS, Z_MAX_POS } }; #define apply_motion_limits(V) NOOP #define update_software_endstops(...) NOOP #endif void report_current_position(); -inline void set_current_from_destination() { COPY(current_position, destination); } -inline void set_destination_from_current() { COPY(destination, current_position); } - void get_cartesian_from_steppers(); void set_current_from_steppers_for_axis(const AxisEnum axis); @@ -202,12 +205,17 @@ void do_blocking_move_to_y(const float &ry, const feedRate_t &fr_mm_s=0.0f); void do_blocking_move_to_z(const float &rz, const feedRate_t &fr_mm_s=0.0f); void do_blocking_move_to_xy(const float &rx, const float &ry, const feedRate_t &fr_mm_s=0.0f); -FORCE_INLINE void do_blocking_move_to(const float (&raw)[XYZ], const feedRate_t &fr_mm_s=0) { - do_blocking_move_to(raw[X_AXIS], raw[Y_AXIS], raw[Z_AXIS], fr_mm_s); +FORCE_INLINE void do_blocking_move_to(const xy_pos_t &raw, const feedRate_t &fr_mm_s=0.0f) { + do_blocking_move_to(raw.x, raw.y, current_position.z, fr_mm_s); } - -FORCE_INLINE void do_blocking_move_to(const float (&raw)[XYZE], const feedRate_t &fr_mm_s=0) { - do_blocking_move_to(raw[X_AXIS], raw[Y_AXIS], raw[Z_AXIS], fr_mm_s); +FORCE_INLINE void do_blocking_move_to(const xyz_pos_t &raw, const feedRate_t &fr_mm_s=0.0f) { + do_blocking_move_to(raw.x, raw.y, raw.z, fr_mm_s); +} +FORCE_INLINE void do_blocking_move_to(const xyze_pos_t &raw, const feedRate_t &fr_mm_s=0.0f) { + do_blocking_move_to(raw.x, raw.y, raw.z, fr_mm_s); +} +FORCE_INLINE void do_blocking_move_to_xy(const xy_pos_t &raw, const feedRate_t &fr_mm_s=0.0f) { + do_blocking_move_to_xy(raw.x, raw.y, fr_mm_s); } void remember_feedrate_and_scaling(); @@ -238,24 +246,36 @@ void homeaxis(const AxisEnum axis); */ #if HAS_HOME_OFFSET || HAS_POSITION_SHIFT #if HAS_HOME_OFFSET - extern float home_offset[XYZ]; + extern xyz_pos_t home_offset; #endif #if HAS_POSITION_SHIFT - extern float position_shift[XYZ]; + extern xyz_pos_t position_shift; #endif #if HAS_HOME_OFFSET && HAS_POSITION_SHIFT - extern float workspace_offset[XYZ]; - #define WORKSPACE_OFFSET(AXIS) workspace_offset[AXIS] + extern xyz_pos_t workspace_offset; + #define _WS workspace_offset #elif HAS_HOME_OFFSET - #define WORKSPACE_OFFSET(AXIS) home_offset[AXIS] + #define _WS home_offset #else - #define WORKSPACE_OFFSET(AXIS) position_shift[AXIS] + #define _WS position_shift #endif - #define NATIVE_TO_LOGICAL(POS, AXIS) ((POS) + WORKSPACE_OFFSET(AXIS)) - #define LOGICAL_TO_NATIVE(POS, AXIS) ((POS) - WORKSPACE_OFFSET(AXIS)) + #define NATIVE_TO_LOGICAL(POS, AXIS) ((POS) + _WS[AXIS]) + #define LOGICAL_TO_NATIVE(POS, AXIS) ((POS) - _WS[AXIS]) + FORCE_INLINE void toLogical(xy_pos_t &raw) { raw += _WS; } + FORCE_INLINE void toLogical(xyz_pos_t &raw) { raw += _WS; } + FORCE_INLINE void toLogical(xyze_pos_t &raw) { raw += _WS; } + FORCE_INLINE void toNative(xy_pos_t &raw) { raw -= _WS; } + FORCE_INLINE void toNative(xyz_pos_t &raw) { raw -= _WS; } + FORCE_INLINE void toNative(xyze_pos_t &raw) { raw -= _WS; } #else #define NATIVE_TO_LOGICAL(POS, AXIS) (POS) #define LOGICAL_TO_NATIVE(POS, AXIS) (POS) + FORCE_INLINE void toLogical(xy_pos_t &raw) { UNUSED(raw); } + FORCE_INLINE void toLogical(xyz_pos_t &raw) { UNUSED(raw); } + FORCE_INLINE void toLogical(xyze_pos_t &raw) { UNUSED(raw); } + FORCE_INLINE void toNative(xy_pos_t &raw) { UNUSED(raw); } + FORCE_INLINE void toNative(xyz_pos_t &raw) { UNUSED(raw); } + FORCE_INLINE void toNative(xyze_pos_t &raw) { UNUSED(raw); } #endif #define LOGICAL_X_POSITION(POS) NATIVE_TO_LOGICAL(POS, X_AXIS) #define LOGICAL_Y_POSITION(POS) NATIVE_TO_LOGICAL(POS, Y_AXIS) @@ -270,7 +290,7 @@ void homeaxis(const AxisEnum axis); #if IS_KINEMATIC // (DELTA or SCARA) #if HAS_SCARA_OFFSET - extern float scara_home_offset[ABC]; // A and B angular offsets, Z mm offset + extern abc_pos_t scara_home_offset; // A and B angular offsets, Z mm offset #endif // Return true if the given point is within the printable area @@ -288,11 +308,15 @@ void homeaxis(const AxisEnum axis); #endif } + inline bool position_is_reachable(const xy_pos_t &pos, const float inset=0) { + return position_is_reachable(pos.x, pos.y, inset); + } + #if HAS_BED_PROBE // Return true if the both nozzle and the probe can reach the given point. // Note: This won't work on SCARA since the probe offset rotates with the arm. inline bool position_is_reachable_by_probe(const float &rx, const float &ry) { - return position_is_reachable(rx - probe_offset[X_AXIS], ry - probe_offset[Y_AXIS]) + return position_is_reachable(rx - probe_offset.x, ry - probe_offset.y) && position_is_reachable(rx, ry, ABS(MIN_PROBE_EDGE)); } #endif @@ -311,6 +335,7 @@ void homeaxis(const AxisEnum axis); return WITHIN(rx, X_MIN_POS - slop, X_MAX_POS + slop); #endif } + inline bool position_is_reachable(const xy_pos_t &pos) { return position_is_reachable(pos.x, pos.y); } #if HAS_BED_PROBE /** @@ -321,7 +346,7 @@ void homeaxis(const AxisEnum axis); * nozzle must be be able to reach +10,-10. */ inline bool position_is_reachable_by_probe(const float &rx, const float &ry) { - return position_is_reachable(rx - probe_offset[X_AXIS], ry - probe_offset[Y_AXIS]) + return position_is_reachable(rx - probe_offset.x, ry - probe_offset.y) && WITHIN(rx, probe_min_x() - slop, probe_max_x() + slop) && WITHIN(ry, probe_min_y() - slop, probe_max_y() + slop); } @@ -332,6 +357,8 @@ void homeaxis(const AxisEnum axis); #if !HAS_BED_PROBE FORCE_INLINE bool position_is_reachable_by_probe(const float &rx, const float &ry) { return position_is_reachable(rx, ry); } #endif +FORCE_INLINE bool position_is_reachable_by_probe(const xy_int_t &pos) { return position_is_reachable_by_probe(pos.x, pos.y); } +FORCE_INLINE bool position_is_reachable_by_probe(const xy_pos_t &pos) { return position_is_reachable_by_probe(pos.x, pos.y); } /** * Duplication mode @@ -358,8 +385,8 @@ void homeaxis(const AxisEnum axis); extern DualXMode dual_x_carriage_mode; extern float inactive_extruder_x_pos, // Used in mode 0 & 1 - raised_parked_position[XYZE], // Used in mode 1 duplicate_extruder_x_offset; // Used in mode 2 & 3 + extern xyz_pos_t raised_parked_position; // Used in mode 1 extern bool active_extruder_parked; // Used in mode 1, 2 & 3 extern millis_t delayed_move_time; // Used in mode 1 extern int16_t duplicate_extruder_temp_offset; // Used in mode 2 & 3 diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 2715221f3..8d488e1f9 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -137,9 +137,9 @@ float Planner::steps_to_mm[XYZE_N]; // (mm) Millimeters per step #endif #if HAS_CLASSIC_JERK #if BOTH(JUNCTION_DEVIATION, LIN_ADVANCE) - float Planner::max_jerk[XYZ]; // (mm/s^2) M205 XYZ - The largest speed change requiring no acceleration. + xyz_pos_t Planner::max_jerk; // (mm/s^2) M205 XYZ - The largest speed change requiring no acceleration. #else - float Planner::max_jerk[XYZE]; // (mm/s^2) M205 XYZE - The largest speed change requiring no acceleration. + xyze_pos_t Planner::max_jerk; // (mm/s^2) M205 XYZE - The largest speed change requiring no acceleration. #endif #endif @@ -187,12 +187,12 @@ skew_factor_t Planner::skew_factor; // Initialized by settings.load() // private: -int32_t Planner::position[NUM_AXIS] = { 0 }; +xyze_long_t Planner::position{0}; uint32_t Planner::cutoff_long; -float Planner::previous_speed[NUM_AXIS], - Planner::previous_nominal_speed_sqr; +xyze_float_t Planner::previous_speed; +float Planner::previous_nominal_speed_sqr; #if ENABLED(DISABLE_INACTIVE_EXTRUDER) uint8_t Planner::g_uc_extruder_last_move[EXTRUDERS] = { 0 }; @@ -202,7 +202,7 @@ float Planner::previous_speed[NUM_AXIS], // Old direction bits. Used for speed calculations unsigned char Planner::old_direction_bits = 0; // Segment times (in µs). Used for speed calculations - uint32_t Planner::axis_segment_time_us[2][3] = { { MAX_FREQ_TIME_US + 1, 0, 0 }, { MAX_FREQ_TIME_US + 1, 0, 0 } }; + xy_ulong_t Planner::axis_segment_time_us[3] = { { MAX_FREQ_TIME_US + 1, MAX_FREQ_TIME_US + 1 } }; #endif #if ENABLED(LIN_ADVANCE) @@ -210,11 +210,11 @@ float Planner::previous_speed[NUM_AXIS], #endif #if HAS_POSITION_FLOAT - float Planner::position_float[XYZE]; // Needed for accurate maths. Steps cannot be used! + xyze_pos_t Planner::position_float; // Needed for accurate maths. Steps cannot be used! #endif #if IS_KINEMATIC - float Planner::position_cart[XYZE]; + xyze_pos_t Planner::position_cart; #endif #if HAS_SPI_LCD @@ -228,14 +228,14 @@ float Planner::previous_speed[NUM_AXIS], Planner::Planner() { init(); } void Planner::init() { - ZERO(position); + position.reset(); #if HAS_POSITION_FLOAT - ZERO(position_float); + position_float.reset(); #endif #if IS_KINEMATIC - ZERO(position_cart); + position_cart.reset(); #endif - ZERO(previous_speed); + previous_speed.reset(); previous_nominal_speed_sqr = 0; #if ABL_PLANAR bed_level_matrix.set_to_identity(); @@ -1155,8 +1155,8 @@ void Planner::recalculate() { float high = 0.0; for (uint8_t b = block_buffer_tail; b != block_buffer_head; b = next_block_index(b)) { block_t* block = &block_buffer[b]; - if (block->steps[X_AXIS] || block->steps[Y_AXIS] || block->steps[Z_AXIS]) { - const float se = (float)block->steps[E_AXIS] / block->step_event_count * SQRT(block->nominal_speed_sqr); // mm/sec; + if (block->steps.x || block->steps.y || block->steps.z) { + const float se = (float)block->steps.e / block->step_event_count * SQRT(block->nominal_speed_sqr); // mm/sec; NOLESS(high, se); } } @@ -1176,7 +1176,7 @@ void Planner::recalculate() { void Planner::check_axes_activity() { #if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z, DISABLE_E) - uint8_t axis_active[NUM_AXIS] = { 0 }; + xyze_bool_t axis_active = { false }; #endif #if FAN_COUNT > 0 @@ -1236,16 +1236,16 @@ void Planner::check_axes_activity() { } #if ENABLED(DISABLE_X) - if (!axis_active[X_AXIS]) disable_X(); + if (!axis_active.x) disable_X(); #endif #if ENABLED(DISABLE_Y) - if (!axis_active[Y_AXIS]) disable_Y(); + if (!axis_active.y) disable_Y(); #endif #if ENABLED(DISABLE_Z) - if (!axis_active[Z_AXIS]) disable_Z(); + if (!axis_active.z) disable_Z(); #endif #if ENABLED(DISABLE_E) - if (!axis_active[E_AXIS]) disable_e_steppers(); + if (!axis_active.e) disable_e_steppers(); #endif #if FAN_COUNT > 0 @@ -1354,40 +1354,32 @@ void Planner::check_axes_activity() { * rx, ry, rz - Cartesian positions in mm * Leveled XYZ on completion */ - void Planner::apply_leveling(float &rx, float &ry, float &rz) { + void Planner::apply_leveling(xyz_pos_t &raw) { if (!leveling_active) return; #if ABL_PLANAR - float dx = rx - (X_TILT_FULCRUM), - dy = ry - (Y_TILT_FULCRUM); - - apply_rotation_xyz(bed_level_matrix, dx, dy, rz); - - rx = dx + X_TILT_FULCRUM; - ry = dy + Y_TILT_FULCRUM; + xy_pos_t d = raw - level_fulcrum; + apply_rotation_xyz(bed_level_matrix, d.x, d.y, raw.z); + raw = d + level_fulcrum; #elif HAS_MESH #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - const float fade_scaling_factor = fade_scaling_factor_for_z(rz); + const float fade_scaling_factor = fade_scaling_factor_for_z(raw.z); #else constexpr float fade_scaling_factor = 1.0; #endif - #if ENABLED(AUTO_BED_LEVELING_BILINEAR) - const float raw[XYZ] = { rx, ry, 0 }; - #endif - - rz += ( + raw.z += ( #if ENABLED(MESH_BED_LEVELING) - mbl.get_z(rx, ry + mbl.get_z(raw #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) , fade_scaling_factor #endif ) #elif ENABLED(AUTO_BED_LEVELING_UBL) - fade_scaling_factor ? fade_scaling_factor * ubl.get_z_correction(rx, ry) : 0.0 + fade_scaling_factor ? fade_scaling_factor * ubl.get_z_correction(raw) : 0.0 #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) fade_scaling_factor ? fade_scaling_factor * bilinear_z_offset(raw) : 0.0 #endif @@ -1396,7 +1388,7 @@ void Planner::check_axes_activity() { #endif } - void Planner::unapply_leveling(float raw[XYZ]) { + void Planner::unapply_leveling(xyz_pos_t &raw) { if (leveling_active) { @@ -1404,31 +1396,27 @@ void Planner::check_axes_activity() { matrix_3x3 inverse = matrix_3x3::transpose(bed_level_matrix); - float dx = raw[X_AXIS] - (X_TILT_FULCRUM), - dy = raw[Y_AXIS] - (Y_TILT_FULCRUM); - - apply_rotation_xyz(inverse, dx, dy, raw[Z_AXIS]); - - raw[X_AXIS] = dx + X_TILT_FULCRUM; - raw[Y_AXIS] = dy + Y_TILT_FULCRUM; + xy_pos_t d = raw - level_fulcrum; + apply_rotation_xyz(inverse, d.x, d.y, raw.z); + raw = d + level_fulcrum; #elif HAS_MESH #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - const float fade_scaling_factor = fade_scaling_factor_for_z(raw[Z_AXIS]); + const float fade_scaling_factor = fade_scaling_factor_for_z(raw.z); #else constexpr float fade_scaling_factor = 1.0; #endif - raw[Z_AXIS] -= ( + raw.z -= ( #if ENABLED(MESH_BED_LEVELING) - mbl.get_z(raw[X_AXIS], raw[Y_AXIS] + mbl.get_z(raw #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) , fade_scaling_factor #endif ) #elif ENABLED(AUTO_BED_LEVELING_UBL) - fade_scaling_factor ? fade_scaling_factor * ubl.get_z_correction(raw[X_AXIS], raw[Y_AXIS]) : 0.0 + fade_scaling_factor ? fade_scaling_factor * ubl.get_z_correction(raw) : 0.0 #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) fade_scaling_factor ? fade_scaling_factor * bilinear_z_offset(raw) : 0.0 #endif @@ -1438,7 +1426,7 @@ void Planner::check_axes_activity() { } #if ENABLED(SKEW_CORRECTION) - unskew(raw[X_AXIS], raw[Y_AXIS], raw[Z_AXIS]); + unskew(raw); #endif } @@ -1563,12 +1551,12 @@ void Planner::synchronize() { * * Returns true if movement was properly queued, false otherwise */ -bool Planner::_buffer_steps(const int32_t (&target)[XYZE] +bool Planner::_buffer_steps(const xyze_long_t &target #if HAS_POSITION_FLOAT - , const float (&target_float)[ABCE] + , const xyze_pos_t &target_float #endif #if IS_KINEMATIC && ENABLED(JUNCTION_DEVIATION) - , const float (&delta_mm_cart)[XYZE] + , const xyze_float_t &delta_mm_cart #endif , feedRate_t fr_mm_s, const uint8_t extruder, const float &millimeters ) { @@ -1627,33 +1615,33 @@ bool Planner::_buffer_steps(const int32_t (&target)[XYZE] * Returns true is movement is acceptable, false otherwise */ bool Planner::_populate_block(block_t * const block, bool split_move, - const int32_t (&target)[ABCE] + const abce_long_t &target #if HAS_POSITION_FLOAT - , const float (&target_float)[ABCE] + , const xyze_pos_t &target_float #endif #if IS_KINEMATIC && ENABLED(JUNCTION_DEVIATION) - , const float (&delta_mm_cart)[XYZE] + , const xyze_float_t &delta_mm_cart #endif , feedRate_t fr_mm_s, const uint8_t extruder, const float &millimeters/*=0.0*/ ) { - const int32_t da = target[A_AXIS] - position[A_AXIS], - db = target[B_AXIS] - position[B_AXIS], - dc = target[C_AXIS] - position[C_AXIS]; + const int32_t da = target.a - position.a, + db = target.b - position.b, + dc = target.c - position.c; #if EXTRUDERS - int32_t de = target[E_AXIS] - position[E_AXIS]; + int32_t de = target.e - position.e; #else constexpr int32_t de = 0; #endif /* <-- add a slash to enable SERIAL_ECHOLNPAIR(" _populate_block FR:", fr_mm_s, - " A:", target[A_AXIS], " (", da, " steps)" - " B:", target[B_AXIS], " (", db, " steps)" - " C:", target[C_AXIS], " (", dc, " steps)" + " A:", target.a, " (", da, " steps)" + " B:", target.b, " (", db, " steps)" + " C:", target.c, " (", dc, " steps)" #if EXTRUDERS - " E:", target[E_AXIS], " (", de, " steps)" + " E:", target.e, " (", de, " steps)" #endif ); //*/ @@ -1662,9 +1650,9 @@ bool Planner::_populate_block(block_t * const block, bool split_move, if (de) { #if ENABLED(PREVENT_COLD_EXTRUSION) if (thermalManager.tooColdToExtrude(extruder)) { - position[E_AXIS] = target[E_AXIS]; // Behave as if the move really took place, but ignore E part + position.e = target.e; // Behave as if the move really took place, but ignore E part #if HAS_POSITION_FLOAT - position_float[E_AXIS] = target_float[E_AXIS]; + position_float.e = target_float.e; #endif de = 0; // no difference SERIAL_ECHO_MSG(MSG_ERR_COLD_EXTRUDE_STOP); @@ -1684,9 +1672,9 @@ bool Planner::_populate_block(block_t * const block, bool split_move, constexpr bool ignore_e = true; #endif if (ignore_e) { - position[E_AXIS] = target[E_AXIS]; // Behave as if the move really took place, but ignore E part + position.e = target.e; // Behave as if the move really took place, but ignore E part #if HAS_POSITION_FLOAT - position_float[E_AXIS] = target_float[E_AXIS]; + position_float.e = target_float.e; #endif de = 0; // no difference SERIAL_ECHO_MSG(MSG_ERR_LONG_EXTRUDE_STOP); @@ -1739,26 +1727,16 @@ bool Planner::_populate_block(block_t * const block, bool split_move, // Number of steps for each axis // See http://www.corexy.com/theory.html #if CORE_IS_XY - block->steps[A_AXIS] = ABS(da + db); - block->steps[B_AXIS] = ABS(da - db); - block->steps[Z_AXIS] = ABS(dc); + block->steps.set(ABS(da + db), ABS(da - db), ABS(dc)); #elif CORE_IS_XZ - block->steps[A_AXIS] = ABS(da + dc); - block->steps[Y_AXIS] = ABS(db); - block->steps[C_AXIS] = ABS(da - dc); + block->steps.set(ABS(da + dc), ABS(db), ABS(da - dc)); #elif CORE_IS_YZ - block->steps[X_AXIS] = ABS(da); - block->steps[B_AXIS] = ABS(db + dc); - block->steps[C_AXIS] = ABS(db - dc); + block->steps.set(ABS(da), ABS(db + dc), ABS(db - dc)); #elif IS_SCARA - block->steps[A_AXIS] = ABS(da); - block->steps[B_AXIS] = ABS(db); - block->steps[Z_AXIS] = ABS(dc); + block->steps.set(ABS(da), ABS(db), ABS(dc)); #else // default non-h-bot planning - block->steps[A_AXIS] = ABS(da); - block->steps[B_AXIS] = ABS(db); - block->steps[C_AXIS] = ABS(dc); + block->steps.set(ABS(da), ABS(db), ABS(dc)); #endif /** @@ -1769,42 +1747,45 @@ bool Planner::_populate_block(block_t * const block, bool split_move, * So we need to create other 2 "AXIS", named X_HEAD and Y_HEAD, meaning the real displacement of the Head. * Having the real displacement of the head, we can calculate the total movement length and apply the desired speed. */ + struct DeltaMM : abce_float_t { + #if IS_CORE + xyz_pos_t head; + #endif + } delta_mm; #if IS_CORE - float delta_mm[Z_HEAD + 1]; #if CORE_IS_XY - delta_mm[X_HEAD] = da * steps_to_mm[A_AXIS]; - delta_mm[Y_HEAD] = db * steps_to_mm[B_AXIS]; - delta_mm[Z_AXIS] = dc * steps_to_mm[Z_AXIS]; - delta_mm[A_AXIS] = (da + db) * steps_to_mm[A_AXIS]; - delta_mm[B_AXIS] = CORESIGN(da - db) * steps_to_mm[B_AXIS]; + delta_mm.head.x = da * steps_to_mm[A_AXIS]; + delta_mm.head.y = db * steps_to_mm[B_AXIS]; + delta_mm.z = dc * steps_to_mm[Z_AXIS]; + delta_mm.a = (da + db) * steps_to_mm[A_AXIS]; + delta_mm.b = CORESIGN(da - db) * steps_to_mm[B_AXIS]; #elif CORE_IS_XZ - delta_mm[X_HEAD] = da * steps_to_mm[A_AXIS]; - delta_mm[Y_AXIS] = db * steps_to_mm[Y_AXIS]; - delta_mm[Z_HEAD] = dc * steps_to_mm[C_AXIS]; - delta_mm[A_AXIS] = (da + dc) * steps_to_mm[A_AXIS]; - delta_mm[C_AXIS] = CORESIGN(da - dc) * steps_to_mm[C_AXIS]; + delta_mm.head.x = da * steps_to_mm[A_AXIS]; + delta_mm.y = db * steps_to_mm[Y_AXIS]; + delta_mm.head.z = dc * steps_to_mm[C_AXIS]; + delta_mm.a = (da + dc) * steps_to_mm[A_AXIS]; + delta_mm.c = CORESIGN(da - dc) * steps_to_mm[C_AXIS]; #elif CORE_IS_YZ - delta_mm[X_AXIS] = da * steps_to_mm[X_AXIS]; - delta_mm[Y_HEAD] = db * steps_to_mm[B_AXIS]; - delta_mm[Z_HEAD] = dc * steps_to_mm[C_AXIS]; - delta_mm[B_AXIS] = (db + dc) * steps_to_mm[B_AXIS]; - delta_mm[C_AXIS] = CORESIGN(db - dc) * steps_to_mm[C_AXIS]; + delta_mm.x = da * steps_to_mm[X_AXIS]; + delta_mm.head.y = db * steps_to_mm[B_AXIS]; + delta_mm.head.z = dc * steps_to_mm[C_AXIS]; + delta_mm.b = (db + dc) * steps_to_mm[B_AXIS]; + delta_mm.c = CORESIGN(db - dc) * steps_to_mm[C_AXIS]; #endif #else - float delta_mm[ABCE]; - delta_mm[A_AXIS] = da * steps_to_mm[A_AXIS]; - delta_mm[B_AXIS] = db * steps_to_mm[B_AXIS]; - delta_mm[C_AXIS] = dc * steps_to_mm[C_AXIS]; + delta_mm.a = da * steps_to_mm[A_AXIS]; + delta_mm.b = db * steps_to_mm[B_AXIS]; + delta_mm.c = dc * steps_to_mm[C_AXIS]; #endif #if EXTRUDERS - delta_mm[E_AXIS] = esteps_float * steps_to_mm[E_AXIS_N(extruder)]; + delta_mm.e = esteps_float * steps_to_mm[E_AXIS_N(extruder)]; #endif - if (block->steps[A_AXIS] < MIN_STEPS_PER_SEGMENT && block->steps[B_AXIS] < MIN_STEPS_PER_SEGMENT && block->steps[C_AXIS] < MIN_STEPS_PER_SEGMENT) { + if (block->steps.a < MIN_STEPS_PER_SEGMENT && block->steps.b < MIN_STEPS_PER_SEGMENT && block->steps.c < MIN_STEPS_PER_SEGMENT) { block->millimeters = (0 #if EXTRUDERS - + ABS(delta_mm[E_AXIS]) + + ABS(delta_mm.e) #endif ); } @@ -1814,13 +1795,13 @@ bool Planner::_populate_block(block_t * const block, bool split_move, else block->millimeters = SQRT( #if CORE_IS_XY - sq(delta_mm[X_HEAD]) + sq(delta_mm[Y_HEAD]) + sq(delta_mm[Z_AXIS]) + sq(delta_mm.head.x) + sq(delta_mm.head.y) + sq(delta_mm.z) #elif CORE_IS_XZ - sq(delta_mm[X_HEAD]) + sq(delta_mm[Y_AXIS]) + sq(delta_mm[Z_HEAD]) + sq(delta_mm.head.x) + sq(delta_mm.y) + sq(delta_mm.head.z) #elif CORE_IS_YZ - sq(delta_mm[X_AXIS]) + sq(delta_mm[Y_HEAD]) + sq(delta_mm[Z_HEAD]) + sq(delta_mm.x) + sq(delta_mm.head.y) + sq(delta_mm.head.z) #else - sq(delta_mm[X_AXIS]) + sq(delta_mm[Y_AXIS]) + sq(delta_mm[Z_AXIS]) + sq(delta_mm.x) + sq(delta_mm.y) + sq(delta_mm.z) #endif ); @@ -1839,10 +1820,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move, } #if EXTRUDERS - block->steps[E_AXIS] = esteps; + block->steps.e = esteps; #endif - block->step_event_count = _MAX(block->steps[A_AXIS], block->steps[B_AXIS], block->steps[C_AXIS], esteps); + block->step_event_count = _MAX(block->steps.a, block->steps.b, block->steps.c, esteps); // Bail if this is a zero-length block if (block->step_event_count < MIN_STEPS_PER_SEGMENT) return false; @@ -1865,36 +1846,36 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #endif #if ENABLED(AUTO_POWER_CONTROL) - if (block->steps[X_AXIS] || block->steps[Y_AXIS] || block->steps[Z_AXIS]) + if (block->steps.x || block->steps.y || block->steps.z) powerManager.power_on(); #endif // Enable active axes #if CORE_IS_XY - if (block->steps[A_AXIS] || block->steps[B_AXIS]) { + if (block->steps.a || block->steps.b) { enable_X(); enable_Y(); } #if DISABLED(Z_LATE_ENABLE) - if (block->steps[Z_AXIS]) enable_Z(); + if (block->steps.z) enable_Z(); #endif #elif CORE_IS_XZ - if (block->steps[A_AXIS] || block->steps[C_AXIS]) { + if (block->steps.a || block->steps.c) { enable_X(); enable_Z(); } - if (block->steps[Y_AXIS]) enable_Y(); + if (block->steps.y) enable_Y(); #elif CORE_IS_YZ - if (block->steps[B_AXIS] || block->steps[C_AXIS]) { + if (block->steps.b || block->steps.c) { enable_Y(); enable_Z(); } - if (block->steps[X_AXIS]) enable_X(); + if (block->steps.x) enable_X(); #else - if (block->steps[X_AXIS]) enable_X(); - if (block->steps[Y_AXIS]) enable_Y(); + if (block->steps.x) enable_X(); + if (block->steps.y) enable_Y(); #if DISABLED(Z_LATE_ENABLE) - if (block->steps[Z_AXIS]) enable_Z(); + if (block->steps.z) enable_Z(); #endif #endif @@ -2074,20 +2055,21 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #if ENABLED(FILAMENT_WIDTH_SENSOR) if (extruder == FILAMENT_SENSOR_EXTRUDER_NUM) // Only for extruder with filament sensor - filwidth.advance_e(delta_mm[E_AXIS]); + filwidth.advance_e(delta_mm.e); #endif // Calculate and limit speed in mm/sec for each axis - float current_speed[NUM_AXIS], speed_factor = 1.0f; // factor <1 decreases speed + xyze_float_t current_speed; + float speed_factor = 1.0f; // factor <1 decreases speed LOOP_XYZE(i) { #if BOTH(MIXING_EXTRUDER, RETRACT_SYNC_MIXING) // In worst case, only one extruder running, no change is needed. // In best case, all extruders run the same amount, we can divide by MIXING_STEPPERS float delta_mm_i = 0; if (i == E_AXIS && mixer.get_current_vtool() == MIXER_AUTORETRACT_TOOL) - delta_mm_i = delta_mm[i] / MIXING_STEPPERS; + delta_mm_i = delta_mm.e / MIXING_STEPPERS; else - delta_mm_i = delta_mm[i]; + delta_mm_i = delta_mm.e; #else const float delta_mm_i = delta_mm[i]; #endif @@ -2106,26 +2088,26 @@ bool Planner::_populate_block(block_t * const block, bool split_move, old_direction_bits = block->direction_bits; segment_time_us = LROUND((float)segment_time_us / speed_factor); - uint32_t xs0 = axis_segment_time_us[X_AXIS][0], - xs1 = axis_segment_time_us[X_AXIS][1], - xs2 = axis_segment_time_us[X_AXIS][2], - ys0 = axis_segment_time_us[Y_AXIS][0], - ys1 = axis_segment_time_us[Y_AXIS][1], - ys2 = axis_segment_time_us[Y_AXIS][2]; + uint32_t xs0 = axis_segment_time_us[0].x, + xs1 = axis_segment_time_us[1].x, + xs2 = axis_segment_time_us[2].x, + ys0 = axis_segment_time_us[0].y, + ys1 = axis_segment_time_us[1].y, + ys2 = axis_segment_time_us[2].y; if (TEST(direction_change, X_AXIS)) { - xs2 = axis_segment_time_us[X_AXIS][2] = xs1; - xs1 = axis_segment_time_us[X_AXIS][1] = xs0; + xs2 = axis_segment_time_us[2].x = xs1; + xs1 = axis_segment_time_us[1].x = xs0; xs0 = 0; } - xs0 = axis_segment_time_us[X_AXIS][0] = xs0 + segment_time_us; + xs0 = axis_segment_time_us[0].x = xs0 + segment_time_us; if (TEST(direction_change, Y_AXIS)) { - ys2 = axis_segment_time_us[Y_AXIS][2] = axis_segment_time_us[Y_AXIS][1]; - ys1 = axis_segment_time_us[Y_AXIS][1] = axis_segment_time_us[Y_AXIS][0]; + ys2 = axis_segment_time_us[2].y = axis_segment_time_us[1].y; + ys1 = axis_segment_time_us[1].y = axis_segment_time_us[0].y; ys0 = 0; } - ys0 = axis_segment_time_us[Y_AXIS][0] = ys0 + segment_time_us; + ys0 = axis_segment_time_us[0].y = ys0 + segment_time_us; const uint32_t max_x_segment_time = _MAX(xs0, xs1, xs2), max_y_segment_time = _MAX(ys0, ys1, ys2), @@ -2138,7 +2120,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, // Correct the speed if (speed_factor < 1.0f) { - LOOP_XYZE(i) current_speed[i] *= speed_factor; + current_speed *= speed_factor; block->nominal_rate *= speed_factor; block->nominal_speed_sqr = block->nominal_speed_sqr * sq(speed_factor); } @@ -2146,7 +2128,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, // Compute and limit the acceleration rate for the trapezoid generator. const float steps_per_mm = block->step_event_count * inverse_millimeters; uint32_t accel; - if (!block->steps[A_AXIS] && !block->steps[B_AXIS] && !block->steps[C_AXIS]) { + if (!block->steps.a && !block->steps.b && !block->steps.c) { // convert to: acceleration steps/sec^2 accel = CEIL(settings.retract_acceleration * steps_per_mm); #if ENABLED(LIN_ADVANCE) @@ -2180,7 +2162,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #define MAX_E_JERK max_e_jerk #endif #else - #define MAX_E_JERK max_jerk[E_AXIS] + #define MAX_E_JERK max_jerk.e #endif /** @@ -2198,13 +2180,13 @@ bool Planner::_populate_block(block_t * const block, bool split_move, && de > 0; if (block->use_advance_lead) { - block->e_D_ratio = (target_float[E_AXIS] - position_float[E_AXIS]) / + block->e_D_ratio = (target_float.e - position_float.e) / #if IS_KINEMATIC block->millimeters #else - SQRT(sq(target_float[X_AXIS] - position_float[X_AXIS]) - + sq(target_float[Y_AXIS] - position_float[Y_AXIS]) - + sq(target_float[Z_AXIS] - position_float[Z_AXIS])) + SQRT(sq(target_float.x - position_float.x) + + sq(target_float.y - position_float.y) + + sq(target_float.z - position_float.z)) #endif ; @@ -2297,23 +2279,16 @@ bool Planner::_populate_block(block_t * const block, bool split_move, already calculated in a different place. */ // Unit vector of previous path line segment - static float previous_unit_vec[XYZE]; + static xyze_float_t prev_unit_vec; - #if IS_KINEMATIC && ENABLED(JUNCTION_DEVIATION) - float unit_vec[] = { - delta_mm_cart[X_AXIS] * inverse_millimeters, - delta_mm_cart[Y_AXIS] * inverse_millimeters, - delta_mm_cart[Z_AXIS] * inverse_millimeters, - delta_mm_cart[E_AXIS] * inverse_millimeters - }; - #else - float unit_vec[] = { - delta_mm[X_AXIS] * inverse_millimeters, - delta_mm[Y_AXIS] * inverse_millimeters, - delta_mm[Z_AXIS] * inverse_millimeters, - delta_mm[E_AXIS] * inverse_millimeters - }; - #endif + xyze_float_t unit_vec = + #if IS_KINEMATIC && ENABLED(JUNCTION_DEVIATION) + delta_mm_cart + #else + { delta_mm.x, delta_mm.y, delta_mm.z, delta_mm.e } + #endif + ; + unit_vec *= inverse_millimeters; #if IS_CORE && ENABLED(JUNCTION_DEVIATION) /** @@ -2328,11 +2303,8 @@ bool Planner::_populate_block(block_t * const block, bool split_move, if (moves_queued && !UNEAR_ZERO(previous_nominal_speed_sqr)) { // Compute cosine of angle between previous and current path. (prev_unit_vec is negative) // NOTE: Max junction velocity is computed without sin() or acos() by trig half angle identity. - float junction_cos_theta = -previous_unit_vec[X_AXIS] * unit_vec[X_AXIS] - -previous_unit_vec[Y_AXIS] * unit_vec[Y_AXIS] - -previous_unit_vec[Z_AXIS] * unit_vec[Z_AXIS] - -previous_unit_vec[E_AXIS] * unit_vec[E_AXIS] - ; + float junction_cos_theta = (-prev_unit_vec.x * unit_vec.x) + (-prev_unit_vec.y * unit_vec.y) + + (-prev_unit_vec.z * unit_vec.z) + (-prev_unit_vec.e * unit_vec.e); // NOTE: Computed without any expensive trig, sin() or acos(), by trig half angle identity of cos(theta). if (junction_cos_theta > 0.999999f) { @@ -2343,12 +2315,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, NOLESS(junction_cos_theta, -0.999999f); // Check for numerical round-off to avoid divide by zero. // Convert delta vector to unit vector - float junction_unit_vec[XYZE] = { - unit_vec[X_AXIS] - previous_unit_vec[X_AXIS], - unit_vec[Y_AXIS] - previous_unit_vec[Y_AXIS], - unit_vec[Z_AXIS] - previous_unit_vec[Z_AXIS], - unit_vec[E_AXIS] - previous_unit_vec[E_AXIS] - }; + xyze_float_t junction_unit_vec = unit_vec - prev_unit_vec; normalize_junction_vector(junction_unit_vec); const float junction_acceleration = limit_value_by_axis_maximum(block->acceleration, junction_unit_vec), @@ -2374,7 +2341,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, else // Init entry speed to zero. Assume it starts from rest. Planner will correct this later. vmax_junction_sqr = 0; - COPY(previous_unit_vec, unit_vec); + prev_unit_vec = unit_vec; #endif @@ -2497,18 +2464,17 @@ bool Planner::_populate_block(block_t * const block, bool split_move, block->flag |= block->nominal_speed_sqr <= v_allowable_sqr ? BLOCK_FLAG_RECALCULATE | BLOCK_FLAG_NOMINAL_LENGTH : BLOCK_FLAG_RECALCULATE; // Update previous path unit_vector and nominal speed - COPY(previous_speed, current_speed); + previous_speed = current_speed; previous_nominal_speed_sqr = block->nominal_speed_sqr; // Update the position - static_assert(COUNT(target) > 1, "Parameter to _buffer_steps must be (&target)[XYZE]!"); - COPY(position, target); + position = target; #if HAS_POSITION_FLOAT - COPY(position_float, target_float); + position_float = target_float; #endif #if ENABLED(GRADIENT_MIX) - mixer.gradient_control(target_float[Z_AXIS]); + mixer.gradient_control(target_float.z); #endif #if ENABLED(POWER_LOSS_RECOVERY) @@ -2533,10 +2499,7 @@ void Planner::buffer_sync_block() { block->flag = BLOCK_FLAG_SYNC_POSITION; - block->position[A_AXIS] = position[A_AXIS]; - block->position[B_AXIS] = position[B_AXIS]; - block->position[C_AXIS] = position[C_AXIS]; - block->position[E_AXIS] = position[E_AXIS]; + block->position = position; // If this is the first added movement, reload the delay, otherwise, cancel it. if (block_buffer_head == block_buffer_tail) { @@ -2567,7 +2530,7 @@ void Planner::buffer_sync_block() { */ bool Planner::buffer_segment(const float &a, const float &b, const float &c, const float &e #if IS_KINEMATIC && ENABLED(JUNCTION_DEVIATION) - , const float (&delta_mm_cart)[XYZE] + , const xyze_float_t &delta_mm_cart #endif , const feedRate_t &fr_mm_s, const uint8_t extruder, const float &millimeters/*=0.0*/ ) { @@ -2578,14 +2541,14 @@ bool Planner::buffer_segment(const float &a, const float &b, const float &c, con // When changing extruders recalculate steps corresponding to the E position #if ENABLED(DISTINCT_E_FACTORS) if (last_extruder != extruder && settings.axis_steps_per_mm[E_AXIS_N(extruder)] != settings.axis_steps_per_mm[E_AXIS_N(last_extruder)]) { - position[E_AXIS] = LROUND(position[E_AXIS] * settings.axis_steps_per_mm[E_AXIS_N(extruder)] * steps_to_mm[E_AXIS_N(last_extruder)]); + position.e = LROUND(position.e * settings.axis_steps_per_mm[E_AXIS_N(extruder)] * steps_to_mm[E_AXIS_N(last_extruder)]); last_extruder = extruder; } #endif // The target position of the tool in absolute steps // Calculate target position in absolute steps - const int32_t target[ABCE] = { + const abce_long_t target = { int32_t(LROUND(a * settings.axis_steps_per_mm[A_AXIS])), int32_t(LROUND(b * settings.axis_steps_per_mm[B_AXIS])), int32_t(LROUND(c * settings.axis_steps_per_mm[C_AXIS])), @@ -2593,14 +2556,14 @@ bool Planner::buffer_segment(const float &a, const float &b, const float &c, con }; #if HAS_POSITION_FLOAT - const float target_float[XYZE] = { a, b, c, e }; + const xyze_pos_t target_float = { a, b, c, e }; #endif // DRYRUN prevents E moves from taking place if (DEBUGGING(DRYRUN)) { - position[E_AXIS] = target[E_AXIS]; + position.e = target.e; #if HAS_POSITION_FLOAT - position_float[E_AXIS] = e; + position_float.e = e; #endif } @@ -2608,27 +2571,27 @@ bool Planner::buffer_segment(const float &a, const float &b, const float &c, con SERIAL_ECHOPAIR(" buffer_segment FR:", fr_mm_s); #if IS_KINEMATIC SERIAL_ECHOPAIR(" A:", a); - SERIAL_ECHOPAIR(" (", position[A_AXIS]); - SERIAL_ECHOPAIR("->", target[A_AXIS]); + SERIAL_ECHOPAIR(" (", position.a); + SERIAL_ECHOPAIR("->", target.a); SERIAL_ECHOPAIR(") B:", b); #else SERIAL_ECHOPAIR(" X:", a); - SERIAL_ECHOPAIR(" (", position[X_AXIS]); - SERIAL_ECHOPAIR("->", target[X_AXIS]); + SERIAL_ECHOPAIR(" (", position.x); + SERIAL_ECHOPAIR("->", target.x); SERIAL_ECHOPAIR(") Y:", b); #endif - SERIAL_ECHOPAIR(" (", position[Y_AXIS]); - SERIAL_ECHOPAIR("->", target[Y_AXIS]); + SERIAL_ECHOPAIR(" (", position.y); + SERIAL_ECHOPAIR("->", target.y); #if ENABLED(DELTA) SERIAL_ECHOPAIR(") C:", c); #else SERIAL_ECHOPAIR(") Z:", c); #endif - SERIAL_ECHOPAIR(" (", position[Z_AXIS]); - SERIAL_ECHOPAIR("->", target[Z_AXIS]); + SERIAL_ECHOPAIR(" (", position.z); + SERIAL_ECHOPAIR("->", target.z); SERIAL_ECHOPAIR(") E:", e); - SERIAL_ECHOPAIR(" (", position[E_AXIS]); - SERIAL_ECHOPAIR("->", target[E_AXIS]); + SERIAL_ECHOPAIR(" (", position.e); + SERIAL_ECHOPAIR("->", target.e); SERIAL_ECHOLNPGM(")"); //*/ @@ -2665,51 +2628,49 @@ bool Planner::buffer_line(const float &rx, const float &ry, const float &rz, con , const float &inv_duration #endif ) { - float raw[XYZE] = { rx, ry, rz, e }; + xyze_pos_t machine = { rx, ry, rz, e }; #if HAS_POSITION_MODIFIERS - apply_modifiers(raw); + apply_modifiers(machine); #endif #if IS_KINEMATIC - const float delta_mm_cart[] = { - rx - position_cart[X_AXIS], - ry - position_cart[Y_AXIS], - rz - position_cart[Z_AXIS] - #if ENABLED(JUNCTION_DEVIATION) - , e - position_cart[E_AXIS] - #endif - }; + + #if ENABLED(JUNCTION_DEVIATION) + const xyze_pos_t delta_mm_cart = { + rx - position_cart.x, ry - position_cart.y, + rz - position_cart.z, e - position_cart.e + }; + #else + const xyz_pos_t delta_mm_cart = { rx - position_cart.x, ry - position_cart.y, rz - position_cart.z }; + #endif float mm = millimeters; if (mm == 0.0) - mm = (delta_mm_cart[X_AXIS] != 0.0 || delta_mm_cart[Y_AXIS] != 0.0) ? SQRT(sq(delta_mm_cart[X_AXIS]) + sq(delta_mm_cart[Y_AXIS]) + sq(delta_mm_cart[Z_AXIS])) : ABS(delta_mm_cart[Z_AXIS]); + mm = (delta_mm_cart.x != 0.0 || delta_mm_cart.y != 0.0) ? delta_mm_cart.magnitude() : ABS(delta_mm_cart.z); - inverse_kinematics(raw); + inverse_kinematics(machine); #if ENABLED(SCARA_FEEDRATE_SCALING) // For SCARA scale the feed rate from mm/s to degrees/s // i.e., Complete the angular vector in the given time. const float duration_recip = inv_duration ? inv_duration : fr_mm_s / mm; - const feedRate_t feedrate = HYPOT(delta[A_AXIS] - position_float[A_AXIS], delta[B_AXIS] - position_float[B_AXIS]) * duration_recip; + const feedRate_t feedrate = HYPOT(delta.a - position_float.a, delta.b - position_float.b) * duration_recip; #else const feedRate_t feedrate = fr_mm_s; #endif - if (buffer_segment(delta[A_AXIS], delta[B_AXIS], delta[C_AXIS], raw[E_AXIS] + if (buffer_segment(delta.a, delta.b, delta.c, machine.e #if ENABLED(JUNCTION_DEVIATION) , delta_mm_cart #endif , feedrate, extruder, mm )) { - position_cart[X_AXIS] = rx; - position_cart[Y_AXIS] = ry; - position_cart[Z_AXIS] = rz; - position_cart[E_AXIS] = e; + position_cart.set(rx, ry, rz, e); return true; } else return false; #else - return buffer_segment(raw, fr_mm_s, extruder, millimeters); + return buffer_segment(machine, fr_mm_s, extruder, millimeters); #endif } // buffer_line() @@ -2724,30 +2685,27 @@ void Planner::set_machine_position_mm(const float &a, const float &b, const floa #if ENABLED(DISTINCT_E_FACTORS) last_extruder = active_extruder; #endif - position[A_AXIS] = LROUND(a * settings.axis_steps_per_mm[A_AXIS]); - position[B_AXIS] = LROUND(b * settings.axis_steps_per_mm[B_AXIS]); - position[C_AXIS] = LROUND(c * settings.axis_steps_per_mm[C_AXIS]); - position[E_AXIS] = LROUND(e * settings.axis_steps_per_mm[E_AXIS_N(active_extruder)]); #if HAS_POSITION_FLOAT - position_float[A_AXIS] = a; - position_float[B_AXIS] = b; - position_float[C_AXIS] = c; - position_float[E_AXIS] = e; + position_float.set(a, b, c, e); #endif + position.set(LROUND(a * settings.axis_steps_per_mm[A_AXIS]), + LROUND(b * settings.axis_steps_per_mm[B_AXIS]), + LROUND(c * settings.axis_steps_per_mm[C_AXIS]), + LROUND(e * settings.axis_steps_per_mm[E_AXIS_N(active_extruder)])); if (has_blocks_queued()) { //previous_nominal_speed_sqr = 0.0; // Reset planner junction speeds. Assume start from rest. - //ZERO(previous_speed); + //previous_speed.reset(); buffer_sync_block(); } else - stepper.set_position(position[A_AXIS], position[B_AXIS], position[C_AXIS], position[E_AXIS]); + stepper.set_position(position); } void Planner::set_position_mm(const float &rx, const float &ry, const float &rz, const float &e) { - float raw[XYZE] = { rx, ry, rz, e }; + xyze_pos_t machine = { rx, ry, rz, e }; #if HAS_POSITION_MODIFIERS { - apply_modifiers(raw + apply_modifiers(machine #if HAS_LEVELING , true #endif @@ -2755,15 +2713,11 @@ void Planner::set_position_mm(const float &rx, const float &ry, const float &rz, } #endif #if IS_KINEMATIC - position_cart[X_AXIS] = rx; - position_cart[Y_AXIS] = ry; - position_cart[Z_AXIS] = rz; - position_cart[E_AXIS] = e; - - inverse_kinematics(raw); - set_machine_position_mm(delta[A_AXIS], delta[B_AXIS], delta[C_AXIS], raw[E_AXIS]); + position_cart.set(rx, ry, rz, e); + inverse_kinematics(machine); + set_machine_position_mm(delta.a, delta.b, delta.c, machine.e); #else - set_machine_position_mm(raw[X_AXIS], raw[Y_AXIS], raw[Z_AXIS], raw[E_AXIS]); + set_machine_position_mm(machine); #endif } @@ -2780,17 +2734,17 @@ void Planner::set_e_position_mm(const float &e) { #else const float e_new = e; #endif - position[E_AXIS] = LROUND(settings.axis_steps_per_mm[axis_index] * e_new); + position.e = LROUND(settings.axis_steps_per_mm[axis_index] * e_new); #if HAS_POSITION_FLOAT - position_float[E_AXIS] = e_new; + position_float.e = e_new; #endif #if IS_KINEMATIC - position_cart[E_AXIS] = e; + position_cart.e = e; #endif if (has_blocks_queued()) buffer_sync_block(); else - stepper.set_position(E_AXIS, position[E_AXIS]); + stepper.set_axis_position(E_AXIS, position.e); } // Recalculate the steps/s^2 acceleration rates, based on the mm/s^2 diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 2f3ee471d..c18b7753e 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -40,7 +40,7 @@ #endif #if ABL_PLANAR - #include "../libs/vector_3.h" + #include "../libs/vector_3.h" // for matrix_3x3 #endif #if ENABLED(FWRETRACT) @@ -51,6 +51,11 @@ #include "../feature/mixing.h" #endif +// Feedrate for manual moves +#ifdef MANUAL_FEEDRATE + constexpr xyze_feedrate_t manual_feedrate_mm_m = MANUAL_FEEDRATE; +#endif + enum BlockFlagBit : char { // Recalculate trapezoids on entry junction. For optimization. BLOCK_BIT_RECALCULATE, @@ -95,15 +100,8 @@ typedef struct block_t { acceleration; // acceleration mm/sec^2 union { - // Data used by all move blocks - struct { - // Fields used by the Bresenham algorithm for tracing the line - uint32_t steps[NUM_AXIS]; // Step count along each axis - }; - // Data used by all sync blocks - struct { - int32_t position[NUM_AXIS]; // New position to force when this sync block is executed - }; + abce_ulong_t steps; // Step count along each axis + abce_long_t position; // New position to force when this sync block is executed }; uint32_t step_event_count; // The number of step events required to complete this block @@ -259,19 +257,18 @@ class Planner { #endif #if HAS_CLASSIC_JERK - static float max_jerk[ - #if BOTH(JUNCTION_DEVIATION, LIN_ADVANCE) - XYZ // (mm/s^2) M205 XYZ - The largest speed change requiring no acceleration. - #else - XYZE // (mm/s^2) M205 XYZE - The largest speed change requiring no acceleration. - #endif - ]; + #if BOTH(JUNCTION_DEVIATION, LIN_ADVANCE) + static xyz_pos_t max_jerk; // (mm/s^2) M205 XYZ - The largest speed change requiring no acceleration. + #else + static xyze_pos_t max_jerk; // (mm/s^2) M205 XYZE - The largest speed change requiring no acceleration. + #endif #endif #if HAS_LEVELING static bool leveling_active; // Flag that bed leveling is enabled #if ABL_PLANAR static matrix_3x3 bed_level_matrix; // Transform to compensate for bed level + static constexpr xy_pos_t level_fulcrum = { X_TILT_FULCRUM, Y_TILT_FULCRUM }; #endif #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) static float z_fade_height, inverse_z_fade_height; @@ -285,11 +282,11 @@ class Planner { #endif #if HAS_POSITION_FLOAT - static float position_float[XYZE]; + static xyze_pos_t position_float; #endif #if IS_KINEMATIC - static float position_cart[XYZE]; + static xyze_pos_t position_cart; #endif static skew_factor_t skew_factor; @@ -304,12 +301,12 @@ class Planner { * The current position of the tool in absolute steps * Recalculated if any axis_steps_per_mm are changed by gcode */ - static int32_t position[NUM_AXIS]; + static xyze_long_t position; /** * Speed of previous path line segment */ - static float previous_speed[NUM_AXIS]; + static xyze_float_t previous_speed; /** * Nominal speed of previous path line segment (mm/s)^2 @@ -338,7 +335,7 @@ class Planner { // Old direction bits. Used for speed calculations static unsigned char old_direction_bits; // Segment times (in µs). Used for speed calculations - static uint32_t axis_segment_time_us[2][3]; + static xy_ulong_t axis_segment_time_us[3]; #endif #if HAS_SPI_LCD @@ -454,8 +451,7 @@ class Planner { } } } - FORCE_INLINE static void skew(float (&raw)[XYZ]) { skew(raw[X_AXIS], raw[Y_AXIS], raw[Z_AXIS]); } - FORCE_INLINE static void skew(float (&raw)[XYZE]) { skew(raw[X_AXIS], raw[Y_AXIS], raw[Z_AXIS]); } + FORCE_INLINE static void skew(xyz_pos_t &raw) { skew(raw.x, raw.y, raw.z); } FORCE_INLINE static void unskew(float &cx, float &cy, const float &cz) { if (WITHIN(cx, X_MIN_POS, X_MAX_POS) && WITHIN(cy, Y_MIN_POS, Y_MAX_POS)) { @@ -466,8 +462,7 @@ class Planner { } } } - FORCE_INLINE static void unskew(float (&raw)[XYZ]) { unskew(raw[X_AXIS], raw[Y_AXIS], raw[Z_AXIS]); } - FORCE_INLINE static void unskew(float (&raw)[XYZE]) { unskew(raw[X_AXIS], raw[Y_AXIS], raw[Z_AXIS]); } + FORCE_INLINE static void unskew(xyz_pos_t &raw) { unskew(raw.x, raw.y, raw.z); } #endif // SKEW_CORRECTION @@ -476,22 +471,24 @@ class Planner { * Apply leveling to transform a cartesian position * as it will be given to the planner and steppers. */ - static void apply_leveling(float &rx, float &ry, float &rz); - FORCE_INLINE static void apply_leveling(float (&raw)[XYZ]) { apply_leveling(raw[X_AXIS], raw[Y_AXIS], raw[Z_AXIS]); } - FORCE_INLINE static void apply_leveling(float (&raw)[XYZE]) { apply_leveling(raw[X_AXIS], raw[Y_AXIS], raw[Z_AXIS]); } - - static void unapply_leveling(float raw[XYZ]); + static void apply_leveling(xyz_pos_t &raw); + static void unapply_leveling(xyz_pos_t &raw); + FORCE_INLINE static void force_unapply_leveling(xyz_pos_t &raw) { + leveling_active = true; + unapply_leveling(raw); + leveling_active = false; + } #endif #if ENABLED(FWRETRACT) static void apply_retract(float &rz, float &e); - FORCE_INLINE static void apply_retract(float (&raw)[XYZE]) { apply_retract(raw[Z_AXIS], raw[E_AXIS]); } + FORCE_INLINE static void apply_retract(xyze_pos_t &raw) { apply_retract(raw.z, raw.e); } static void unapply_retract(float &rz, float &e); - FORCE_INLINE static void unapply_retract(float (&raw)[XYZE]) { unapply_retract(raw[Z_AXIS], raw[E_AXIS]); } + FORCE_INLINE static void unapply_retract(xyze_pos_t &raw) { unapply_retract(raw.z, raw.e); } #endif #if HAS_POSITION_MODIFIERS - FORCE_INLINE static void apply_modifiers(float (&pos)[XYZE] + FORCE_INLINE static void apply_modifiers(xyze_pos_t &pos #if HAS_LEVELING , bool leveling = #if PLANNER_LEVELING @@ -512,7 +509,7 @@ class Planner { #endif } - FORCE_INLINE static void unapply_modifiers(float (&pos)[XYZE] + FORCE_INLINE static void unapply_modifiers(xyze_pos_t &pos #if HAS_LEVELING , bool leveling = #if PLANNER_LEVELING @@ -578,12 +575,12 @@ class Planner { * * Returns true if movement was buffered, false otherwise */ - static bool _buffer_steps(const int32_t (&target)[XYZE] + static bool _buffer_steps(const xyze_long_t &target #if HAS_POSITION_FLOAT - , const float (&target_float)[ABCE] + , const xyze_pos_t &target_float #endif #if IS_KINEMATIC && ENABLED(JUNCTION_DEVIATION) - , const float (&delta_mm_cart)[XYZE] + , const xyze_float_t &delta_mm_cart #endif , feedRate_t fr_mm_s, const uint8_t extruder, const float &millimeters=0.0 ); @@ -601,12 +598,12 @@ class Planner { * Returns true is movement is acceptable, false otherwise */ static bool _populate_block(block_t * const block, bool split_move, - const int32_t (&target)[XYZE] + const xyze_long_t &target #if HAS_POSITION_FLOAT - , const float (&target_float)[XYZE] + , const xyze_pos_t &target_float #endif #if IS_KINEMATIC && ENABLED(JUNCTION_DEVIATION) - , const float (&delta_mm_cart)[XYZE] + , const xyze_float_t &delta_mm_cart #endif , feedRate_t fr_mm_s, const uint8_t extruder, const float &millimeters=0.0 ); @@ -638,18 +635,18 @@ class Planner { */ static bool buffer_segment(const float &a, const float &b, const float &c, const float &e #if IS_KINEMATIC && ENABLED(JUNCTION_DEVIATION) - , const float (&delta_mm_cart)[XYZE] + , const xyze_float_t &delta_mm_cart #endif , const feedRate_t &fr_mm_s, const uint8_t extruder, const float &millimeters=0.0 ); - FORCE_INLINE static bool buffer_segment(const float (&abce)[ABCE] + FORCE_INLINE static bool buffer_segment(abce_pos_t &abce #if IS_KINEMATIC && ENABLED(JUNCTION_DEVIATION) - , const float (&delta_mm_cart)[XYZE] + , const xyze_float_t &delta_mm_cart #endif , const feedRate_t &fr_mm_s, const uint8_t extruder, const float &millimeters=0.0 ) { - return buffer_segment(abce[A_AXIS], abce[B_AXIS], abce[C_AXIS], abce[E_AXIS] + return buffer_segment(abce.a, abce.b, abce.c, abce.e #if IS_KINEMATIC && ENABLED(JUNCTION_DEVIATION) , delta_mm_cart #endif @@ -675,12 +672,12 @@ class Planner { #endif ); - FORCE_INLINE static bool buffer_line(const float (&cart)[XYZE], const feedRate_t &fr_mm_s, const uint8_t extruder, const float millimeters=0.0 + FORCE_INLINE static bool buffer_line(const xyze_pos_t &cart, const feedRate_t &fr_mm_s, const uint8_t extruder, const float millimeters=0.0 #if ENABLED(SCARA_FEEDRATE_SCALING) , const float &inv_duration=0.0 #endif ) { - return buffer_line(cart[X_AXIS], cart[Y_AXIS], cart[Z_AXIS], cart[E_AXIS], fr_mm_s, extruder, millimeters + return buffer_line(cart.x, cart.y, cart.z, cart.e, fr_mm_s, extruder, millimeters #if ENABLED(SCARA_FEEDRATE_SCALING) , inv_duration #endif @@ -701,7 +698,7 @@ class Planner { * Clears previous speed values. */ static void set_position_mm(const float &rx, const float &ry, const float &rz, const float &e); - FORCE_INLINE static void set_position_mm(const float (&cart)[XYZE]) { set_position_mm(cart[X_AXIS], cart[Y_AXIS], cart[Z_AXIS], cart[E_AXIS]); } + FORCE_INLINE static void set_position_mm(const xyze_pos_t &cart) { set_position_mm(cart.x, cart.y, cart.z, cart.e); } static void set_e_position_mm(const float &e); /** @@ -711,7 +708,7 @@ class Planner { * conversions are applied. */ static void set_machine_position_mm(const float &a, const float &b, const float &c, const float &e); - FORCE_INLINE static void set_machine_position_mm(const float (&abce)[ABCE]) { set_machine_position_mm(abce[A_AXIS], abce[B_AXIS], abce[C_AXIS], abce[E_AXIS]); } + FORCE_INLINE static void set_machine_position_mm(const abce_pos_t &abce) { set_machine_position_mm(abce.a, abce.b, abce.c, abce.e); } /** * Get an axis position according to stepper position(s) @@ -942,14 +939,13 @@ class Planner { #if ENABLED(JUNCTION_DEVIATION) - FORCE_INLINE static void normalize_junction_vector(float (&vector)[XYZE]) { + FORCE_INLINE static void normalize_junction_vector(xyze_float_t &vector) { float magnitude_sq = 0; LOOP_XYZE(idx) if (vector[idx]) magnitude_sq += sq(vector[idx]); - const float inv_magnitude = RSQRT(magnitude_sq); - LOOP_XYZE(idx) vector[idx] *= inv_magnitude; + vector *= RSQRT(magnitude_sq); } - FORCE_INLINE static float limit_value_by_axis_maximum(const float &max_value, float (&unit_vec)[XYZE]) { + FORCE_INLINE static float limit_value_by_axis_maximum(const float &max_value, xyze_float_t &unit_vec) { float limit_value = max_value; LOOP_XYZE(idx) if (unit_vec[idx]) // Avoid divide by zero NOMORE(limit_value, ABS(settings.max_acceleration_mm_per_s2[idx] / unit_vec[idx])); diff --git a/Marlin/src/module/planner_bezier.cpp b/Marlin/src/module/planner_bezier.cpp index 6e6746bce..080f4e41a 100644 --- a/Marlin/src/module/planner_bezier.cpp +++ b/Marlin/src/module/planner_bezier.cpp @@ -108,21 +108,17 @@ static inline float dist1(const float &x1, const float &y1, const float &x2, con * power available on Arduino, I think it is not wise to implement it. */ void cubic_b_spline( - const float position[NUM_AXIS], // current position - const float target[NUM_AXIS], // target position - const float (&offset)[4], // a pair of offsets + const xyze_pos_t &position, // current position + const xyze_pos_t &target, // target position + const xy_pos_t (&offsets)[2], // a pair of offsets const feedRate_t &scaled_fr_mm_s, // mm/s scaled by feedrate % const uint8_t extruder ) { // Absolute first and second control points are recovered. - const float first0 = position[X_AXIS] + offset[0], - first1 = position[Y_AXIS] + offset[1], - second0 = target[X_AXIS] + offset[2], - second1 = target[Y_AXIS] + offset[3]; - - float bez_target[4]; - bez_target[X_AXIS] = position[X_AXIS]; - bez_target[Y_AXIS] = position[Y_AXIS]; + const xy_pos_t first = position + offsets[0], second = target + offsets[1]; + + xyze_pos_t bez_target; + bez_target.set(position.x, position.y); float step = MAX_STEP; millis_t next_idle_ms = millis() + 200UL; @@ -141,15 +137,15 @@ void cubic_b_spline( bool did_reduce = false; float new_t = t + step; NOMORE(new_t, 1); - float new_pos0 = eval_bezier(position[X_AXIS], first0, second0, target[X_AXIS], new_t), - new_pos1 = eval_bezier(position[Y_AXIS], first1, second1, target[Y_AXIS], new_t); + float new_pos0 = eval_bezier(position.x, first.x, second.x, target.x, new_t), + new_pos1 = eval_bezier(position.y, first.y, second.y, target.y, new_t); for (;;) { if (new_t - t < (MIN_STEP)) break; const float candidate_t = 0.5f * (t + new_t), - candidate_pos0 = eval_bezier(position[X_AXIS], first0, second0, target[X_AXIS], candidate_t), - candidate_pos1 = eval_bezier(position[Y_AXIS], first1, second1, target[Y_AXIS], candidate_t), - interp_pos0 = 0.5f * (bez_target[X_AXIS] + new_pos0), - interp_pos1 = 0.5f * (bez_target[Y_AXIS] + new_pos1); + candidate_pos0 = eval_bezier(position.x, first.x, second.x, target.x, candidate_t), + candidate_pos1 = eval_bezier(position.y, first.y, second.y, target.y, candidate_t), + interp_pos0 = 0.5f * (bez_target.x + new_pos0), + interp_pos1 = 0.5f * (bez_target.y + new_pos1); if (dist1(candidate_pos0, candidate_pos1, interp_pos0, interp_pos1) <= (SIGMA)) break; new_t = candidate_t; new_pos0 = candidate_pos0; @@ -162,10 +158,10 @@ void cubic_b_spline( if (new_t - t > MAX_STEP) break; const float candidate_t = t + 2 * (new_t - t); if (candidate_t >= 1) break; - const float candidate_pos0 = eval_bezier(position[X_AXIS], first0, second0, target[X_AXIS], candidate_t), - candidate_pos1 = eval_bezier(position[Y_AXIS], first1, second1, target[Y_AXIS], candidate_t), - interp_pos0 = 0.5f * (bez_target[X_AXIS] + candidate_pos0), - interp_pos1 = 0.5f * (bez_target[Y_AXIS] + candidate_pos1); + const float candidate_pos0 = eval_bezier(position.x, first.x, second.x, target.x, candidate_t), + candidate_pos1 = eval_bezier(position.y, first.y, second.y, target.y, candidate_t), + interp_pos0 = 0.5f * (bez_target.x + candidate_pos0), + interp_pos1 = 0.5f * (bez_target.y + candidate_pos1); if (dist1(new_pos0, new_pos1, interp_pos0, interp_pos1) > (SIGMA)) break; new_t = candidate_t; new_pos0 = candidate_pos0; @@ -187,19 +183,19 @@ void cubic_b_spline( t = new_t; // Compute and send new position - bez_target[X_AXIS] = new_pos0; - bez_target[Y_AXIS] = new_pos1; - // FIXME. The following two are wrong, since the parameter t is - // not linear in the distance. - bez_target[Z_AXIS] = interp(position[Z_AXIS], target[Z_AXIS], t); - bez_target[E_AXIS] = interp(position[E_AXIS], target[E_AXIS], t); - apply_motion_limits(bez_target); + xyze_pos_t new_bez = { + new_pos0, new_pos1, + interp(position.z, target.z, t), // FIXME. These two are wrong, since the parameter t is + interp(position.e, target.e, t) // not linear in the distance. + }; + apply_motion_limits(new_bez); + bez_target = new_bez; #if HAS_LEVELING && !PLANNER_LEVELING - float pos[XYZE] = { bez_target[X_AXIS], bez_target[Y_AXIS], bez_target[Z_AXIS], bez_target[E_AXIS] }; + xyze_pos_t pos = bez_target; planner.apply_leveling(pos); #else - const float (&pos)[XYZE] = bez_target; + const xyze_pos_t &pos = bez_target; #endif if (!planner.buffer_line(pos, scaled_fr_mm_s, active_extruder, step)) diff --git a/Marlin/src/module/planner_bezier.h b/Marlin/src/module/planner_bezier.h index 5e959dd0f..d0aa82858 100644 --- a/Marlin/src/module/planner_bezier.h +++ b/Marlin/src/module/planner_bezier.h @@ -28,13 +28,12 @@ * */ -#include -#include "../core/macros.h" +#include "../core/types.h" void cubic_b_spline( - const float position[NUM_AXIS], // current position - const float target[NUM_AXIS], // target position - const float (&offset)[4], // a pair of offsets + const xyze_pos_t &position, // current position + const xyze_pos_t &target, // target position + const xy_pos_t (&offsets)[2], // a pair of offsets const feedRate_t &scaled_fr_mm_s, // mm/s scaled by feedrate % const uint8_t extruder ); diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index ce0d84e41..0217a2fd5 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -56,7 +56,7 @@ #include "../feature/backlash.h" #endif -float probe_offset[XYZ]; // Initialized by settings.load() +xyz_pos_t probe_offset; // Initialized by settings.load() #if ENABLED(BLTOUCH) #include "../feature/bltouch.h" @@ -146,10 +146,10 @@ float probe_offset[XYZ]; // Initialized by settings.load() // Move down to the bed to stow the probe void run_stow_moves_script() { - const float old_pos[] = { current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS] }; + const xyz_pos_t oldpos = current_position; endstops.enable_z_probe(false); do_blocking_move_to_z(TOUCH_MI_RETRACT_Z, MMM_TO_MMS(HOMING_FEEDRATE_Z)); - do_blocking_move_to(old_pos, MMM_TO_MMS(HOMING_FEEDRATE_Z)); + do_blocking_move_to(oldpos, MMM_TO_MMS(HOMING_FEEDRATE_Z)); } #elif ENABLED(Z_PROBE_ALLEN_KEY) @@ -159,35 +159,35 @@ float probe_offset[XYZ]; // Initialized by settings.load() #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_1_FEEDRATE #define Z_PROBE_ALLEN_KEY_DEPLOY_1_FEEDRATE 0.0 #endif - constexpr float deploy_1[] = Z_PROBE_ALLEN_KEY_DEPLOY_1; + constexpr xyz_pos_t deploy_1 = Z_PROBE_ALLEN_KEY_DEPLOY_1; do_blocking_move_to(deploy_1, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_1_FEEDRATE)); #endif #ifdef Z_PROBE_ALLEN_KEY_DEPLOY_2 #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE #define Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE 0.0 #endif - constexpr float deploy_2[] = Z_PROBE_ALLEN_KEY_DEPLOY_2; + constexpr xyz_pos_t deploy_2 = Z_PROBE_ALLEN_KEY_DEPLOY_2; do_blocking_move_to(deploy_2, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE)); #endif #ifdef Z_PROBE_ALLEN_KEY_DEPLOY_3 #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE #define Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE 0.0 #endif - constexpr float deploy_3[] = Z_PROBE_ALLEN_KEY_DEPLOY_3; + constexpr xyz_pos_t deploy_3 = Z_PROBE_ALLEN_KEY_DEPLOY_3; do_blocking_move_to(deploy_3, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE)); #endif #ifdef Z_PROBE_ALLEN_KEY_DEPLOY_4 #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_4_FEEDRATE #define Z_PROBE_ALLEN_KEY_DEPLOY_4_FEEDRATE 0.0 #endif - constexpr float deploy_4[] = Z_PROBE_ALLEN_KEY_DEPLOY_4; + constexpr xyz_pos_t deploy_4 = Z_PROBE_ALLEN_KEY_DEPLOY_4; do_blocking_move_to(deploy_4, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_4_FEEDRATE)); #endif #ifdef Z_PROBE_ALLEN_KEY_DEPLOY_5 #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_5_FEEDRATE #define Z_PROBE_ALLEN_KEY_DEPLOY_5_FEEDRATE 0.0 #endif - constexpr float deploy_5[] = Z_PROBE_ALLEN_KEY_DEPLOY_5; + constexpr xyz_pos_t deploy_5 = Z_PROBE_ALLEN_KEY_DEPLOY_5; do_blocking_move_to(deploy_5, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_5_FEEDRATE)); #endif } @@ -197,35 +197,35 @@ float probe_offset[XYZ]; // Initialized by settings.load() #ifndef Z_PROBE_ALLEN_KEY_STOW_1_FEEDRATE #define Z_PROBE_ALLEN_KEY_STOW_1_FEEDRATE 0.0 #endif - constexpr float stow_1[] = Z_PROBE_ALLEN_KEY_STOW_1; + constexpr xyz_pos_t stow_1 = Z_PROBE_ALLEN_KEY_STOW_1; do_blocking_move_to(stow_1, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_1_FEEDRATE)); #endif #ifdef Z_PROBE_ALLEN_KEY_STOW_2 #ifndef Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE #define Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE 0.0 #endif - constexpr float stow_2[] = Z_PROBE_ALLEN_KEY_STOW_2; + constexpr xyz_pos_t stow_2 = Z_PROBE_ALLEN_KEY_STOW_2; do_blocking_move_to(stow_2, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE)); #endif #ifdef Z_PROBE_ALLEN_KEY_STOW_3 #ifndef Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE #define Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE 0.0 #endif - constexpr float stow_3[] = Z_PROBE_ALLEN_KEY_STOW_3; + constexpr xyz_pos_t stow_3 = Z_PROBE_ALLEN_KEY_STOW_3; do_blocking_move_to(stow_3, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE)); #endif #ifdef Z_PROBE_ALLEN_KEY_STOW_4 #ifndef Z_PROBE_ALLEN_KEY_STOW_4_FEEDRATE #define Z_PROBE_ALLEN_KEY_STOW_4_FEEDRATE 0.0 #endif - constexpr float stow_4[] = Z_PROBE_ALLEN_KEY_STOW_4; + constexpr xyz_pos_t stow_4 = Z_PROBE_ALLEN_KEY_STOW_4; do_blocking_move_to(stow_4, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_4_FEEDRATE)); #endif #ifdef Z_PROBE_ALLEN_KEY_STOW_5 #ifndef Z_PROBE_ALLEN_KEY_STOW_5_FEEDRATE #define Z_PROBE_ALLEN_KEY_STOW_5_FEEDRATE 0.0 #endif - constexpr float stow_5[] = Z_PROBE_ALLEN_KEY_STOW_5; + constexpr xyz_pos_t stow_5 = Z_PROBE_ALLEN_KEY_STOW_5; do_blocking_move_to(stow_5, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_5_FEEDRATE)); #endif } @@ -263,11 +263,11 @@ inline void do_probe_raise(const float z_raise) { if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("do_probe_raise(", z_raise, ")"); float z_dest = z_raise; - if (probe_offset[Z_AXIS] < 0) z_dest -= probe_offset[Z_AXIS]; + if (probe_offset.z < 0) z_dest -= probe_offset.z; NOMORE(z_dest, Z_MAX_POS); - if (z_dest > current_position[Z_AXIS]) + if (z_dest > current_position.z) do_blocking_move_to_z(z_dest); } @@ -384,8 +384,7 @@ bool set_probe_deployed(const bool deploy) { } #endif - const float oldXpos = current_position[X_AXIS], - oldYpos = current_position[Y_AXIS]; + const xy_pos_t old_xy = current_position; #if ENABLED(PROBE_TRIGGERED_WHEN_STOWED_TEST) #if USES_Z_MIN_PROBE_ENDSTOP @@ -419,7 +418,7 @@ bool set_probe_deployed(const bool deploy) { #endif - do_blocking_move_to(oldXpos, oldYpos, current_position[Z_AXIS]); // return to position before deploy + do_blocking_move_to(old_xy); endstops.enable_z_probe(deploy); return false; } @@ -427,9 +426,9 @@ bool set_probe_deployed(const bool deploy) { #ifdef Z_AFTER_PROBING // After probing move to a preferred Z position void move_z_after_probing() { - if (current_position[Z_AXIS] != Z_AFTER_PROBING) { + if (current_position.z != Z_AFTER_PROBING) { do_blocking_move_to_z(Z_AFTER_PROBING); - current_position[Z_AXIS] = Z_AFTER_PROBING; + current_position.z = Z_AFTER_PROBING; } } #endif @@ -532,7 +531,7 @@ static bool do_probe_move(const float z, const feedRate_t fr_mm_s) { * @brief Probe at the current XY (possibly more than once) to find the bed Z. * * @details Used by probe_at_point to get the bed Z height at the current XY. - * Leaves current_position[Z_AXIS] at the height where the probe triggered. + * Leaves current_position.z at the height where the probe triggered. * * @return The Z position of the bed at the current XY or NAN on error. */ @@ -542,7 +541,7 @@ static float run_z_probe() { // Stop the probe before it goes too low to prevent damage. // If Z isn't known then probe to -10mm. - const float z_probe_low_point = TEST(axis_known_position, Z_AXIS) ? -probe_offset[Z_AXIS] + Z_PROBE_LOW_POINT : -10.0; + const float z_probe_low_point = TEST(axis_known_position, Z_AXIS) ? -probe_offset.z + Z_PROBE_LOW_POINT : -10.0; // Double-probing does a fast probe followed by a slow probe #if TOTAL_PROBING == 2 @@ -556,22 +555,22 @@ static float run_z_probe() { return NAN; } - const float first_probe_z = current_position[Z_AXIS]; + const float first_probe_z = current_position.z; if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("1st Probe Z:", first_probe_z); // Raise to give the probe clearance - do_blocking_move_to_z(current_position[Z_AXIS] + Z_CLEARANCE_MULTI_PROBE, MMM_TO_MMS(Z_PROBE_SPEED_FAST)); + do_blocking_move_to_z(current_position.z + Z_CLEARANCE_MULTI_PROBE, MMM_TO_MMS(Z_PROBE_SPEED_FAST)); #elif Z_PROBE_SPEED_FAST != Z_PROBE_SPEED_SLOW // If the nozzle is well over the travel height then // move down quickly before doing the slow probe - const float z = Z_CLEARANCE_DEPLOY_PROBE + 5.0 + (probe_offset[Z_AXIS] < 0 ? -probe_offset[Z_AXIS] : 0); - if (current_position[Z_AXIS] > z) { + const float z = Z_CLEARANCE_DEPLOY_PROBE + 5.0 + (probe_offset.z < 0 ? -probe_offset.z : 0); + if (current_position.z > z) { // Probe down fast. If the probe never triggered, raise for probe clearance if (!do_probe_move(z, MMM_TO_MMS(Z_PROBE_SPEED_FAST))) - do_blocking_move_to_z(current_position[Z_AXIS] + Z_CLEARANCE_BETWEEN_PROBES, MMM_TO_MMS(Z_PROBE_SPEED_FAST)); + do_blocking_move_to_z(current_position.z + Z_CLEARANCE_BETWEEN_PROBES, MMM_TO_MMS(Z_PROBE_SPEED_FAST)); } #endif @@ -603,7 +602,7 @@ static float run_z_probe() { backlash.measure_with_probe(); #endif - const float z = current_position[Z_AXIS]; + const float z = current_position.z; #if EXTRA_PROBING // Insert Z measurement into probes[]. Keep it sorted ascending. @@ -654,7 +653,7 @@ static float run_z_probe() { #elif TOTAL_PROBING == 2 - const float z2 = current_position[Z_AXIS]; + const float z2 = current_position.z; if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("2nd Probe Z:", z2, " Discrepancy:", first_probe_z - z2); @@ -664,7 +663,7 @@ static float run_z_probe() { #else // Return the single probe result - const float measured_z = current_position[Z_AXIS]; + const float measured_z = current_position.z; #endif @@ -694,20 +693,19 @@ float probe_at_point(const float &rx, const float &ry, const ProbePtRaise raise_ } // TODO: Adapt for SCARA, where the offset rotates - float nx = rx, ny = ry; + xyz_pos_t npos = { rx, ry }; if (probe_relative) { - if (!position_is_reachable_by_probe(rx, ry)) return NAN; // The given position is in terms of the probe - nx -= probe_offset[X_AXIS]; // Get the nozzle position - ny -= probe_offset[Y_AXIS]; + if (!position_is_reachable_by_probe(npos)) return NAN; // The given position is in terms of the probe + npos -= probe_offset; // Get the nozzle position } - else if (!position_is_reachable(nx, ny)) return NAN; // The given position is in terms of the nozzle + else if (!position_is_reachable(npos)) return NAN; // The given position is in terms of the nozzle - const float nz = + npos.z = #if ENABLED(DELTA) // Move below clip height or xy move will be aborted by do_blocking_move_to - _MIN(current_position[Z_AXIS], delta_clip_start_height) + _MIN(current_position.z, delta_clip_start_height) #else - current_position[Z_AXIS] + current_position.z #endif ; @@ -715,15 +713,15 @@ float probe_at_point(const float &rx, const float &ry, const ProbePtRaise raise_ feedrate_mm_s = XY_PROBE_FEEDRATE_MM_S; // Move the probe to the starting XYZ - do_blocking_move_to(nx, ny, nz); + do_blocking_move_to(npos); float measured_z = NAN; if (!DEPLOY_PROBE()) { - measured_z = run_z_probe() + probe_offset[Z_AXIS]; + measured_z = run_z_probe() + probe_offset.z; const bool big_raise = raise_after == PROBE_PT_BIG_RAISE; if (big_raise || raise_after == PROBE_PT_RAISE) - do_blocking_move_to_z(current_position[Z_AXIS] + (big_raise ? 25 : Z_CLEARANCE_BETWEEN_PROBES), MMM_TO_MMS(Z_PROBE_SPEED_FAST)); + do_blocking_move_to_z(current_position.z + (big_raise ? 25 : Z_CLEARANCE_BETWEEN_PROBES), MMM_TO_MMS(Z_PROBE_SPEED_FAST)); else if (raise_after == PROBE_PT_STOW) if (STOW_PROBE()) measured_z = NAN; } diff --git a/Marlin/src/module/probe.h b/Marlin/src/module/probe.h index dbdb66e14..ab546b9be 100644 --- a/Marlin/src/module/probe.h +++ b/Marlin/src/module/probe.h @@ -29,9 +29,9 @@ #if HAS_BED_PROBE - constexpr float nozzle_to_probe_offset[XYZ] = NOZZLE_TO_PROBE_OFFSET; + constexpr xyz_pos_t nozzle_to_probe_offset = NOZZLE_TO_PROBE_OFFSET; - extern float probe_offset[XYZ]; + extern xyz_pos_t probe_offset; bool set_probe_deployed(const bool deploy); #ifdef Z_AFTER_PROBING @@ -44,6 +44,9 @@ PROBE_PT_BIG_RAISE // Raise to big clearance after run_z_probe }; float probe_at_point(const float &rx, const float &ry, const ProbePtRaise raise_after=PROBE_PT_NONE, const uint8_t verbose_level=0, const bool probe_relative=true); + inline float probe_at_point(const xy_pos_t &pos, const ProbePtRaise raise_after=PROBE_PT_NONE, const uint8_t verbose_level=0, const bool probe_relative=true) { + return probe_at_point(pos.x, pos.y, raise_after, verbose_level, probe_relative); + } #define DEPLOY_PROBE() set_probe_deployed(true) #define STOW_PROBE() set_probe_deployed(false) #if HAS_HEATED_BED && ENABLED(WAIT_FOR_BED_HEATER) @@ -52,7 +55,8 @@ #else - constexpr float probe_offset[XYZ] = { 0 }; + constexpr xyz_pos_t probe_offset{0}; + #define DEPLOY_PROBE() #define STOW_PROBE() @@ -64,7 +68,7 @@ #if IS_KINEMATIC PROBE_X_MIN, MESH_MIN_X #else - (X_MIN_BED) + (MIN_PROBE_EDGE_LEFT), (X_MIN_POS) + probe_offset[X_AXIS] + (X_MIN_BED) + (MIN_PROBE_EDGE_LEFT), (X_MIN_POS) + probe_offset.x #endif ); } @@ -73,7 +77,7 @@ #if IS_KINEMATIC PROBE_X_MAX, MESH_MAX_X #else - (X_MAX_BED) - (MIN_PROBE_EDGE_RIGHT), (X_MAX_POS) + probe_offset[X_AXIS] + (X_MAX_BED) - (MIN_PROBE_EDGE_RIGHT), (X_MAX_POS) + probe_offset.x #endif ); } @@ -82,7 +86,7 @@ #if IS_KINEMATIC PROBE_Y_MIN, MESH_MIN_Y #else - (Y_MIN_BED) + (MIN_PROBE_EDGE_FRONT), (Y_MIN_POS) + probe_offset[Y_AXIS] + (Y_MIN_BED) + (MIN_PROBE_EDGE_FRONT), (Y_MIN_POS) + probe_offset.y #endif ); } @@ -91,7 +95,7 @@ #if IS_KINEMATIC PROBE_Y_MAX, MESH_MAX_Y #else - (Y_MAX_BED) - (MIN_PROBE_EDGE_BACK), (Y_MAX_POS) + probe_offset[Y_AXIS] + (Y_MAX_BED) - (MIN_PROBE_EDGE_BACK), (Y_MAX_POS) + probe_offset.y #endif ); } diff --git a/Marlin/src/module/scara.cpp b/Marlin/src/module/scara.cpp index fe98df46b..768e31181 100644 --- a/Marlin/src/module/scara.cpp +++ b/Marlin/src/module/scara.cpp @@ -36,25 +36,25 @@ float delta_segments_per_second = SCARA_SEGMENTS_PER_SECOND; void scara_set_axis_is_at_home(const AxisEnum axis) { if (axis == Z_AXIS) - current_position[Z_AXIS] = Z_HOME_POS; + current_position.z = Z_HOME_POS; else { /** * SCARA homes XY at the same time */ - float homeposition[XYZ]; + xyz_pos_t homeposition; LOOP_XYZ(i) homeposition[i] = base_home_pos((AxisEnum)i); - // SERIAL_ECHOLNPAIR("homeposition X:", homeposition[X_AXIS], " Y:", homeposition[Y_AXIS]); + // SERIAL_ECHOLNPAIR("homeposition X:", homeposition.x, " Y:", homeposition.y); /** * Get Home position SCARA arm angles using inverse kinematics, * and calculate homing offset using forward kinematics */ inverse_kinematics(homeposition); - forward_kinematics_SCARA(delta[A_AXIS], delta[B_AXIS]); + forward_kinematics_SCARA(delta.a, delta.b); - // SERIAL_ECHOLNPAIR("Cartesian X:", cartes[X_AXIS], " Y:", cartes[Y_AXIS]); + // SERIAL_ECHOLNPAIR("Cartesian X:", cartes.x, " Y:", cartes.y); current_position[axis] = cartes[axis]; @@ -62,8 +62,10 @@ void scara_set_axis_is_at_home(const AxisEnum axis) { } } +static constexpr xy_pos_t scara_offset = { SCARA_OFFSET_X, SCARA_OFFSET_Y }; + /** - * Morgan SCARA Forward Kinematics. Results in cartes[]. + * Morgan SCARA Forward Kinematics. Results in 'cartes'. * Maths and first version by QHARLEY. * Integrated into Marlin and slightly restructured by Joachim Cerny. */ @@ -74,8 +76,8 @@ void forward_kinematics_SCARA(const float &a, const float &b) { b_sin = sin(RADIANS(b)) * L2, b_cos = cos(RADIANS(b)) * L2; - cartes[X_AXIS] = a_cos + b_cos + SCARA_OFFSET_X; //theta - cartes[Y_AXIS] = a_sin + b_sin + SCARA_OFFSET_Y; //theta+phi + cartes.set(a_cos + b_cos + scara_offset.x, // theta + a_sin + b_sin + scara_offset.y); // theta+phi /* SERIAL_ECHOLNPAIR( @@ -86,31 +88,32 @@ void forward_kinematics_SCARA(const float &a, const float &b) { " b_sin=", b_sin, " b_cos=", b_cos ); - SERIAL_ECHOLNPAIR(" cartes (X,Y) = "(cartes[X_AXIS], ", ", cartes[Y_AXIS], ")"); + SERIAL_ECHOLNPAIR(" cartes (X,Y) = "(cartes.x, ", ", cartes.y, ")"); //*/ } /** - * Morgan SCARA Inverse Kinematics. Results in delta[]. + * Morgan SCARA Inverse Kinematics. Results in 'delta'. * * See http://forums.reprap.org/read.php?185,283327 * * Maths and first version by QHARLEY. * Integrated into Marlin and slightly restructured by Joachim Cerny. */ -void inverse_kinematics(const float (&raw)[XYZ]) { +void inverse_kinematics(const xyz_pos_t &raw) { - static float C2, S2, SK1, SK2, THETA, PSI; + float C2, S2, SK1, SK2, THETA, PSI; - float sx = raw[X_AXIS] - SCARA_OFFSET_X, // Translate SCARA to standard X Y - sy = raw[Y_AXIS] - SCARA_OFFSET_Y; // With scaling factor. + // Translate SCARA to standard XY with scaling factor + const xy_pos_t spos = raw - scara_offset; + const float H2 = HYPOT2(spos.x, spos.y); if (L1 == L2) - C2 = HYPOT2(sx, sy) / L1_2_2 - 1; + C2 = H2 / L1_2_2 - 1; else - C2 = (HYPOT2(sx, sy) - (L1_2 + L2_2)) / (2.0 * L1 * L2); + C2 = (H2 - (L1_2 + L2_2)) / (2.0 * L1 * L2); - S2 = SQRT(1 - sq(C2)); + S2 = SQRT(1.0f - sq(C2)); // Unrotated Arm1 plus rotated Arm2 gives the distance from Center to End SK1 = L1 + L2 * C2; @@ -119,14 +122,12 @@ void inverse_kinematics(const float (&raw)[XYZ]) { SK2 = L2 * S2; // Angle of Arm1 is the difference between Center-to-End angle and the Center-to-Elbow - THETA = ATAN2(SK1, SK2) - ATAN2(sx, sy); + THETA = ATAN2(SK1, SK2) - ATAN2(spos.x, spos.y); // Angle of Arm2 PSI = ATAN2(S2, C2); - delta[A_AXIS] = DEGREES(THETA); // theta is support arm angle - delta[B_AXIS] = DEGREES(THETA + PSI); // equal to sub arm angle (inverted motor) - delta[C_AXIS] = raw[Z_AXIS]; + delta.set(DEGREES(THETA), DEGREES(THETA + PSI), raw.z); /* DEBUG_POS("SCARA IK", raw); diff --git a/Marlin/src/module/scara.h b/Marlin/src/module/scara.h index 3a17cddbf..cde1d1bcd 100644 --- a/Marlin/src/module/scara.h +++ b/Marlin/src/module/scara.h @@ -36,11 +36,7 @@ float constexpr L1 = SCARA_LINKAGE_1, L2 = SCARA_LINKAGE_2, void scara_set_axis_is_at_home(const AxisEnum axis); -void inverse_kinematics(const float (&raw)[XYZ]); -FORCE_INLINE void inverse_kinematics(const float (&raw)[XYZE]) { - const float raw_xyz[XYZ] = { raw[X_AXIS], raw[Y_AXIS], raw[Z_AXIS] }; - inverse_kinematics(raw_xyz); -} +void inverse_kinematics(const xyz_pos_t &raw); void forward_kinematics_SCARA(const float &a, const float &b); void scara_report_positions(); diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index b806cb114..6bee709b4 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -169,10 +169,10 @@ uint8_t Stepper::steps_per_isr; #endif uint8_t Stepper::oversampling_factor; -int32_t Stepper::delta_error[XYZE] = { 0 }; +xyze_long_t Stepper::delta_error{0}; -uint32_t Stepper::advance_dividend[XYZE] = { 0 }, - Stepper::advance_divisor = 0, +xyze_ulong_t Stepper::advance_dividend{0}; +uint32_t Stepper::advance_divisor = 0, Stepper::step_events_completed = 0, // The number of step events executed in the current block Stepper::accelerate_until, // The count at which to stop accelerating Stepper::decelerate_after, // The count at which to start decelerating @@ -218,10 +218,9 @@ int32_t Stepper::ticks_nominal = -1; uint32_t Stepper::acc_step_rate; // needed for deceleration start point #endif -volatile int32_t Stepper::endstops_trigsteps[XYZ]; - -volatile int32_t Stepper::count_position[NUM_AXIS] = { 0 }; -int8_t Stepper::count_direction[NUM_AXIS] = { 0, 0, 0, 0 }; +xyz_long_t Stepper::endstops_trigsteps; +xyze_long_t Stepper::count_position{0}; +xyze_int8_t Stepper::count_direction{0}; #define DUAL_ENDSTOP_APPLY_STEP(A,V) \ if (separate_multi_axis) { \ @@ -390,20 +389,20 @@ void Stepper::set_directions() { // what e-steppers will step. Likely all. Set all. if (motor_direction(E_AXIS)) { MIXER_STEPPER_LOOP(j) REV_E_DIR(j); - count_direction[E_AXIS] = -1; + count_direction.e = -1; } else { MIXER_STEPPER_LOOP(j) NORM_E_DIR(j); - count_direction[E_AXIS] = 1; + count_direction.e = 1; } #else if (motor_direction(E_AXIS)) { REV_E_DIR(stepper_extruder); - count_direction[E_AXIS] = -1; + count_direction.e = -1; } else { NORM_E_DIR(stepper_extruder); - count_direction[E_AXIS] = 1; + count_direction.e = 1; } #endif #endif // !LIN_ADVANCE @@ -1459,15 +1458,15 @@ void Stepper::stepper_pulse_phase_isr() { // Pulse Extruders // Tick the E axis, correct error term and update position #if EITHER(LIN_ADVANCE, MIXING_EXTRUDER) - delta_error[E_AXIS] += advance_dividend[E_AXIS]; - if (delta_error[E_AXIS] >= 0) { - count_position[E_AXIS] += count_direction[E_AXIS]; + delta_error.e += advance_dividend.e; + if (delta_error.e >= 0) { + count_position.e += count_direction.e; #if ENABLED(LIN_ADVANCE) - delta_error[E_AXIS] -= advance_divisor; + delta_error.e -= advance_divisor; // Don't step E here - But remember the number of steps to perform motor_direction(E_AXIS) ? --LA_steps : ++LA_steps; #else // !LIN_ADVANCE && MIXING_EXTRUDER - // Don't adjust delta_error[E_AXIS] here! + // Don't adjust delta_error.e here! // Being positive is the criteria for ending the pulse. E_STEP_WRITE(mixer.get_next_stepper(), !INVERT_E_STEP_PIN); #endif @@ -1504,8 +1503,8 @@ void Stepper::stepper_pulse_phase_isr() { #if DISABLED(LIN_ADVANCE) #if ENABLED(MIXING_EXTRUDER) - if (delta_error[E_AXIS] >= 0) { - delta_error[E_AXIS] -= advance_divisor; + if (delta_error.e >= 0) { + delta_error.e -= advance_divisor; E_STEP_WRITE(mixer.get_stepper(), INVERT_E_STEP_PIN); } #else // !MIXING_EXTRUDER @@ -1660,10 +1659,7 @@ uint32_t Stepper::stepper_block_phase_isr() { // Sync block? Sync the stepper counts and return while (TEST(current_block->flag, BLOCK_BIT_SYNC_POSITION)) { - _set_position( - current_block->position[A_AXIS], current_block->position[B_AXIS], - current_block->position[C_AXIS], current_block->position[E_AXIS] - ); + _set_position(current_block->position); planner.discard_current_block(); // Try to get a new block @@ -1698,7 +1694,7 @@ uint32_t Stepper::stepper_block_phase_isr() { #endif #define X_MOVE_TEST ( S_(1) != S_(2) || (S_(1) > 0 && D_(1) X_CMP D_(2)) ) #else - #define X_MOVE_TEST !!current_block->steps[A_AXIS] + #define X_MOVE_TEST !!current_block->steps.a #endif #if CORE_IS_XY || CORE_IS_YZ @@ -1716,7 +1712,7 @@ uint32_t Stepper::stepper_block_phase_isr() { #endif #define Y_MOVE_TEST ( S_(1) != S_(2) || (S_(1) > 0 && D_(1) Y_CMP D_(2)) ) #else - #define Y_MOVE_TEST !!current_block->steps[B_AXIS] + #define Y_MOVE_TEST !!current_block->steps.b #endif #if CORE_IS_XZ || CORE_IS_YZ @@ -1734,17 +1730,17 @@ uint32_t Stepper::stepper_block_phase_isr() { #endif #define Z_MOVE_TEST ( S_(1) != S_(2) || (S_(1) > 0 && D_(1) Z_CMP D_(2)) ) #else - #define Z_MOVE_TEST !!current_block->steps[C_AXIS] + #define Z_MOVE_TEST !!current_block->steps.c #endif uint8_t axis_bits = 0; if (X_MOVE_TEST) SBI(axis_bits, A_AXIS); if (Y_MOVE_TEST) SBI(axis_bits, B_AXIS); if (Z_MOVE_TEST) SBI(axis_bits, C_AXIS); - //if (!!current_block->steps[E_AXIS]) SBI(axis_bits, E_AXIS); - //if (!!current_block->steps[A_AXIS]) SBI(axis_bits, X_HEAD); - //if (!!current_block->steps[B_AXIS]) SBI(axis_bits, Y_HEAD); - //if (!!current_block->steps[C_AXIS]) SBI(axis_bits, Z_HEAD); + //if (!!current_block->steps.e) SBI(axis_bits, E_AXIS); + //if (!!current_block->steps.a) SBI(axis_bits, X_HEAD); + //if (!!current_block->steps.b) SBI(axis_bits, Y_HEAD); + //if (!!current_block->steps.c) SBI(axis_bits, Z_HEAD); axis_did_move = axis_bits; // No acceleration / deceleration time elapsed so far @@ -1767,15 +1763,10 @@ uint32_t Stepper::stepper_block_phase_isr() { step_event_count = current_block->step_event_count << oversampling; // Initialize Bresenham delta errors to 1/2 - delta_error[X_AXIS] = delta_error[Y_AXIS] = delta_error[Z_AXIS] = delta_error[E_AXIS] = -int32_t(step_event_count); + delta_error = -int32_t(step_event_count); - // Calculate Bresenham dividends - advance_dividend[X_AXIS] = current_block->steps[X_AXIS] << 1; - advance_dividend[Y_AXIS] = current_block->steps[Y_AXIS] << 1; - advance_dividend[Z_AXIS] = current_block->steps[Z_AXIS] << 1; - advance_dividend[E_AXIS] = current_block->steps[E_AXIS] << 1; - - // Calculate Bresenham divisor + // Calculate Bresenham dividends and divisors + advance_dividend = current_block->steps << 1; advance_divisor = step_event_count << 1; // No step events completed so far @@ -1840,7 +1831,7 @@ uint32_t Stepper::stepper_block_phase_isr() { // If delayed Z enable, enable it now. This option will severely interfere with // timing between pulses when chaining motion between blocks, and it could lead // to lost steps in both X and Y axis, so avoid using it unless strictly necessary!! - if (current_block->steps[Z_AXIS]) enable_Z(); + if (current_block->steps.z) enable_Z(); #endif // Mark the time_nominal as not calculated yet @@ -2195,26 +2186,18 @@ void Stepper::_set_position(const int32_t &a, const int32_t &b, const int32_t &c #if CORE_IS_XY // corexy positioning // these equations follow the form of the dA and dB equations on http://www.corexy.com/theory.html - count_position[A_AXIS] = a + b; - count_position[B_AXIS] = CORESIGN(a - b); - count_position[Z_AXIS] = c; + count_position.set(a + b, CORESIGN(a - b), c); #elif CORE_IS_XZ // corexz planning - count_position[A_AXIS] = a + c; - count_position[Y_AXIS] = b; - count_position[C_AXIS] = CORESIGN(a - c); + count_position.set(a + c, b, CORESIGN(a - c)); #elif CORE_IS_YZ // coreyz planning - count_position[X_AXIS] = a; - count_position[B_AXIS] = b + c; - count_position[C_AXIS] = CORESIGN(b - c); + count_position.set(a, b + c, CORESIGN(b - c)); #else // default non-h-bot planning - count_position[X_AXIS] = a; - count_position[Y_AXIS] = b; - count_position[Z_AXIS] = c; + count_position.set(a, b, c); #endif - count_position[E_AXIS] = e; + count_position.e = e; } /** @@ -2290,36 +2273,22 @@ void Stepper::report_positions() { if (was_enabled) DISABLE_STEPPER_DRIVER_INTERRUPT(); #endif - const int32_t xpos = count_position[X_AXIS], - ypos = count_position[Y_AXIS], - zpos = count_position[Z_AXIS]; + const xyz_long_t pos = count_position; #ifdef __AVR__ if (was_enabled) ENABLE_STEPPER_DRIVER_INTERRUPT(); #endif #if CORE_IS_XY || CORE_IS_XZ || ENABLED(DELTA) || IS_SCARA - SERIAL_ECHOPGM(MSG_COUNT_A); - #else - SERIAL_ECHOPGM(MSG_COUNT_X); - #endif - SERIAL_ECHO(xpos); - - #if CORE_IS_XY || CORE_IS_YZ || ENABLED(DELTA) || IS_SCARA - SERIAL_ECHOPGM(" B:"); + SERIAL_ECHOPAIR(MSG_COUNT_A, pos.x, " B:", pos.y); #else - SERIAL_ECHOPGM(" Y:"); + SERIAL_ECHOPAIR(MSG_COUNT_X, pos.x, " Y:", pos.y); #endif - SERIAL_ECHO(ypos); - #if CORE_IS_XZ || CORE_IS_YZ || ENABLED(DELTA) - SERIAL_ECHOPGM(" C:"); + SERIAL_ECHOLNPAIR(" C:", pos.z); #else - SERIAL_ECHOPGM(" Z:"); + SERIAL_ECHOLNPAIR(" Z:", pos.z); #endif - SERIAL_ECHO(zpos); - - SERIAL_EOL(); } #if ENABLED(BABYSTEPPING) diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index d098dd448..839a9a9d5 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -278,9 +278,9 @@ class Stepper { #endif // Delta error variables for the Bresenham line tracer - static int32_t delta_error[XYZE]; - static uint32_t advance_dividend[XYZE], - advance_divisor, + static xyze_long_t delta_error; + static xyze_ulong_t advance_dividend; + static uint32_t advance_divisor, step_events_completed, // The number of step events executed in the current block accelerate_until, // The point from where we need to stop acceleration decelerate_after, // The point from where we need to start decelerating @@ -320,17 +320,17 @@ class Stepper { // // Exact steps at which an endstop was triggered // - static volatile int32_t endstops_trigsteps[XYZ]; + static xyz_long_t endstops_trigsteps; // // Positions of stepper motors, in step units // - static volatile int32_t count_position[NUM_AXIS]; + static xyze_long_t count_position; // // Current direction of stepper motors (+1 or -1) // - static int8_t count_direction[NUM_AXIS]; + static xyze_int8_t count_direction; public: @@ -382,13 +382,11 @@ class Stepper { // The extruder associated to the last movement FORCE_INLINE static uint8_t movement_extruder() { - return - #if ENABLED(MIXING_EXTRUDER) || EXTRUDERS < 2 - 0 - #else - last_moved_extruder + return (0 + #if EXTRUDERS > 1 && DISABLED(MIXING_EXTRUDER) + + last_moved_extruder #endif - ; + ); } // Handle a triggered endstop @@ -443,8 +441,9 @@ class Stepper { _set_position(a, b, c, e); if (was_enabled) ENABLE_STEPPER_DRIVER_INTERRUPT(); } + static inline void set_position(const xyze_long_t &abce) { set_position(abce.a, abce.b, abce.c, abce.e); } - static inline void set_position(const AxisEnum a, const int32_t &v) { + static inline void set_axis_position(const AxisEnum a, const int32_t &v) { planner.synchronize(); #ifdef __AVR__ @@ -469,6 +468,7 @@ class Stepper { // Set the current position in steps static void _set_position(const int32_t &a, const int32_t &b, const int32_t &c, const int32_t &e); + FORCE_INLINE static void _set_position(const abce_long_t &spos) { _set_position(spos.a, spos.b, spos.c, spos.e); } FORCE_INLINE static uint32_t calc_timer_interval(uint32_t step_rate, uint8_t scale, uint8_t* loops) { uint32_t timer; diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index 6178a7ce5..cd6d21bae 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -133,8 +133,8 @@ #endif // SWITCHING_NOZZLE -inline void _line_to_current(const AxisEnum fr_axis, const float fscale=1.0f) { - planner.buffer_line(current_position, planner.settings.max_feedrate_mm_s[fr_axis] * fscale, active_extruder); +inline void _line_to_current(const AxisEnum fr_axis, const float fscale=1) { + line_to_current_position(planner.settings.max_feedrate_mm_s[fr_axis] * fscale); } inline void slow_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0.5f); } inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis); } @@ -150,11 +150,11 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a inline void magnetic_parking_extruder_tool_change(const uint8_t new_tool) { - const float oldx = current_position[X_AXIS], + const float oldx = current_position.x, grabpos = mpe_settings.parking_xpos[new_tool] + (new_tool ? mpe_settings.grab_distance : -mpe_settings.grab_distance), offsetcompensation = (0 #if HAS_HOTEND_OFFSET - + hotend_offset[X_AXIS][active_extruder] * mpe_settings.compensation_factor + + hotend_offset[active_extruder].x * mpe_settings.compensation_factor #endif ); @@ -174,7 +174,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a // STEP 1 - current_position[X_AXIS] = mpe_settings.parking_xpos[new_tool] + offsetcompensation; + current_position.x = mpe_settings.parking_xpos[new_tool] + offsetcompensation; if (DEBUGGING(LEVELING)) { DEBUG_ECHOPAIR("(1) Move extruder ", int(new_tool)); @@ -186,7 +186,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a // STEP 2 - current_position[X_AXIS] = grabpos + offsetcompensation; + current_position.x = grabpos + offsetcompensation; if (DEBUGGING(LEVELING)) { DEBUG_ECHOPAIR("(2) Couple extruder ", int(new_tool)); @@ -201,7 +201,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a // STEP 3 - current_position[X_AXIS] = mpe_settings.parking_xpos[new_tool] + offsetcompensation; + current_position.x = mpe_settings.parking_xpos[new_tool] + offsetcompensation; if (DEBUGGING(LEVELING)) { DEBUG_ECHOPAIR("(3) Move extruder ", int(new_tool)); DEBUG_POS(" back to new extruder ParkPos", current_position); @@ -212,7 +212,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a // STEP 4 - current_position[X_AXIS] = mpe_settings.parking_xpos[active_extruder] + (active_extruder == 0 ? MPE_TRAVEL_DISTANCE : -MPE_TRAVEL_DISTANCE) + offsetcompensation; + current_position.x = mpe_settings.parking_xpos[active_extruder] + (active_extruder == 0 ? MPE_TRAVEL_DISTANCE : -MPE_TRAVEL_DISTANCE) + offsetcompensation; if (DEBUGGING(LEVELING)) { DEBUG_ECHOPAIR("(4) Move extruder ", int(new_tool)); DEBUG_POS(" close to old extruder ParkPos", current_position); @@ -223,7 +223,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a // STEP 5 - current_position[X_AXIS] = mpe_settings.parking_xpos[active_extruder] + offsetcompensation; + current_position.x = mpe_settings.parking_xpos[active_extruder] + offsetcompensation; if (DEBUGGING(LEVELING)) { DEBUG_ECHOPAIR("(5) Park extruder ", int(new_tool)); @@ -235,7 +235,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a // STEP 6 - current_position[X_AXIS] = oldx; + current_position.x = oldx; if (DEBUGGING(LEVELING)) { DEBUG_ECHOPAIR("(6) Move extruder ", int(new_tool)); @@ -275,12 +275,12 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a constexpr float parkingposx[] = PARKING_EXTRUDER_PARKING_X; #if HAS_HOTEND_OFFSET - const float x_offset = hotend_offset[X_AXIS][active_extruder]; + const float x_offset = hotend_offset[active_extruder].x; #else constexpr float x_offset = 0; #endif - const float midpos = (parkingposx[0] + parkingposx[1]) * 0.5 + x_offset, + const float midpos = (parkingposx[0] + parkingposx[1]) * 0.5f + x_offset, grabpos = parkingposx[new_tool] + (new_tool ? PARKING_EXTRUDER_GRAB_DISTANCE : -(PARKING_EXTRUDER_GRAB_DISTANCE)) + x_offset; /** @@ -296,7 +296,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a if (DEBUGGING(LEVELING)) DEBUG_POS("Start PE Tool-Change", current_position); - current_position[X_AXIS] = parkingposx[active_extruder] + x_offset; + current_position.x = parkingposx[active_extruder] + x_offset; if (DEBUGGING(LEVELING)) { DEBUG_ECHOLNPAIR("(1) Park extruder ", int(active_extruder)); DEBUG_POS("Moving ParkPos", current_position); @@ -311,7 +311,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a // STEP 3 - current_position[X_AXIS] += active_extruder ? -10 : 10; // move 10mm away from parked extruder + current_position.x += active_extruder ? -10 : 10; // move 10mm away from parked extruder if (DEBUGGING(LEVELING)) { DEBUG_ECHOLNPGM("(3) Move near new extruder"); DEBUG_POS("Move away from parked extruder", current_position); @@ -329,10 +329,10 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a // STEP 5 - current_position[X_AXIS] = grabpos + (new_tool ? -10 : 10); + current_position.x = grabpos + (new_tool ? -10 : 10); fast_line_to_current(X_AXIS); - current_position[X_AXIS] = grabpos; + current_position.x = grabpos; if (DEBUGGING(LEVELING)) { planner.synchronize(); DEBUG_POS("(5) Unpark extruder", current_position); @@ -341,9 +341,9 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a // STEP 6 - current_position[X_AXIS] = midpos + current_position.x = midpos #if HAS_HOTEND_OFFSET - - hotend_offset[X_AXIS][new_tool] + - hotend_offset[new_tool].x #endif ; if (DEBUGGING(LEVELING)) { @@ -388,14 +388,14 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a if (DEBUGGING(LEVELING)) DEBUG_POS("Start ST Tool-Change", current_position); - current_position[X_AXIS] = placexpos; + current_position.x = placexpos; if (DEBUGGING(LEVELING)) { DEBUG_ECHOLNPAIR("(1) Place old tool ", int(active_extruder)); DEBUG_POS("Move X SwitchPos", current_position); } fast_line_to_current(X_AXIS); - current_position[Y_AXIS] = SWITCHING_TOOLHEAD_Y_POS - (SWITCHING_TOOLHEAD_Y_SECURITY); + current_position.y = SWITCHING_TOOLHEAD_Y_POS - (SWITCHING_TOOLHEAD_Y_SECURITY); if (DEBUGGING(LEVELING)) { planner.synchronize(); DEBUG_POS("Move Y SwitchPos + Security", current_position); @@ -409,7 +409,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a MOVE_SERVO(SWITCHING_TOOLHEAD_SERVO_NR, angles[1]); safe_delay(500); - current_position[Y_AXIS] = SWITCHING_TOOLHEAD_Y_POS; + current_position.y = SWITCHING_TOOLHEAD_Y_POS; if (DEBUGGING(LEVELING)) DEBUG_POS("Move Y SwitchPos", current_position); slow_line_to_current(Y_AXIS); @@ -417,13 +417,13 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a planner.synchronize(); safe_delay(200); - current_position[Y_AXIS] -= SWITCHING_TOOLHEAD_Y_CLEAR; + current_position.y -= SWITCHING_TOOLHEAD_Y_CLEAR; if (DEBUGGING(LEVELING)) DEBUG_POS("Move back Y clear", current_position); fast_line_to_current(Y_AXIS); // move away from docked toolhead // 3. Move to the new toolhead - current_position[X_AXIS] = grabxpos; + current_position.x = grabxpos; if (DEBUGGING(LEVELING)) { planner.synchronize(); DEBUG_ECHOLNPGM("(3) Move to new toolhead position"); @@ -431,7 +431,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a } fast_line_to_current(X_AXIS); - current_position[Y_AXIS] = SWITCHING_TOOLHEAD_Y_POS - (SWITCHING_TOOLHEAD_Y_SECURITY); + current_position.y = SWITCHING_TOOLHEAD_Y_POS - (SWITCHING_TOOLHEAD_Y_SECURITY); if (DEBUGGING(LEVELING)) { planner.synchronize(); DEBUG_POS("Move Y SwitchPos + Security", current_position); @@ -440,7 +440,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a // 4. Grab and lock the new toolhead - current_position[Y_AXIS] = SWITCHING_TOOLHEAD_Y_POS; + current_position.y = SWITCHING_TOOLHEAD_Y_POS; if (DEBUGGING(LEVELING)) { planner.synchronize(); DEBUG_ECHOLNPGM("(4) Grab and lock new toolhead"); @@ -454,7 +454,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a MOVE_SERVO(SWITCHING_TOOLHEAD_SERVO_NR, angles[0]); safe_delay(500); - current_position[Y_AXIS] -= SWITCHING_TOOLHEAD_Y_CLEAR; + current_position.y -= SWITCHING_TOOLHEAD_Y_CLEAR; if (DEBUGGING(LEVELING)) DEBUG_POS("Move back Y clear", current_position); fast_line_to_current(Y_AXIS); // Move away from docked toolhead planner.synchronize(); // Always sync the final move @@ -486,33 +486,33 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a // 1. Move to switch position current toolhead - current_position[Y_AXIS] = SWITCHING_TOOLHEAD_Y_POS + SWITCHING_TOOLHEAD_Y_CLEAR; + current_position.y = SWITCHING_TOOLHEAD_Y_POS + SWITCHING_TOOLHEAD_Y_CLEAR; if (DEBUGGING(LEVELING)) { SERIAL_ECHOLNPAIR("(1) Place old tool ", int(active_extruder)); DEBUG_POS("Move Y SwitchPos + Security", current_position); } fast_line_to_current(Y_AXIS); - current_position[X_AXIS] = placexclear; + current_position.x = placexclear; if (DEBUGGING(LEVELING)) { planner.synchronize(); DEBUG_POS("Move X SwitchPos + Security", current_position); } fast_line_to_current(X_AXIS); - current_position[Y_AXIS] = SWITCHING_TOOLHEAD_Y_POS; + current_position.y = SWITCHING_TOOLHEAD_Y_POS; if (DEBUGGING(LEVELING)) { planner.synchronize(); DEBUG_POS("Move Y SwitchPos", current_position); } fast_line_to_current(Y_AXIS); - current_position[X_AXIS] = placexpos; + current_position.x = placexpos; if (DEBUGGING(LEVELING)) { planner.synchronize(); DEBUG_POS("Move X SwitchPos", current_position); } - planner.buffer_line(current_position, (planner.settings.max_feedrate_mm_s[X_AXIS] * 0.25), active_extruder); + line_to_current_position(planner.settings.max_feedrate_mm_s[X_AXIS] * 0.25f); // 2. Release and place toolhead in the dock @@ -521,16 +521,16 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a DEBUG_ECHOLNPGM("(2) Release and Place Toolhead"); } - current_position[Y_AXIS] = SWITCHING_TOOLHEAD_Y_POS + SWITCHING_TOOLHEAD_Y_RELEASE; + current_position.y = SWITCHING_TOOLHEAD_Y_POS + SWITCHING_TOOLHEAD_Y_RELEASE; if (DEBUGGING(LEVELING)) DEBUG_POS("Move Y SwitchPos + Release", current_position); - planner.buffer_line(current_position, (planner.settings.max_feedrate_mm_s[Y_AXIS] * 0.1), active_extruder); + line_to_current_position(planner.settings.max_feedrate_mm_s[Y_AXIS] * 0.1f); - current_position[Y_AXIS] = SWITCHING_TOOLHEAD_Y_POS + SWITCHING_TOOLHEAD_Y_SECURITY; + current_position.y = SWITCHING_TOOLHEAD_Y_POS + SWITCHING_TOOLHEAD_Y_SECURITY; if (DEBUGGING(LEVELING)) { planner.synchronize(); DEBUG_POS("Move Y SwitchPos + Security", current_position); } - planner.buffer_line(current_position, (planner.settings.max_feedrate_mm_s[Y_AXIS]), active_extruder); + line_to_current_position(planner.settings.max_feedrate_mm_s[Y_AXIS]); // 3. Move to new toolhead position @@ -539,7 +539,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a DEBUG_ECHOLNPGM("(3) Move to new toolhead position"); } - current_position[X_AXIS] = grabxpos; + current_position.x = grabxpos; if (DEBUGGING(LEVELING)) DEBUG_POS("Move to new toolhead X", current_position); fast_line_to_current(X_AXIS); @@ -550,11 +550,11 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a DEBUG_ECHOLNPGM("(4) Grab new toolhead, move to security position"); } - current_position[Y_AXIS] = SWITCHING_TOOLHEAD_Y_POS + SWITCHING_TOOLHEAD_Y_RELEASE; + current_position.y = SWITCHING_TOOLHEAD_Y_POS + SWITCHING_TOOLHEAD_Y_RELEASE; if (DEBUGGING(LEVELING)) DEBUG_POS("Move Y SwitchPos + Release", current_position); - planner.buffer_line(current_position, (planner.settings.max_feedrate_mm_s[Y_AXIS]), active_extruder); + line_to_current_position(planner.settings.max_feedrate_mm_s[Y_AXIS]); - current_position[Y_AXIS] = SWITCHING_TOOLHEAD_Y_POS; + current_position.y = SWITCHING_TOOLHEAD_Y_POS; if (DEBUGGING(LEVELING)) { planner.synchronize(); DEBUG_POS("Move Y SwitchPos", current_position); @@ -563,11 +563,11 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a #if ENABLED(PRIME_BEFORE_REMOVE) && (SWITCHING_TOOLHEAD_PRIME_MM || SWITCHING_TOOLHEAD_RETRACT_MM) #if SWITCHING_TOOLHEAD_PRIME_MM - current_position[E_AXIS] += SWITCHING_TOOLHEAD_PRIME_MM; + current_position.e += SWITCHING_TOOLHEAD_PRIME_MM; planner.buffer_line(current_position, MMM_TO_MMS(SWITCHING_TOOLHEAD_PRIME_FEEDRATE), new_tool); #endif #if SWITCHING_TOOLHEAD_RETRACT_MM - current_position[E_AXIS] -= SWITCHING_TOOLHEAD_RETRACT_MM; + current_position.e -= SWITCHING_TOOLHEAD_RETRACT_MM; planner.buffer_line(current_position, MMM_TO_MMS(SWITCHING_TOOLHEAD_RETRACT_FEEDRATE), new_tool); #endif #else @@ -575,13 +575,13 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a safe_delay(100); // Give switch time to settle #endif - current_position[X_AXIS] = grabxclear; + current_position.x = grabxclear; if (DEBUGGING(LEVELING)) DEBUG_POS("Move to new toolhead X + Security", current_position); _line_to_current(X_AXIS, 0.1f); planner.synchronize(); safe_delay(100); // Give switch time to settle - current_position[Y_AXIS] += SWITCHING_TOOLHEAD_Y_CLEAR; + current_position.y += SWITCHING_TOOLHEAD_Y_CLEAR; if (DEBUGGING(LEVELING)) DEBUG_POS("Move back Y clear", current_position); fast_line_to_current(Y_AXIS); // move away from docked toolhead planner.synchronize(); // Always sync last tool-change move @@ -601,6 +601,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a constexpr float toolheadposx[] = SWITCHING_TOOLHEAD_X_POS; const float placexpos = toolheadposx[active_extruder], grabxpos = toolheadposx[new_tool]; + const xyz_pos_t &hoffs = hotend_offset[active_extruder]; /** * 1. Raise Z-Axis to give enough clearance @@ -618,7 +619,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a // 1. Raise Z-Axis to give enough clearance - current_position[Z_AXIS] += SWITCHING_TOOLHEAD_Z_HOP; + current_position.z += SWITCHING_TOOLHEAD_Z_HOP; if (DEBUGGING(LEVELING)) DEBUG_POS("(1) Raise Z-Axis ", current_position); fast_line_to_current(Z_AXIS); @@ -629,8 +630,8 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a SERIAL_ECHOLNPAIR("(2) Move near active extruder parking", active_extruder); DEBUG_POS("Moving ParkPos", current_position); } - current_position[X_AXIS] = hotend_offset[X_AXIS][active_extruder] + placexpos; - current_position[Y_AXIS] = hotend_offset[Y_AXIS][active_extruder] + SWITCHING_TOOLHEAD_Y_POS + SWITCHING_TOOLHEAD_Y_CLEAR; + current_position.set(hoffs.x + placexpos, + hoffs.y + SWITCHING_TOOLHEAD_Y_POS + SWITCHING_TOOLHEAD_Y_CLEAR); fast_line_to_current(X_AXIS); // 3. Move gently to park position of active extruder @@ -641,7 +642,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a DEBUG_POS("Moving ParkPos", current_position); } - current_position[Y_AXIS] -= SWITCHING_TOOLHEAD_Y_CLEAR; + current_position.y -= SWITCHING_TOOLHEAD_Y_CLEAR; slow_line_to_current(Y_AXIS); // 4. Disengage magnetic field, wait for delay @@ -657,16 +658,15 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a DEBUG_POS("Moving ParkPos", current_position); } - current_position[Y_AXIS] += SWITCHING_TOOLHEAD_Y_CLEAR; + current_position.y += SWITCHING_TOOLHEAD_Y_CLEAR; slow_line_to_current(Y_AXIS); - - current_position[X_AXIS] = hotend_offset[X_AXIS][active_extruder] + grabxpos; - current_position[Y_AXIS] = hotend_offset[Y_AXIS][active_extruder] + SWITCHING_TOOLHEAD_Y_POS + SWITCHING_TOOLHEAD_Y_CLEAR; + current_position.set(hoffs.x + grabxpos, + hoffs.y + SWITCHING_TOOLHEAD_Y_POS + SWITCHING_TOOLHEAD_Y_CLEAR); fast_line_to_current(X_AXIS); // 6. Move gently to park position of new extruder - current_position[Y_AXIS] -= SWITCHING_TOOLHEAD_Y_CLEAR; + current_position.y -= SWITCHING_TOOLHEAD_Y_CLEAR; if (DEBUGGING(LEVELING)) { planner.synchronize(); DEBUG_ECHOLNPGM("(6) Move near new extruder"); @@ -681,7 +681,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a // 8. Unpark extruder - current_position[Y_AXIS] += SWITCHING_TOOLHEAD_Y_CLEAR; + current_position.y += SWITCHING_TOOLHEAD_Y_CLEAR; if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("(8) Unpark extruder"); slow_line_to_current(X_AXIS); planner.synchronize(); // Always sync the final move @@ -689,7 +689,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a // 9. Apply Z hotend offset to current position if (DEBUGGING(LEVELING)) DEBUG_POS("(9) Applying Z-offset", current_position); - current_position[Z_AXIS] += hotend_offset[Z_AXIS][active_extruder] - hotend_offset[Z_AXIS][new_tool]; + current_position.z += hoffs.z - hotend_offset[new_tool].z; if (DEBUGGING(LEVELING)) DEBUG_POS("EMST Tool-Change done.", current_position); } @@ -719,14 +719,15 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a const float xhome = x_home_pos(active_extruder); if (dual_x_carriage_mode == DXC_AUTO_PARK_MODE - && IsRunning() - && (delayed_move_time || current_position[X_AXIS] != xhome) && ! no_move + && IsRunning() && !no_move + && (delayed_move_time || current_position.x != xhome) ) { if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("MoveX to ", xhome); // Park old head - planner.buffer_line(xhome, current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], planner.settings.max_feedrate_mm_s[X_AXIS], active_extruder); + current_position.x = xhome; + line_to_current_position(planner.settings.max_feedrate_mm_s[X_AXIS]); planner.synchronize(); } @@ -741,13 +742,13 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a switch (dual_x_carriage_mode) { case DXC_FULL_CONTROL_MODE: // New current position is the position of the activated extruder - current_position[X_AXIS] = inactive_extruder_x_pos; + current_position.x = inactive_extruder_x_pos; // Save the inactive extruder's position (from the old current_position) - inactive_extruder_x_pos = destination[X_AXIS]; + inactive_extruder_x_pos = destination.x; break; case DXC_AUTO_PARK_MODE: // record current raised toolhead position for use by unpark - COPY(raised_parked_position, current_position); + raised_parked_position = current_position; active_extruder_parked = true; delayed_move_time = 0; break; @@ -852,7 +853,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { #if ENABLED(ADVANCED_PAUSE_FEATURE) do_pause_e_move(-toolchange_settings.swap_length, MMM_TO_MMS(toolchange_settings.retract_speed)); #else - current_position[E_AXIS] -= toolchange_settings.swap_length / planner.e_factor[old_tool]; + current_position.e -= toolchange_settings.swap_length / planner.e_factor[old_tool]; planner.buffer_line(current_position, MMM_TO_MMS(toolchange_settings.retract_speed), old_tool); planner.synchronize(); #endif @@ -886,19 +887,18 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { #endif #endif - set_destination_from_current(); + destination = current_position; #if DISABLED(SWITCHING_NOZZLE) if (can_move_away) { // Do a small lift to avoid the workpiece in the move back (below) - current_position[Z_AXIS] += toolchange_settings.z_raise; + current_position.z += toolchange_settings.z_raise; #if HAS_SOFTWARE_ENDSTOPS - NOMORE(current_position[Z_AXIS], soft_endstop[Z_AXIS].max); + NOMORE(current_position.z, soft_endstop.max.z); #endif fast_line_to_current(Z_AXIS); #if ENABLED(TOOLCHANGE_PARK) - current_position[X_AXIS] = toolchange_settings.change_point.x; - current_position[Y_AXIS] = toolchange_settings.change_point.y; + current_position = toolchange_settings.change_point; #endif planner.buffer_line(current_position, feedrate_mm_s, old_tool); planner.synchronize(); @@ -906,15 +906,12 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { #endif #if HAS_HOTEND_OFFSET + xyz_pos_t diff = hotend_offset[new_tool]; #if ENABLED(DUAL_X_CARRIAGE) - constexpr float xdiff = 0; - #else - const float xdiff = hotend_offset[X_AXIS][new_tool] - hotend_offset[X_AXIS][old_tool]; + diff.x = 0; #endif - const float ydiff = hotend_offset[Y_AXIS][new_tool] - hotend_offset[Y_AXIS][old_tool], - zdiff = hotend_offset[Z_AXIS][new_tool] - hotend_offset[Z_AXIS][old_tool]; #else - constexpr float xdiff = 0, ydiff = 0, zdiff = 0; + constexpr xyz_pos_t diff{0}; #endif #if ENABLED(DUAL_X_CARRIAGE) @@ -932,30 +929,28 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { #elif ENABLED(SWITCHING_NOZZLE) && !SWITCHING_NOZZLE_TWO_SERVOS // Switching Nozzle (single servo) // Raise by a configured distance to avoid workpiece, except with // SWITCHING_NOZZLE_TWO_SERVOS, as both nozzles will lift instead. - current_position[Z_AXIS] += _MAX(-zdiff, 0.0) + toolchange_settings.z_raise; + current_position.z += _MAX(-zdiff, 0.0) + toolchange_settings.z_raise; #if HAS_SOFTWARE_ENDSTOPS - NOMORE(current_position[Z_AXIS], soft_endstop[Z_AXIS].max); + NOMORE(current_position.z, soft_endstop.max.z); #endif if (!no_move) fast_line_to_current(Z_AXIS); move_nozzle_servo(new_tool); #endif - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Offset Tool XY by { ", xdiff, ", ", ydiff, ", ", zdiff, " }"); - - // The newly-selected extruder XY is actually at... - current_position[X_AXIS] += xdiff; - current_position[Y_AXIS] += ydiff; - current_position[Z_AXIS] += zdiff; + #if DISABLED(DUAL_X_CARRIAGE) + active_extruder = new_tool; // Set the new active extruder + #endif - // Set the new active extruder if not already done in tool specific function above - active_extruder = new_tool; + // The newly-selected extruder XYZ is actually at... + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Offset Tool XY by { ", diff.x, ", ", diff.y, ", ", diff.z, " }"); + current_position += diff; // Tell the planner the new "current position" sync_plan_position(); #if ENABLED(DELTA) //LOOP_XYZ(i) update_software_endstops(i); // or modify the constrain function - const bool safe_to_move = current_position[Z_AXIS] < delta_clip_start_height - 1; + const bool safe_to_move = current_position.z < delta_clip_start_height - 1; #else constexpr bool safe_to_move = true; #endif @@ -985,21 +980,21 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { do_pause_e_move(toolchange_settings.swap_length, MMM_TO_MMS(toolchange_settings.prime_speed)); do_pause_e_move(toolchange_settings.extra_prime, ADVANCED_PAUSE_PURGE_FEEDRATE); #else - current_position[E_AXIS] += toolchange_settings.swap_length / planner.e_factor[new_tool]; + current_position.e += toolchange_settings.swap_length / planner.e_factor[new_tool]; planner.buffer_line(current_position, MMM_TO_MMS(toolchange_settings.prime_speed), new_tool); - current_position[E_AXIS] += toolchange_settings.extra_prime / planner.e_factor[new_tool]; + current_position.e += toolchange_settings.extra_prime / planner.e_factor[new_tool]; planner.buffer_line(current_position, MMM_TO_MMS(toolchange_settings.prime_speed * 0.2f), new_tool); #endif planner.synchronize(); - planner.set_e_position_mm((destination[E_AXIS] = current_position[E_AXIS] = current_position[E_AXIS] - (TOOLCHANGE_FIL_EXTRA_PRIME))); + planner.set_e_position_mm((destination.e = current_position.e = current_position.e - (TOOLCHANGE_FIL_EXTRA_PRIME))); } #endif // Prevent a move outside physical bounds #if ENABLED(MAGNETIC_SWITCHING_TOOLHEAD) // If the original position is within tool store area, go to X origin at once - if (destination[Y_AXIS] < SWITCHING_TOOLHEAD_Y_POS + SWITCHING_TOOLHEAD_Y_CLEAR) { - current_position[X_AXIS] = 0; + if (destination.y < SWITCHING_TOOLHEAD_Y_POS + SWITCHING_TOOLHEAD_Y_CLEAR) { + current_position.x = 0; planner.buffer_line(current_position, planner.settings.max_feedrate_mm_s[X_AXIS], new_tool); planner.synchronize(); } @@ -1012,7 +1007,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { #if ENABLED(TOOLCHANGE_NO_RETURN) // Just move back down if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Move back Z only"); - do_blocking_move_to_z(destination[Z_AXIS], planner.settings.max_feedrate_mm_s[Z_AXIS]); + do_blocking_move_to_z(destination.z, planner.settings.max_feedrate_mm_s[Z_AXIS]); #else // Move back to the original (or adjusted) position if (DEBUGGING(LEVELING)) DEBUG_POS("Move back", destination); @@ -1028,7 +1023,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { #if ENABLED(SWITCHING_NOZZLE) else { // Move back down. (Including when the new tool is higher.) - do_blocking_move_to_z(destination[Z_AXIS], planner.settings.max_feedrate_mm_s[Z_AXIS]); + do_blocking_move_to_z(destination.z, planner.settings.max_feedrate_mm_s[Z_AXIS]); } #endif diff --git a/Marlin/src/module/tool_change.h b/Marlin/src/module/tool_change.h index 42b96e2c6..613cb1612 100644 --- a/Marlin/src/module/tool_change.h +++ b/Marlin/src/module/tool_change.h @@ -22,6 +22,7 @@ #pragma once #include "../inc/MarlinConfigPre.h" +#include "../core/types.h" #if EXTRUDERS > 1 @@ -31,7 +32,7 @@ int16_t prime_speed, retract_speed; #endif #if ENABLED(TOOLCHANGE_PARK) - struct { float x, y; } change_point; + xy_pos_t change_point; #endif float z_raise; } toolchange_settings_t; diff --git a/config/default/Configuration_adv.h b/config/default/Configuration_adv.h index 9f0217a80..3bedfab70 100644 --- a/config/default/Configuration_adv.h +++ b/config/default/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/3DFabXYZ/Migbot/Configuration_adv.h b/config/examples/3DFabXYZ/Migbot/Configuration_adv.h index c93807b61..47a758e90 100644 --- a/config/examples/3DFabXYZ/Migbot/Configuration_adv.h +++ b/config/examples/3DFabXYZ/Migbot/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/ADIMLab/Gantry v1/Configuration_adv.h b/config/examples/ADIMLab/Gantry v1/Configuration_adv.h index a41fa9e9b..55b6c998d 100644 --- a/config/examples/ADIMLab/Gantry v1/Configuration_adv.h +++ b/config/examples/ADIMLab/Gantry v1/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/ADIMLab/Gantry v2/Configuration_adv.h b/config/examples/ADIMLab/Gantry v2/Configuration_adv.h index 9d69ca35f..3239a3432 100644 --- a/config/examples/ADIMLab/Gantry v2/Configuration_adv.h +++ b/config/examples/ADIMLab/Gantry v2/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/AlephObjects/TAZ4/Configuration_adv.h b/config/examples/AlephObjects/TAZ4/Configuration_adv.h index d365fdcd4..9154af821 100644 --- a/config/examples/AlephObjects/TAZ4/Configuration_adv.h +++ b/config/examples/AlephObjects/TAZ4/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Alfawise/U20-bltouch/Configuration_adv.h b/config/examples/Alfawise/U20-bltouch/Configuration_adv.h index 8bf2c2beb..7685ea3ef 100644 --- a/config/examples/Alfawise/U20-bltouch/Configuration_adv.h +++ b/config/examples/Alfawise/U20-bltouch/Configuration_adv.h @@ -603,9 +603,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Alfawise/U20/Configuration_adv.h b/config/examples/Alfawise/U20/Configuration_adv.h index 56ac66671..8c1841c0d 100644 --- a/config/examples/Alfawise/U20/Configuration_adv.h +++ b/config/examples/Alfawise/U20/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/AliExpress/UM2pExt/Configuration_adv.h b/config/examples/AliExpress/UM2pExt/Configuration_adv.h index a48841652..02528e51c 100644 --- a/config/examples/AliExpress/UM2pExt/Configuration_adv.h +++ b/config/examples/AliExpress/UM2pExt/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Anet/A2/Configuration_adv.h b/config/examples/Anet/A2/Configuration_adv.h index 3bed49adf..e3b4ccb2a 100644 --- a/config/examples/Anet/A2/Configuration_adv.h +++ b/config/examples/Anet/A2/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Anet/A2plus/Configuration_adv.h b/config/examples/Anet/A2plus/Configuration_adv.h index 3bed49adf..e3b4ccb2a 100644 --- a/config/examples/Anet/A2plus/Configuration_adv.h +++ b/config/examples/Anet/A2plus/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Anet/A6/Configuration_adv.h b/config/examples/Anet/A6/Configuration_adv.h index 01d8e89e1..c0f6d138e 100644 --- a/config/examples/Anet/A6/Configuration_adv.h +++ b/config/examples/Anet/A6/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Anet/A8/Configuration_adv.h b/config/examples/Anet/A8/Configuration_adv.h index 605afc09f..194dff4f1 100644 --- a/config/examples/Anet/A8/Configuration_adv.h +++ b/config/examples/Anet/A8/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Anet/A8plus/Configuration_adv.h b/config/examples/Anet/A8plus/Configuration_adv.h index 3b759d3b3..771aadb12 100644 --- a/config/examples/Anet/A8plus/Configuration_adv.h +++ b/config/examples/Anet/A8plus/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Anet/E16/Configuration_adv.h b/config/examples/Anet/E16/Configuration_adv.h index c64d24c60..c891129c6 100644 --- a/config/examples/Anet/E16/Configuration_adv.h +++ b/config/examples/Anet/E16/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/AnyCubic/i3/Configuration_adv.h b/config/examples/AnyCubic/i3/Configuration_adv.h index 0e0349ebc..fb395cf5f 100644 --- a/config/examples/AnyCubic/i3/Configuration_adv.h +++ b/config/examples/AnyCubic/i3/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/ArmEd/Configuration_adv.h b/config/examples/ArmEd/Configuration_adv.h index 1ad055cb4..2d700565a 100644 --- a/config/examples/ArmEd/Configuration_adv.h +++ b/config/examples/ArmEd/Configuration_adv.h @@ -606,9 +606,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/BIBO/TouchX/cyclops/Configuration_adv.h b/config/examples/BIBO/TouchX/cyclops/Configuration_adv.h index 760915c3b..46009ee5c 100644 --- a/config/examples/BIBO/TouchX/cyclops/Configuration_adv.h +++ b/config/examples/BIBO/TouchX/cyclops/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/BIBO/TouchX/default/Configuration_adv.h b/config/examples/BIBO/TouchX/default/Configuration_adv.h index 5ce50d730..5bc675294 100644 --- a/config/examples/BIBO/TouchX/default/Configuration_adv.h +++ b/config/examples/BIBO/TouchX/default/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/BQ/Hephestos/Configuration_adv.h b/config/examples/BQ/Hephestos/Configuration_adv.h index 5561fd1e2..4370242cb 100644 --- a/config/examples/BQ/Hephestos/Configuration_adv.h +++ b/config/examples/BQ/Hephestos/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/BQ/Hephestos_2/Configuration_adv.h b/config/examples/BQ/Hephestos_2/Configuration_adv.h index 43ad192cc..4a3468ab2 100644 --- a/config/examples/BQ/Hephestos_2/Configuration_adv.h +++ b/config/examples/BQ/Hephestos_2/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/BQ/WITBOX/Configuration_adv.h b/config/examples/BQ/WITBOX/Configuration_adv.h index 5561fd1e2..4370242cb 100644 --- a/config/examples/BQ/WITBOX/Configuration_adv.h +++ b/config/examples/BQ/WITBOX/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Cartesio/Configuration_adv.h b/config/examples/Cartesio/Configuration_adv.h index 53cd20647..b80bdb448 100644 --- a/config/examples/Cartesio/Configuration_adv.h +++ b/config/examples/Cartesio/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Creality/CR-10/Configuration_adv.h b/config/examples/Creality/CR-10/Configuration_adv.h index 1131506e3..85087e95e 100644 --- a/config/examples/Creality/CR-10/Configuration_adv.h +++ b/config/examples/Creality/CR-10/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Creality/CR-10S/Configuration_adv.h b/config/examples/Creality/CR-10S/Configuration_adv.h index 0c968a812..96eb8d33e 100644 --- a/config/examples/Creality/CR-10S/Configuration_adv.h +++ b/config/examples/Creality/CR-10S/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Creality/CR-10_5S/Configuration_adv.h b/config/examples/Creality/CR-10_5S/Configuration_adv.h index ed9957a67..62c1f45bd 100644 --- a/config/examples/Creality/CR-10_5S/Configuration_adv.h +++ b/config/examples/Creality/CR-10_5S/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Creality/CR-10mini/Configuration_adv.h b/config/examples/Creality/CR-10mini/Configuration_adv.h index 11bfdca89..8901d9933 100644 --- a/config/examples/Creality/CR-10mini/Configuration_adv.h +++ b/config/examples/Creality/CR-10mini/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Creality/CR-20 Pro/Configuration_adv.h b/config/examples/Creality/CR-20 Pro/Configuration_adv.h index 8b2e7cc24..ca68194df 100644 --- a/config/examples/Creality/CR-20 Pro/Configuration_adv.h +++ b/config/examples/Creality/CR-20 Pro/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Creality/CR-20/Configuration_adv.h b/config/examples/Creality/CR-20/Configuration_adv.h index 6eda8d449..2a7523d2c 100644 --- a/config/examples/Creality/CR-20/Configuration_adv.h +++ b/config/examples/Creality/CR-20/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Creality/CR-8/Configuration_adv.h b/config/examples/Creality/CR-8/Configuration_adv.h index 987ffe6ab..2e590136e 100644 --- a/config/examples/Creality/CR-8/Configuration_adv.h +++ b/config/examples/Creality/CR-8/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Creality/Ender-2/Configuration_adv.h b/config/examples/Creality/Ender-2/Configuration_adv.h index 9fc48d4e8..f6faed858 100644 --- a/config/examples/Creality/Ender-2/Configuration_adv.h +++ b/config/examples/Creality/Ender-2/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Creality/Ender-3/Configuration_adv.h b/config/examples/Creality/Ender-3/Configuration_adv.h index 44d99596d..da3854d10 100644 --- a/config/examples/Creality/Ender-3/Configuration_adv.h +++ b/config/examples/Creality/Ender-3/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Creality/Ender-4/Configuration_adv.h b/config/examples/Creality/Ender-4/Configuration_adv.h index 112b55f85..f3e0b0750 100644 --- a/config/examples/Creality/Ender-4/Configuration_adv.h +++ b/config/examples/Creality/Ender-4/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Creality/Ender-5/Configuration_adv.h b/config/examples/Creality/Ender-5/Configuration_adv.h index 2ff116c69..ccf4773d1 100644 --- a/config/examples/Creality/Ender-5/Configuration_adv.h +++ b/config/examples/Creality/Ender-5/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Dagoma/Disco Ultimate/Configuration_adv.h b/config/examples/Dagoma/Disco Ultimate/Configuration_adv.h index 075f5605a..f27f7440a 100644 --- a/config/examples/Dagoma/Disco Ultimate/Configuration_adv.h +++ b/config/examples/Dagoma/Disco Ultimate/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/EVNOVO (Artillery)/Sidewinder X1/Configuration_adv.h b/config/examples/EVNOVO (Artillery)/Sidewinder X1/Configuration_adv.h index 525e9963b..d89af2d74 100755 --- a/config/examples/EVNOVO (Artillery)/Sidewinder X1/Configuration_adv.h +++ b/config/examples/EVNOVO (Artillery)/Sidewinder X1/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Einstart-S/Configuration_adv.h b/config/examples/Einstart-S/Configuration_adv.h index f24f158f3..88c2e4c69 100644 --- a/config/examples/Einstart-S/Configuration_adv.h +++ b/config/examples/Einstart-S/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/FYSETC/AIO_II/Configuration_adv.h b/config/examples/FYSETC/AIO_II/Configuration_adv.h index 6451f40a5..9a085b4e4 100644 --- a/config/examples/FYSETC/AIO_II/Configuration_adv.h +++ b/config/examples/FYSETC/AIO_II/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/FYSETC/Cheetah 1.2/BLTouch/Configuration_adv.h b/config/examples/FYSETC/Cheetah 1.2/BLTouch/Configuration_adv.h index 745cd643e..1a4389558 100644 --- a/config/examples/FYSETC/Cheetah 1.2/BLTouch/Configuration_adv.h +++ b/config/examples/FYSETC/Cheetah 1.2/BLTouch/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/FYSETC/Cheetah 1.2/base/Configuration_adv.h b/config/examples/FYSETC/Cheetah 1.2/base/Configuration_adv.h index 745cd643e..1a4389558 100644 --- a/config/examples/FYSETC/Cheetah 1.2/base/Configuration_adv.h +++ b/config/examples/FYSETC/Cheetah 1.2/base/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/FYSETC/Cheetah/BLTouch/Configuration_adv.h b/config/examples/FYSETC/Cheetah/BLTouch/Configuration_adv.h index 745cd643e..1a4389558 100644 --- a/config/examples/FYSETC/Cheetah/BLTouch/Configuration_adv.h +++ b/config/examples/FYSETC/Cheetah/BLTouch/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/FYSETC/Cheetah/base/Configuration_adv.h b/config/examples/FYSETC/Cheetah/base/Configuration_adv.h index 745cd643e..1a4389558 100644 --- a/config/examples/FYSETC/Cheetah/base/Configuration_adv.h +++ b/config/examples/FYSETC/Cheetah/base/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/FYSETC/F6_13/Configuration_adv.h b/config/examples/FYSETC/F6_13/Configuration_adv.h index 7588b43aa..bc0bfc974 100644 --- a/config/examples/FYSETC/F6_13/Configuration_adv.h +++ b/config/examples/FYSETC/F6_13/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Felix/Configuration_adv.h b/config/examples/Felix/Configuration_adv.h index 231458b21..31df1e10d 100644 --- a/config/examples/Felix/Configuration_adv.h +++ b/config/examples/Felix/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/FlashForge/CreatorPro/Configuration_adv.h b/config/examples/FlashForge/CreatorPro/Configuration_adv.h index 80bfc2959..a8ed2b836 100644 --- a/config/examples/FlashForge/CreatorPro/Configuration_adv.h +++ b/config/examples/FlashForge/CreatorPro/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/FolgerTech/i3-2020/Configuration_adv.h b/config/examples/FolgerTech/i3-2020/Configuration_adv.h index d00a05a86..bbadcfa82 100644 --- a/config/examples/FolgerTech/i3-2020/Configuration_adv.h +++ b/config/examples/FolgerTech/i3-2020/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Formbot/Raptor/Configuration_adv.h b/config/examples/Formbot/Raptor/Configuration_adv.h index a40d28e4e..a8d6934f4 100644 --- a/config/examples/Formbot/Raptor/Configuration_adv.h +++ b/config/examples/Formbot/Raptor/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Formbot/T_Rex_2+/Configuration_adv.h b/config/examples/Formbot/T_Rex_2+/Configuration_adv.h index d3b290730..d01238211 100644 --- a/config/examples/Formbot/T_Rex_2+/Configuration_adv.h +++ b/config/examples/Formbot/T_Rex_2+/Configuration_adv.h @@ -606,9 +606,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Formbot/T_Rex_3/Configuration_adv.h b/config/examples/Formbot/T_Rex_3/Configuration_adv.h index c919581ec..3a9d54179 100644 --- a/config/examples/Formbot/T_Rex_3/Configuration_adv.h +++ b/config/examples/Formbot/T_Rex_3/Configuration_adv.h @@ -606,9 +606,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Geeetech/A10/Configuration_adv.h b/config/examples/Geeetech/A10/Configuration_adv.h index d18140a70..0806d2eed 100644 --- a/config/examples/Geeetech/A10/Configuration_adv.h +++ b/config/examples/Geeetech/A10/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Geeetech/A10M/Configuration_adv.h b/config/examples/Geeetech/A10M/Configuration_adv.h index 85e13f4d5..45d50774c 100644 --- a/config/examples/Geeetech/A10M/Configuration_adv.h +++ b/config/examples/Geeetech/A10M/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Geeetech/A20M/Configuration_adv.h b/config/examples/Geeetech/A20M/Configuration_adv.h index 3be72ca3d..94e47a196 100644 --- a/config/examples/Geeetech/A20M/Configuration_adv.h +++ b/config/examples/Geeetech/A20M/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Geeetech/MeCreator2/Configuration_adv.h b/config/examples/Geeetech/MeCreator2/Configuration_adv.h index 048a1e955..9dab3dbbe 100644 --- a/config/examples/Geeetech/MeCreator2/Configuration_adv.h +++ b/config/examples/Geeetech/MeCreator2/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Geeetech/Prusa i3 Pro C/Configuration_adv.h b/config/examples/Geeetech/Prusa i3 Pro C/Configuration_adv.h index d18140a70..0806d2eed 100644 --- a/config/examples/Geeetech/Prusa i3 Pro C/Configuration_adv.h +++ b/config/examples/Geeetech/Prusa i3 Pro C/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Geeetech/Prusa i3 Pro W/Configuration_adv.h b/config/examples/Geeetech/Prusa i3 Pro W/Configuration_adv.h index d18140a70..0806d2eed 100644 --- a/config/examples/Geeetech/Prusa i3 Pro W/Configuration_adv.h +++ b/config/examples/Geeetech/Prusa i3 Pro W/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/HMS434/Configuration_adv.h b/config/examples/HMS434/Configuration_adv.h index 333a0c85b..4dd9f46bf 100644 --- a/config/examples/HMS434/Configuration_adv.h +++ b/config/examples/HMS434/Configuration_adv.h @@ -594,9 +594,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Infitary/i3-M508/Configuration_adv.h b/config/examples/Infitary/i3-M508/Configuration_adv.h index 6a3b21a04..788f452ae 100644 --- a/config/examples/Infitary/i3-M508/Configuration_adv.h +++ b/config/examples/Infitary/i3-M508/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/JGAurora/A1/Configuration_adv.h b/config/examples/JGAurora/A1/Configuration_adv.h index 642cb2bde..1ed9efeb8 100644 --- a/config/examples/JGAurora/A1/Configuration_adv.h +++ b/config/examples/JGAurora/A1/Configuration_adv.h @@ -607,9 +607,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/JGAurora/A5/Configuration_adv.h b/config/examples/JGAurora/A5/Configuration_adv.h index c244a2a0a..42bf4ca3f 100644 --- a/config/examples/JGAurora/A5/Configuration_adv.h +++ b/config/examples/JGAurora/A5/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/JGAurora/A5S/Configuration_adv.h b/config/examples/JGAurora/A5S/Configuration_adv.h index 642cb2bde..1ed9efeb8 100644 --- a/config/examples/JGAurora/A5S/Configuration_adv.h +++ b/config/examples/JGAurora/A5S/Configuration_adv.h @@ -607,9 +607,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/MakerParts/Configuration_adv.h b/config/examples/MakerParts/Configuration_adv.h index 04527f748..f2995f284 100644 --- a/config/examples/MakerParts/Configuration_adv.h +++ b/config/examples/MakerParts/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Malyan/M150/Configuration_adv.h b/config/examples/Malyan/M150/Configuration_adv.h index 3fff5c7cc..83c67f099 100644 --- a/config/examples/Malyan/M150/Configuration_adv.h +++ b/config/examples/Malyan/M150/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Malyan/M200/Configuration_adv.h b/config/examples/Malyan/M200/Configuration_adv.h index 372b708c2..384776a29 100644 --- a/config/examples/Malyan/M200/Configuration_adv.h +++ b/config/examples/Malyan/M200/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Micromake/C1/enhanced/Configuration_adv.h b/config/examples/Micromake/C1/enhanced/Configuration_adv.h index 3f3ae4054..e0f4b1da2 100644 --- a/config/examples/Micromake/C1/enhanced/Configuration_adv.h +++ b/config/examples/Micromake/C1/enhanced/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Mks/Robin/Configuration_adv.h b/config/examples/Mks/Robin/Configuration_adv.h index 2b43d67e6..6a56e4021 100644 --- a/config/examples/Mks/Robin/Configuration_adv.h +++ b/config/examples/Mks/Robin/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Mks/Sbase/Configuration_adv.h b/config/examples/Mks/Sbase/Configuration_adv.h index 28ec8ab8f..9cc531152 100644 --- a/config/examples/Mks/Sbase/Configuration_adv.h +++ b/config/examples/Mks/Sbase/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/RapideLite/RL200/Configuration_adv.h b/config/examples/RapideLite/RL200/Configuration_adv.h index 32436ebc9..fbd7d429d 100644 --- a/config/examples/RapideLite/RL200/Configuration_adv.h +++ b/config/examples/RapideLite/RL200/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/RigidBot/Configuration_adv.h b/config/examples/RigidBot/Configuration_adv.h index 9ffc55cc9..c0142621a 100644 --- a/config/examples/RigidBot/Configuration_adv.h +++ b/config/examples/RigidBot/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/SCARA/Configuration_adv.h b/config/examples/SCARA/Configuration_adv.h index 5ce747fb3..f7c502789 100644 --- a/config/examples/SCARA/Configuration_adv.h +++ b/config/examples/SCARA/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/STM32/Black_STM32F407VET6/Configuration_adv.h b/config/examples/STM32/Black_STM32F407VET6/Configuration_adv.h index 8fad7e1b9..c60a2e7e5 100644 --- a/config/examples/STM32/Black_STM32F407VET6/Configuration_adv.h +++ b/config/examples/STM32/Black_STM32F407VET6/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Sanguinololu/Configuration_adv.h b/config/examples/Sanguinololu/Configuration_adv.h index 77da1c18d..179f0de35 100644 --- a/config/examples/Sanguinololu/Configuration_adv.h +++ b/config/examples/Sanguinololu/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Tevo/Michelangelo/Configuration_adv.h b/config/examples/Tevo/Michelangelo/Configuration_adv.h index aa71156d6..5709472fc 100644 --- a/config/examples/Tevo/Michelangelo/Configuration_adv.h +++ b/config/examples/Tevo/Michelangelo/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Tevo/Tarantula Pro/Configuration_adv.h b/config/examples/Tevo/Tarantula Pro/Configuration_adv.h index 1cc140d9d..a179733e4 100755 --- a/config/examples/Tevo/Tarantula Pro/Configuration_adv.h +++ b/config/examples/Tevo/Tarantula Pro/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Tevo/Tornado/V1 (MKS Base)/Configuration_adv.h b/config/examples/Tevo/Tornado/V1 (MKS Base)/Configuration_adv.h index 56c1900e7..4856a3a8d 100755 --- a/config/examples/Tevo/Tornado/V1 (MKS Base)/Configuration_adv.h +++ b/config/examples/Tevo/Tornado/V1 (MKS Base)/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Tevo/Tornado/V2 (MKS GEN-L)/Configuration_adv.h b/config/examples/Tevo/Tornado/V2 (MKS GEN-L)/Configuration_adv.h index 56c1900e7..4856a3a8d 100755 --- a/config/examples/Tevo/Tornado/V2 (MKS GEN-L)/Configuration_adv.h +++ b/config/examples/Tevo/Tornado/V2 (MKS GEN-L)/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/TheBorg/Configuration_adv.h b/config/examples/TheBorg/Configuration_adv.h index 60053f18a..dea285797 100644 --- a/config/examples/TheBorg/Configuration_adv.h +++ b/config/examples/TheBorg/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/TinyBoy2/Configuration_adv.h b/config/examples/TinyBoy2/Configuration_adv.h index 1c7f8e266..34c68cac4 100644 --- a/config/examples/TinyBoy2/Configuration_adv.h +++ b/config/examples/TinyBoy2/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Tronxy/X3A/Configuration_adv.h b/config/examples/Tronxy/X3A/Configuration_adv.h index b207a08f4..514eac10c 100644 --- a/config/examples/Tronxy/X3A/Configuration_adv.h +++ b/config/examples/Tronxy/X3A/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Tronxy/X5S-2E/Configuration_adv.h b/config/examples/Tronxy/X5S-2E/Configuration_adv.h index 5f8969c6e..55e9c6c94 100644 --- a/config/examples/Tronxy/X5S-2E/Configuration_adv.h +++ b/config/examples/Tronxy/X5S-2E/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/UltiMachine/Archim1/Configuration_adv.h b/config/examples/UltiMachine/Archim1/Configuration_adv.h index f72be1c5e..e9ec937f6 100644 --- a/config/examples/UltiMachine/Archim1/Configuration_adv.h +++ b/config/examples/UltiMachine/Archim1/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/UltiMachine/Archim2/Configuration_adv.h b/config/examples/UltiMachine/Archim2/Configuration_adv.h index 6b399f2d7..ac956d958 100644 --- a/config/examples/UltiMachine/Archim2/Configuration_adv.h +++ b/config/examples/UltiMachine/Archim2/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/VORONDesign/Configuration_adv.h b/config/examples/VORONDesign/Configuration_adv.h index 47e3eeef3..c7bba80ea 100644 --- a/config/examples/VORONDesign/Configuration_adv.h +++ b/config/examples/VORONDesign/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Velleman/K8200/Configuration_adv.h b/config/examples/Velleman/K8200/Configuration_adv.h index d7bc110d4..04f65763b 100644 --- a/config/examples/Velleman/K8200/Configuration_adv.h +++ b/config/examples/Velleman/K8200/Configuration_adv.h @@ -615,9 +615,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Velleman/K8400/Configuration_adv.h b/config/examples/Velleman/K8400/Configuration_adv.h index 66938132d..ba14b40a3 100644 --- a/config/examples/Velleman/K8400/Configuration_adv.h +++ b/config/examples/Velleman/K8400/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/WASP/PowerWASP/Configuration_adv.h b/config/examples/WASP/PowerWASP/Configuration_adv.h index c2a3ec8d6..880018e34 100644 --- a/config/examples/WASP/PowerWASP/Configuration_adv.h +++ b/config/examples/WASP/PowerWASP/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Wanhao/Duplicator 6/Configuration_adv.h b/config/examples/Wanhao/Duplicator 6/Configuration_adv.h index 5742f9852..56bafd602 100644 --- a/config/examples/Wanhao/Duplicator 6/Configuration_adv.h +++ b/config/examples/Wanhao/Duplicator 6/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/Wanhao/Duplicator i3 Mini/Configuration_adv.h b/config/examples/Wanhao/Duplicator i3 Mini/Configuration_adv.h index d38da532d..fddac3a1f 100644 --- a/config/examples/Wanhao/Duplicator i3 Mini/Configuration_adv.h +++ b/config/examples/Wanhao/Duplicator i3 Mini/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/delta/Anycubic/Kossel/Configuration_adv.h b/config/examples/delta/Anycubic/Kossel/Configuration_adv.h index e6ca073dd..561862cd8 100644 --- a/config/examples/delta/Anycubic/Kossel/Configuration_adv.h +++ b/config/examples/delta/Anycubic/Kossel/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/delta/Dreammaker/Overlord/Configuration_adv.h b/config/examples/delta/Dreammaker/Overlord/Configuration_adv.h index 5d7d144a0..053523576 100644 --- a/config/examples/delta/Dreammaker/Overlord/Configuration_adv.h +++ b/config/examples/delta/Dreammaker/Overlord/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/delta/Dreammaker/Overlord_Pro/Configuration_adv.h b/config/examples/delta/Dreammaker/Overlord_Pro/Configuration_adv.h index 5d7d144a0..053523576 100644 --- a/config/examples/delta/Dreammaker/Overlord_Pro/Configuration_adv.h +++ b/config/examples/delta/Dreammaker/Overlord_Pro/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/delta/FLSUN/auto_calibrate/Configuration_adv.h b/config/examples/delta/FLSUN/auto_calibrate/Configuration_adv.h index 421699caa..4396038fc 100644 --- a/config/examples/delta/FLSUN/auto_calibrate/Configuration_adv.h +++ b/config/examples/delta/FLSUN/auto_calibrate/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/delta/FLSUN/kossel/Configuration_adv.h b/config/examples/delta/FLSUN/kossel/Configuration_adv.h index 421699caa..4396038fc 100644 --- a/config/examples/delta/FLSUN/kossel/Configuration_adv.h +++ b/config/examples/delta/FLSUN/kossel/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/delta/FLSUN/kossel_mini/Configuration_adv.h b/config/examples/delta/FLSUN/kossel_mini/Configuration_adv.h index 810f4d90e..62ef3984d 100644 --- a/config/examples/delta/FLSUN/kossel_mini/Configuration_adv.h +++ b/config/examples/delta/FLSUN/kossel_mini/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/delta/Geeetech/Rostock 301/Configuration_adv.h b/config/examples/delta/Geeetech/Rostock 301/Configuration_adv.h index eb1d0d74f..de2cf53e9 100644 --- a/config/examples/delta/Geeetech/Rostock 301/Configuration_adv.h +++ b/config/examples/delta/Geeetech/Rostock 301/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/delta/MKS/SBASE/Configuration_adv.h b/config/examples/delta/MKS/SBASE/Configuration_adv.h index 74c94824c..f9b6af4aa 100644 --- a/config/examples/delta/MKS/SBASE/Configuration_adv.h +++ b/config/examples/delta/MKS/SBASE/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/delta/Tevo Little Monster/Configuration_adv.h b/config/examples/delta/Tevo Little Monster/Configuration_adv.h index e19512907..295b8d08c 100644 --- a/config/examples/delta/Tevo Little Monster/Configuration_adv.h +++ b/config/examples/delta/Tevo Little Monster/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/delta/generic/Configuration_adv.h b/config/examples/delta/generic/Configuration_adv.h index 810f4d90e..62ef3984d 100644 --- a/config/examples/delta/generic/Configuration_adv.h +++ b/config/examples/delta/generic/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/delta/kossel_mini/Configuration_adv.h b/config/examples/delta/kossel_mini/Configuration_adv.h index 810f4d90e..62ef3984d 100644 --- a/config/examples/delta/kossel_mini/Configuration_adv.h +++ b/config/examples/delta/kossel_mini/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/delta/kossel_xl/Configuration_adv.h b/config/examples/delta/kossel_xl/Configuration_adv.h index 0b93b3768..abf7bf74e 100644 --- a/config/examples/delta/kossel_xl/Configuration_adv.h +++ b/config/examples/delta/kossel_xl/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/gCreate/gMax1.5+/Configuration_adv.h b/config/examples/gCreate/gMax1.5+/Configuration_adv.h index 2c1683b18..68ec30b77 100644 --- a/config/examples/gCreate/gMax1.5+/Configuration_adv.h +++ b/config/examples/gCreate/gMax1.5+/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/makibox/Configuration_adv.h b/config/examples/makibox/Configuration_adv.h index 5bfcb3ee2..5f116061b 100644 --- a/config/examples/makibox/Configuration_adv.h +++ b/config/examples/makibox/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/tvrrug/Round2/Configuration_adv.h b/config/examples/tvrrug/Round2/Configuration_adv.h index cdd57bee1..450494ba0 100644 --- a/config/examples/tvrrug/Round2/Configuration_adv.h +++ b/config/examples/tvrrug/Round2/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34 diff --git a/config/examples/wt150/Configuration_adv.h b/config/examples/wt150/Configuration_adv.h index 7228429ea..92810b2ce 100644 --- a/config/examples/wt150/Configuration_adv.h +++ b/config/examples/wt150/Configuration_adv.h @@ -602,9 +602,7 @@ //#define Z_STEPPER_AUTO_ALIGN #if ENABLED(Z_STEPPER_AUTO_ALIGN) // Define probe X and Y positions for Z1, Z2 [, Z3] - #define Z_STEPPER_ALIGN_X { 10, 150, 290 } - #define Z_STEPPER_ALIGN_Y { 290, 10, 290 } - // Set number of iterations to align + #define Z_STEPPER_ALIGN_XY { { 10, 290 }, { 150, 10 }, { 290, 290 } } // Set number of iterations to align #define Z_STEPPER_ALIGN_ITERATIONS 3 // Enable to restore leveling setup after operation #define RESTORE_LEVELING_AFTER_G34