diff --git a/.github/workflows/check-pr.yml b/.github/workflows/check-pr.yml index f73ffc5fbe4ae..b30513f7ccb0e 100644 --- a/.github/workflows/check-pr.yml +++ b/.github/workflows/check-pr.yml @@ -20,10 +20,8 @@ jobs: runs-on: ubuntu-latest steps: - - uses: peter-evans/close-pull@v1 + - uses: superbrothers/close-pull-request@v3 with: - token: ${{ github.token }} - delete-branch: false comment: > Thanks for your contribution! Unfortunately we can't accept PRs directed at release branches. We make patches to the bugfix branches and only later do we push them out as releases. diff --git a/.github/workflows/test-builds.yml b/.github/workflows/test-builds.yml index 979f56cb6a357..5429f3eb95cea 100644 --- a/.github/workflows/test-builds.yml +++ b/.github/workflows/test-builds.yml @@ -56,29 +56,31 @@ jobs: # STM32F1 (Maple) Environments - - STM32F103RC_btt - - STM32F103RC_btt_USB - - STM32F103RE_btt - - STM32F103RE_btt_USB + #- STM32F103RC_btt_maple + - STM32F103RC_btt_USB_maple - STM32F103RC_fysetc - STM32F103RC_meeb - jgaurora_a5s_a1 - STM32F103VE_longer - - mks_robin + #- mks_robin_maple - mks_robin_lite - mks_robin_pro - - STM32F103RET6_creality - - mks_robin_nano35 + #- mks_robin_nano35_maple + #- STM32F103RET6_creality_maple # STM32 (ST) Environments - - STM32F103RC_btt_stm32 + - STM32F103RC_btt + #- STM32F103RC_btt_USB + - STM32F103RE_btt + - STM32F103RE_btt_USB + - STM32F103RET6_creality - STM32F407VE_black - STM32F401VE_STEVAL - BIGTREE_BTT002 - BIGTREE_SKR_PRO - BIGTREE_GTR_V1_0 - - mks_robin_stm32 + - mks_robin - ARMED - FYSETC_S6 - STM32F070CB_malyan @@ -88,7 +90,7 @@ jobs: - rumba32 - LERDGEX - LERDGEK - - mks_robin_nano35_stm32 + - mks_robin_nano35 - NUCLEO_F767ZI - REMRAM_V1 - BTT_SKR_SE_BX @@ -107,8 +109,25 @@ jobs: steps: + - name: Check out the PR + uses: actions/checkout@v2 + + - name: Cache pip + uses: actions/cache@v2 + with: + path: ~/.cache/pip + key: ${{ runner.os }}-pip-${{ hashFiles('**/requirements.txt') }} + restore-keys: | + ${{ runner.os }}-pip- + + - name: Cache PlatformIO + uses: actions/cache@v2 + with: + path: ~/.platformio + key: ${{ runner.os }}-${{ hashFiles('**/lockfiles') }} + - name: Select Python 3.7 - uses: actions/setup-python@v1 + uses: actions/setup-python@v2 with: python-version: '3.7' # Version range or exact version of a Python version to use, using semvers version range syntax. architecture: 'x64' # optional x64 or x86. Defaults to x64 if not specified @@ -118,9 +137,6 @@ jobs: pip install -U https://github.com/platformio/platformio-core/archive/develop.zip platformio update - - name: Check out the PR - uses: actions/checkout@v2 - - name: Run ${{ matrix.test-platform }} Tests run: | make tests-single-ci TEST_TARGET=${{ matrix.test-platform }} diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index dfbfb0e628aae..fb14d5cd616f5 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -37,7 +37,7 @@ * * Advanced settings can be found in Configuration_adv.h */ -#define CONFIGURATION_H_VERSION 02000801 +#define CONFIGURATION_H_VERSION 02000901 //=========================================================================== //============================= Getting Started ============================= @@ -106,12 +106,27 @@ */ #define SERIAL_PORT 2 +/** + * Serial Port Baud Rate + * This is the default communication speed for all serial ports. + * Set the baud rate defaults for additional serial ports below. + * + * 250000 works in most cases, but you might try a lower speed if + * you commonly experience drop-outs during host printing. + * You may try up to 1000000 to speed up SD file transfer. + * + * :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000] + */ +#define BAUDRATE 250000 +//#define BAUD_RATE_GCODE // Enable G-code M575 to set the baud rate + /** * Select a secondary serial port on the board to use for communication with the host. * Currently Ethernet (-2) is only supported on Teensy 4.1 boards. * :[-2, -1, 0, 1, 2, 3, 4, 5, 6, 7] */ #define SERIAL_PORT_2 -1 +#define BAUDRATE_2 1000000 // Enable to override BAUDRATE /** * Select a third serial port on the board to use for communication with the host. @@ -119,17 +134,7 @@ * :[-1, 0, 1, 2, 3, 4, 5, 6, 7] */ //#define SERIAL_PORT_3 1 - -/** - * This setting determines the communication speed of the printer. - * - * 250000 works in most cases, but you might try a lower speed if - * you commonly experience drop-outs during host printing. - * You may try up to 1000000 to speed up SD file transfer. - * - * :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000] - */ -#define BAUDRATE 1000000 +//#define BAUDRATE_3 250000 // Enable to override BAUDRATE // Enable the Bluetooth serial interface on AT90USB devices //#define BLUETOOTH @@ -146,6 +151,45 @@ // Choose your own or use a service like https://www.uuidgenerator.net/version4 //#define MACHINE_UUID "00000000-0000-0000-0000-000000000000" +/** + * Define the number of coordinated linear axes. + * See https://github.com/DerAndere1/Marlin/wiki + * Each linear axis gets its own stepper control and endstop: + * + * Steppers: *_STEP_PIN, *_ENABLE_PIN, *_DIR_PIN, *_ENABLE_ON + * Endstops: *_STOP_PIN, USE_*MIN_PLUG, USE_*MAX_PLUG + * Axes: *_MIN_POS, *_MAX_POS, INVERT_*_DIR + * Planner: DEFAULT_AXIS_STEPS_PER_UNIT, DEFAULT_MAX_FEEDRATE + * DEFAULT_MAX_ACCELERATION, AXIS_RELATIVE_MODES, + * MICROSTEP_MODES, MANUAL_FEEDRATE + * + * :[3, 4, 5, 6] + */ +//#define LINEAR_AXES 3 + +/** + * Axis codes for additional axes: + * This defines the axis code that is used in G-code commands to + * reference a specific axis. + * 'A' for rotational axis parallel to X + * 'B' for rotational axis parallel to Y + * 'C' for rotational axis parallel to Z + * 'U' for secondary linear axis parallel to X + * 'V' for secondary linear axis parallel to Y + * 'W' for secondary linear axis parallel to Z + * Regardless of the settings, firmware-internal axis IDs are + * I (AXIS4), J (AXIS5), K (AXIS6). + */ +#if LINEAR_AXES >= 4 + #define AXIS4_NAME 'A' // :['A', 'B', 'C', 'U', 'V', 'W'] +#endif +#if LINEAR_AXES >= 5 + #define AXIS5_NAME 'B' // :['A', 'B', 'C', 'U', 'V', 'W'] +#endif +#if LINEAR_AXES >= 6 + #define AXIS6_NAME 'C' // :['A', 'B', 'C', 'U', 'V', 'W'] +#endif + // @section extruder // This defines the number of extruders @@ -430,6 +474,7 @@ #define TEMP_SENSOR_PROBE 0 #define TEMP_SENSOR_CHAMBER 0 #define TEMP_SENSOR_COOLER 0 +#define TEMP_SENSOR_REDUNDANT 0 // Dummy thermistor constant temperature readings, for use with 998 and 999 #define DUMMY_THERMISTOR_998_VALUE 25 @@ -441,11 +486,6 @@ //#define MAX31865_SENSOR_OHMS_1 100 //#define MAX31865_CALIBRATION_OHMS_1 430 -// Use temp sensor 1 as a redundant sensor with sensor 0. If the readings -// from the two sensors differ too much the print will be aborted. -//#define TEMP_SENSOR_1_AS_REDUNDANT -#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10 - #define TEMP_RESIDENCY_TIME 10 // (seconds) Time to wait for hotend to "settle" in M109 #define TEMP_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer #define TEMP_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target @@ -458,6 +498,28 @@ #define TEMP_CHAMBER_WINDOW 1 // (°C) Temperature proximity for the "temperature reached" timer #define TEMP_CHAMBER_HYSTERESIS 3 // (°C) Temperature proximity considered "close enough" to the target +/** + * Redundant Temperature Sensor (TEMP_SENSOR_REDUNDANT) + * + * Use a temp sensor as a redundant sensor for another reading. Select an unused temperature sensor, and another + * sensor you'd like it to be redundant for. If the two thermistors differ by TEMP_SENSOR_REDUNDANT_MAX_DIFF (°C), + * the print will be aborted. Whichever sensor is selected will have its normal functions disabled; i.e. selecting + * the Bed sensor (-1) will disable bed heating/monitoring. + * + * Use the following to select temp sensors: + * -5 : Cooler + * -4 : Probe + * -3 : not used + * -2 : Chamber + * -1 : Bed + * 0-7 : E0 through E7 + */ +#if TEMP_SENSOR_REDUNDANT + #define TEMP_SENSOR_REDUNDANT_SOURCE 1 // The sensor that will provide the redundant reading. + #define TEMP_SENSOR_REDUNDANT_TARGET 0 // The sensor that we are providing a redundant reading for. + #define TEMP_SENSOR_REDUNDANT_MAX_DIFF 10 // (°C) Temperature difference that will trigger a print abort. +#endif + // Below this temperature the heater will be switched off // because it probably indicates a broken thermistor wire. #define HEATER_0_MINTEMP 5 @@ -692,9 +754,15 @@ #define USE_XMIN_PLUG #define USE_YMIN_PLUG #define USE_ZMIN_PLUG +//#define USE_IMIN_PLUG +//#define USE_JMIN_PLUG +//#define USE_KMIN_PLUG //#define USE_XMAX_PLUG //#define USE_YMAX_PLUG //#define USE_ZMAX_PLUG +//#define USE_IMAX_PLUG +//#define USE_JMAX_PLUG +//#define USE_KMAX_PLUG // Enable pullup for all endstops to prevent a floating state #define ENDSTOPPULLUPS @@ -703,9 +771,15 @@ //#define ENDSTOPPULLUP_XMAX //#define ENDSTOPPULLUP_YMAX //#define ENDSTOPPULLUP_ZMAX + //#define ENDSTOPPULLUP_IMAX + //#define ENDSTOPPULLUP_JMAX + //#define ENDSTOPPULLUP_KMAX //#define ENDSTOPPULLUP_XMIN //#define ENDSTOPPULLUP_YMIN //#define ENDSTOPPULLUP_ZMIN + //#define ENDSTOPPULLUP_IMIN + //#define ENDSTOPPULLUP_JMIN + //#define ENDSTOPPULLUP_KMIN //#define ENDSTOPPULLUP_ZMIN_PROBE #endif @@ -716,9 +790,15 @@ //#define ENDSTOPPULLDOWN_XMAX //#define ENDSTOPPULLDOWN_YMAX //#define ENDSTOPPULLDOWN_ZMAX + //#define ENDSTOPPULLDOWN_IMAX + //#define ENDSTOPPULLDOWN_JMAX + //#define ENDSTOPPULLDOWN_KMAX //#define ENDSTOPPULLDOWN_XMIN //#define ENDSTOPPULLDOWN_YMIN //#define ENDSTOPPULLDOWN_ZMIN + //#define ENDSTOPPULLDOWN_IMIN + //#define ENDSTOPPULLDOWN_JMIN + //#define ENDSTOPPULLDOWN_KMIN //#define ENDSTOPPULLDOWN_ZMIN_PROBE #endif @@ -726,9 +806,15 @@ #define X_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. #define Y_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. #define Z_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. +#define I_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. +#define J_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. +#define K_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. #define X_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. #define Y_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. #define Z_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. +#define I_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. +#define J_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. +#define K_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop. #define Z_MIN_PROBE_ENDSTOP_INVERTING false // Set to true to invert the logic of the probe. /** @@ -757,6 +843,9 @@ //#define Z2_DRIVER_TYPE A4988 //#define Z3_DRIVER_TYPE A4988 //#define Z4_DRIVER_TYPE A4988 +//#define I_DRIVER_TYPE A4988 +//#define J_DRIVER_TYPE A4988 +//#define K_DRIVER_TYPE A4988 #define E0_DRIVER_TYPE TMC2209 //#define E1_DRIVER_TYPE A4988 //#define E2_DRIVER_TYPE A4988 @@ -810,7 +899,7 @@ /** * Default Axis Steps Per Unit (steps/mm) * Override with M92 - * X, Y, Z, E0 [, E1[, E2...]] + * X, Y, Z [, I [, J [, K]]], E0 [, E1[, E2...]] */ //#define DEFAULT_AXIS_STEPS_PER_UNIT { 78.97, 78.97, 400, 93 } #define DEFAULT_AXIS_STEPS_PER_UNIT { 79.43, 79.43, 400, 98.75 } @@ -818,7 +907,7 @@ /** * Default Max Feed Rate (mm/s) * Override with M203 - * X, Y, Z, E0 [, E1[, E2...]] + * X, Y, Z [, I [, J [, K]]], E0 [, E1[, E2...]] */ #define DEFAULT_MAX_FEEDRATE { 500, 500, 20, 120 } @@ -831,7 +920,7 @@ * Default Max Acceleration (change/s) change = mm/s * (Maximum start speed for accelerated moves) * Override with M201 - * X, Y, Z, E0 [, E1[, E2...]] + * X, Y, Z [, I [, J [, K]]], E0 [, E1[, E2...]] */ #define DEFAULT_MAX_ACCELERATION { 500, 500, 100, 5000 } @@ -865,6 +954,9 @@ #define DEFAULT_XJERK 10.0 #define DEFAULT_YJERK 10.0 #define DEFAULT_ZJERK 0.3 + //#define DEFAULT_IJERK 0.3 + //#define DEFAULT_JJERK 0.3 + //#define DEFAULT_KJERK 0.3 #define TRAVEL_EXTRA_XYJERK 5.0 // Additional jerk allowance for all travel moves @@ -1163,7 +1255,8 @@ //#define WAIT_FOR_HOTEND // Wait for hotend to heat back up between probes (to improve accuracy & prevent cold extrude) #endif //#define PROBING_FANS_OFF // Turn fans off when probing -//#define PROBING_STEPPERS_OFF // Turn steppers off (unless needed to hold position) when probing +//#define PROBING_ESTEPPERS_OFF // Turn all extruder steppers off when probing +//#define PROBING_STEPPERS_OFF // Turn all steppers off (unless needed to hold position) when probing (including extruders) //#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors // Require minimum nozzle and/or bed temperature for probing @@ -1179,12 +1272,18 @@ #define Y_ENABLE_ON 0 #define Z_ENABLE_ON 0 #define E_ENABLE_ON 0 // For all extruders +//#define I_ENABLE_ON 0 +//#define J_ENABLE_ON 0 +//#define K_ENABLE_ON 0 // Disable axis steppers immediately when they're not being stepped. // WARNING: When motors turn off there is a chance of losing position accuracy! #define DISABLE_X false #define DISABLE_Y false #define DISABLE_Z false +//#define DISABLE_I false +//#define DISABLE_J false +//#define DISABLE_K false // Turn off the display blinking that warns about possible accuracy reduction //#define DISABLE_REDUCED_ACCURACY_WARNING @@ -1200,6 +1299,9 @@ #define INVERT_X_DIR true #define INVERT_Y_DIR true #define INVERT_Z_DIR false +//#define INVERT_I_DIR false +//#define INVERT_J_DIR false +//#define INVERT_K_DIR false // @section extruder @@ -1235,6 +1337,9 @@ #define X_HOME_DIR -1 #define Y_HOME_DIR -1 #define Z_HOME_DIR -1 +//#define I_HOME_DIR -1 +//#define J_HOME_DIR -1 +//#define K_HOME_DIR -1 // @section machine @@ -1249,6 +1354,12 @@ #define X_MAX_POS 251 #define Y_MAX_POS 229 #define Z_MAX_POS 250 +//#define I_MIN_POS 0 +//#define I_MAX_POS 50 +//#define J_MIN_POS 0 +//#define J_MAX_POS 50 +//#define K_MIN_POS 0 +//#define K_MAX_POS 50 /** * Software Endstops @@ -1265,6 +1376,9 @@ #define MIN_SOFTWARE_ENDSTOP_X #define MIN_SOFTWARE_ENDSTOP_Y #define MIN_SOFTWARE_ENDSTOP_Z + #define MIN_SOFTWARE_ENDSTOP_I + #define MIN_SOFTWARE_ENDSTOP_J + #define MIN_SOFTWARE_ENDSTOP_K #endif // Max software endstops constrain movement within maximum coordinate bounds @@ -1273,6 +1387,9 @@ #define MAX_SOFTWARE_ENDSTOP_X #define MAX_SOFTWARE_ENDSTOP_Y #define MAX_SOFTWARE_ENDSTOP_Z + #define MAX_SOFTWARE_ENDSTOP_I + #define MAX_SOFTWARE_ENDSTOP_J + #define MAX_SOFTWARE_ENDSTOP_K #endif #if EITHER(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS) @@ -1584,6 +1701,9 @@ //#define MANUAL_X_HOME_POS 0 //#define MANUAL_Y_HOME_POS 0 //#define MANUAL_Z_HOME_POS 0 +//#define MANUAL_I_HOME_POS 0 +//#define MANUAL_J_HOME_POS 0 +//#define MANUAL_K_HOME_POS 0 // Use "Z Safe Homing" to avoid homing with a Z probe outside the bed area. // @@ -1829,11 +1949,20 @@ /** * Print Job Timer * - * Automatically start and stop the print job timer on M104/M109/M190. + * Automatically start and stop the print job timer on M104/M109/M140/M190/M141/M191. + * The print job timer will only be stopped if the bed/chamber target temp is + * below BED_MINTEMP/CHAMBER_MINTEMP. + * + * M104 (hotend, no wait) - high temp = none, low temp = stop timer + * M109 (hotend, wait) - high temp = start timer, low temp = stop timer + * M140 (bed, no wait) - high temp = none, low temp = stop timer + * M190 (bed, wait) - high temp = start timer, low temp = none + * M141 (chamber, no wait) - high temp = none, low temp = stop timer + * M191 (chamber, wait) - high temp = start timer, low temp = none * - * M104 (hotend, no wait) - high temp = none, low temp = stop timer - * M109 (hotend, wait) - high temp = start timer, low temp = stop timer - * M190 (bed, wait) - high temp = start timer, low temp = none + * For M104/M109, high temp is anything over EXTRUDE_MINTEMP / 2. + * For M140/M190, high temp is anything over BED_MINTEMP. + * For M141/M191, high temp is anything over CHAMBER_MINTEMP. * * The timer can also be controlled with the following commands: * @@ -2695,7 +2824,7 @@ //#define NEOPIXEL_LED #if ENABLED(NEOPIXEL_LED) #define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h) - #define NEOPIXEL_PIN 4 // LED driving pin + //#define NEOPIXEL_PIN 4 // LED driving pin //#define NEOPIXEL2_TYPE NEOPIXEL_TYPE //#define NEOPIXEL2_PIN 5 #define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip. (Longest strip when NEOPIXEL2_SEPARATE is disabled.) @@ -2713,10 +2842,11 @@ //#define NEOPIXEL2_INSERIES // Default behavior is NeoPixel 2 in parallel #endif - // Use a single NeoPixel LED for static (background) lighting - //#define NEOPIXEL_BKGD_LED_INDEX 0 // Index of the LED to use - //#define NEOPIXEL_BKGD_COLOR { 255, 255, 255, 0 } // R, G, B, W - //#define NEOPIXEL_BKGD_ALWAYS_ON // Keep the backlight on when other NeoPixels are off + // Use some of the NeoPixel LEDs for static (background) lighting + //#define NEOPIXEL_BKGD_INDEX_FIRST 0 // Index of the first background LED + //#define NEOPIXEL_BKGD_INDEX_LAST 5 // Index of the last background LED + //#define NEOPIXEL_BKGD_COLOR { 255, 255, 255, 0 } // R, G, B, W + //#define NEOPIXEL_BKGD_ALWAYS_ON // Keep the backlight on when other NeoPixels are off #endif /** diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 2ef3bc455735b..be473cecbacf1 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -32,7 +32,7 @@ * * Basic settings can be found in Configuration.h */ -#define CONFIGURATION_ADV_H_VERSION 02000801 +#define CONFIGURATION_ADV_H_VERSION 02000901 //=========================================================================== //============================= Thermal Settings ============================ @@ -127,6 +127,12 @@ #define PROBE_BETA 3950 // Beta value #endif +#if TEMP_SENSOR_REDUNDANT == 1000 + #define REDUNDANT_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor + #define REDUNDANT_RESISTANCE_25C_OHMS 100000 // Resistance at 25C + #define REDUNDANT_BETA 3950 // Beta value +#endif + // // Hephestos 2 24V heated bed upgrade kit. // https://store.bq.com/en/heated-bed-kit-hephestos2 @@ -198,7 +204,7 @@ #define COOLER_MAXTEMP 26 // (°C) #define COOLER_DEFAULT_TEMP 16 // (°C) #define TEMP_COOLER_HYSTERESIS 1 // (°C) Temperature proximity considered "close enough" to the target - #define COOLER_PIN 8 // Laser cooler on/off pin used to control power to the cooling element e.g. TEC, External chiller via relay + #define COOLER_PIN 8 // Laser cooler on/off pin used to control power to the cooling element (e.g., TEC, External chiller via relay) #define COOLER_INVERTING false #define TEMP_COOLER_PIN 15 // Laser/Cooler temperature sensor pin. ADC is required. #define COOLER_FAN // Enable a fan on the cooler, Fan# 0,1,2,3 etc. @@ -528,6 +534,11 @@ //#define USE_OCR2A_AS_TOP #endif +/** + * Use one of the PWM fans as a redundant part-cooling fan + */ +//#define REDUNDANT_PART_COOLING_FAN 2 // Index of the fan to sync with FAN 0. + // @section extruder /** @@ -673,6 +684,12 @@ #endif #endif +// Drive the E axis with two synchronized steppers +//#define E_DUAL_STEPPER_DRIVERS +#if ENABLED(E_DUAL_STEPPER_DRIVERS) + //#define INVERT_E1_VS_E0_DIR // Enable if the E motors need opposite DIR states +#endif + /** * Dual X Carriage * @@ -736,7 +753,7 @@ * the position of the toolhead relative to the workspace. */ -//#define SENSORLESS_BACKOFF_MM { 2, 2 } // (mm) Backoff from endstops before sensorless homing +//#define SENSORLESS_BACKOFF_MM { 2, 2, 0 } // (mm) Backoff from endstops before sensorless homing #define HOMING_BUMP_MM { 5, 5, 2 } // (mm) Backoff from endstops after first bump #define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate) @@ -920,6 +937,9 @@ #define INVERT_X_STEP_PIN false #define INVERT_Y_STEP_PIN false #define INVERT_Z_STEP_PIN false +#define INVERT_I_STEP_PIN false +#define INVERT_J_STEP_PIN false +#define INVERT_K_STEP_PIN false #define INVERT_E_STEP_PIN false /** @@ -931,6 +951,9 @@ #define DISABLE_INACTIVE_X true #define DISABLE_INACTIVE_Y true #define DISABLE_INACTIVE_Z true // Set 'false' if the nozzle could fall onto your printed part! +#define DISABLE_INACTIVE_I true +#define DISABLE_INACTIVE_J true +#define DISABLE_INACTIVE_K true #define DISABLE_INACTIVE_E true // Default Minimum Feedrates for printing and travel moves @@ -971,7 +994,7 @@ #if ENABLED(BACKLASH_COMPENSATION) // Define values for backlash distance and correction. // If BACKLASH_GCODE is enabled these values are the defaults. - #define BACKLASH_DISTANCE_MM { 0, 0, 0 } // (mm) + #define BACKLASH_DISTANCE_MM { 0, 0, 0 } // (mm) One value for each linear axis #define BACKLASH_CORRECTION 0.0 // 0.0 = no correction; 1.0 = full correction // Add steps for motor direction changes on CORE kinematics @@ -1042,6 +1065,13 @@ #define CALIBRATION_MEASURE_LEFT #define CALIBRATION_MEASURE_BACK + //#define CALIBRATION_MEASURE_IMIN + //#define CALIBRATION_MEASURE_IMAX + //#define CALIBRATION_MEASURE_JMIN + //#define CALIBRATION_MEASURE_JMAX + //#define CALIBRATION_MEASURE_KMIN + //#define CALIBRATION_MEASURE_KMAX + // Probing at the exact top center only works if the center is flat. If // probing on a screwhead or hollow washer, probe near the edges. //#define CALIBRATION_MEASURE_AT_TOP_EDGES @@ -1303,6 +1333,8 @@ //#define BROWSE_MEDIA_ON_INSERT // Open the file browser when media is inserted + //#define MEDIA_MENU_AT_TOP // Force the media menu to be listed on the top of the main menu + #define EVENT_GCODE_SD_ABORT "G28XY" // G-code to run on SD Abort Print (e.g., "G28XY" or "G27") #if ENABLED(PRINTER_EVENT_LEDS) @@ -1564,7 +1596,7 @@ */ //#define STATUS_COMBINE_HEATERS // Use combined heater images instead of separate ones //#define STATUS_HOTEND_NUMBERLESS // Use plain hotend icons instead of numbered ones (with 2+ hotends) - #define STATUS_HOTEND_INVERTED // Show solid nozzle bitmaps when heating (Requires STATUS_HOTEND_ANIM) + #define STATUS_HOTEND_INVERTED // Show solid nozzle bitmaps when heating (Requires STATUS_HOTEND_ANIM for numbered hotends) #define STATUS_HOTEND_ANIM // Use a second bitmap to indicate hotend heating #define STATUS_BED_ANIM // Use a second bitmap to indicate bed heating #define STATUS_CHAMBER_ANIM // Use a second bitmap to indicate chamber heating @@ -1943,30 +1975,30 @@ //#define USE_TEMP_EXT_COMPENSATION // Probe temperature calibration generates a table of values starting at PTC_SAMPLE_START - // (e.g. 30), in steps of PTC_SAMPLE_RES (e.g. 5) with PTC_SAMPLE_COUNT (e.g. 10) samples. + // (e.g., 30), in steps of PTC_SAMPLE_RES (e.g., 5) with PTC_SAMPLE_COUNT (e.g., 10) samples. - //#define PTC_SAMPLE_START 30.0f - //#define PTC_SAMPLE_RES 5.0f - //#define PTC_SAMPLE_COUNT 10U + //#define PTC_SAMPLE_START 30 // (°C) + //#define PTC_SAMPLE_RES 5 // (°C) + //#define PTC_SAMPLE_COUNT 10 // Bed temperature calibration builds a similar table. - //#define BTC_SAMPLE_START 60.0f - //#define BTC_SAMPLE_RES 5.0f - //#define BTC_SAMPLE_COUNT 10U + //#define BTC_SAMPLE_START 60 // (°C) + //#define BTC_SAMPLE_RES 5 // (°C) + //#define BTC_SAMPLE_COUNT 10 // The temperature the probe should be at while taking measurements during bed temperature // calibration. - //#define BTC_PROBE_TEMP 30.0f + //#define BTC_PROBE_TEMP 30 // (°C) - // Height above Z=0.0f to raise the nozzle. Lowering this can help the probe to heat faster. - // Note: the Z=0.0f offset is determined by the probe offset which can be set using M851. - //#define PTC_PROBE_HEATING_OFFSET 0.5f + // Height above Z=0.0 to raise the nozzle. Lowering this can help the probe to heat faster. + // Note: the Z=0.0 offset is determined by the probe offset which can be set using M851. + //#define PTC_PROBE_HEATING_OFFSET 0.5 // Height to raise the Z-probe between heating and taking the next measurement. Some probes // may fail to untrigger if they have been triggered for a long time, which can be solved by // increasing the height the probe is raised to. - //#define PTC_PROBE_RAISE 15U + //#define PTC_PROBE_RAISE 15 // If the probe is outside of the defined range, use linear extrapolation using the closest // point and the PTC_LINEAR_EXTRAPOLATION'th next point. E.g. if set to 4 it will use data[0] @@ -2081,7 +2113,7 @@ // @section motion // The number of linear moves that can be in the planner at once. -// The value of BLOCK_BUFFER_SIZE must be a power of 2 (e.g. 8, 16, 32) +// The value of BLOCK_BUFFER_SIZE must be a power of 2 (e.g., 8, 16, 32) #if BOTH(SDSUPPORT, DIRECT_STEPPING) #define BLOCK_BUFFER_SIZE 8 #elif ENABLED(SDSUPPORT) @@ -2117,9 +2149,6 @@ //#define SERIAL_XON_XOFF #endif -// Add M575 G-code to change the baud rate -//#define BAUD_RATE_GCODE - #if ENABLED(SDSUPPORT) // Enable this option to collect and display the maximum // RX queue usage after transferring a file to SD. @@ -2240,6 +2269,13 @@ //#define EVENT_GCODE_AFTER_TOOLCHANGE "G12X" // Extra G-code to run after tool-change #endif + /** + * Extra G-code to run while executing tool-change commands. Can be used to use an additional + * stepper motor (I axis, see option LINEAR_AXES in Configuration.h) to drive the tool-changer. + */ + //#define EVENT_GCODE_TOOLCHANGE_T0 "G28 A\nG1 A0" // Extra G-code to run while executing tool-change command T0 + //#define EVENT_GCODE_TOOLCHANGE_T1 "G1 A10" // Extra G-code to run while executing tool-change command T1 + /** * Tool Sensors detect when tools have been picked up or dropped. * Requires the pins TOOL_SENSOR1_PIN, TOOL_SENSOR2_PIN, etc. @@ -2417,6 +2453,24 @@ #define Z4_MICROSTEPS Z_MICROSTEPS #endif + #if AXIS_DRIVER_TYPE_I(TMC26X) + #define I_MAX_CURRENT 1000 + #define I_SENSE_RESISTOR 91 + #define I_MICROSTEPS 16 + #endif + + #if AXIS_DRIVER_TYPE_J(TMC26X) + #define J_MAX_CURRENT 1000 + #define J_SENSE_RESISTOR 91 + #define J_MICROSTEPS 16 + #endif + + #if AXIS_DRIVER_TYPE_K(TMC26X) + #define K_MAX_CURRENT 1000 + #define K_SENSE_RESISTOR 91 + #define K_MICROSTEPS 16 + #endif + #if AXIS_DRIVER_TYPE_E0(TMC26X) #define E0_MAX_CURRENT 1000 #define E0_SENSE_RESISTOR 91 @@ -2567,6 +2621,33 @@ //#define Z4_INTERPOLATE true #endif + #if AXIS_IS_TMC(I) + #define I_CURRENT 800 + #define I_CURRENT_HOME I_CURRENT + #define I_MICROSTEPS 16 + #define I_RSENSE 0.11 + #define I_CHAIN_POS -1 + //#define I_INTERPOLATE true + #endif + + #if AXIS_IS_TMC(J) + #define J_CURRENT 800 + #define J_CURRENT_HOME J_CURRENT + #define J_MICROSTEPS 16 + #define J_RSENSE 0.11 + #define J_CHAIN_POS -1 + //#define J_INTERPOLATE true + #endif + + #if AXIS_IS_TMC(K) + #define K_CURRENT 800 + #define K_CURRENT_HOME K_CURRENT + #define K_MICROSTEPS 16 + #define K_RSENSE 0.11 + #define K_CHAIN_POS -1 + //#define K_INTERPOLATE true + #endif + #if AXIS_IS_TMC(E0) #define E0_CURRENT 650 #define E0_MICROSTEPS 16 @@ -2642,6 +2723,10 @@ //#define Y2_CS_PIN -1 //#define Z2_CS_PIN -1 //#define Z3_CS_PIN -1 + //#define Z4_CS_PIN -1 + //#define I_CS_PIN -1 + //#define J_CS_PIN -1 + //#define K_CS_PIN -1 //#define E0_CS_PIN -1 //#define E1_CS_PIN -1 //#define E2_CS_PIN -1 @@ -2705,6 +2790,9 @@ */ #define STEALTHCHOP_XY #define STEALTHCHOP_Z + #define STEALTHCHOP_I + #define STEALTHCHOP_J + #define STEALTHCHOP_K #define STEALTHCHOP_E /** @@ -2760,6 +2848,9 @@ #define Z2_HYBRID_THRESHOLD 3 #define Z3_HYBRID_THRESHOLD 3 #define Z4_HYBRID_THRESHOLD 3 + #define I_HYBRID_THRESHOLD 3 + #define J_HYBRID_THRESHOLD 3 + #define K_HYBRID_THRESHOLD 3 #define E0_HYBRID_THRESHOLD 30 #define E1_HYBRID_THRESHOLD 30 #define E2_HYBRID_THRESHOLD 30 @@ -2785,7 +2876,7 @@ * * It is recommended to set HOMING_BUMP_MM to { 0, 0, 0 }. * - * SPI_ENDSTOPS *** Beta feature! *** TMC2130 Only *** + * SPI_ENDSTOPS *** Beta feature! *** TMC2130/TMC5160 Only *** * Poll the driver through SPI to determine load when homing. * Removes the need for a wire from DIAG1 to an endstop pin. * @@ -2806,6 +2897,9 @@ //#define Z2_STALL_SENSITIVITY Z_STALL_SENSITIVITY //#define Z3_STALL_SENSITIVITY Z_STALL_SENSITIVITY //#define Z4_STALL_SENSITIVITY Z_STALL_SENSITIVITY + //#define I_STALL_SENSITIVITY 8 + //#define J_STALL_SENSITIVITY 8 + //#define K_STALL_SENSITIVITY 8 //#define SPI_ENDSTOPS // TMC2130 only #define IMPROVE_HOMING_RELIABILITY #endif @@ -2946,6 +3040,33 @@ #define Z4_SLEW_RATE 1 #endif + #if AXIS_DRIVER_TYPE_I(L6470) + #define I_MICROSTEPS 128 + #define I_OVERCURRENT 2000 + #define I_STALLCURRENT 1500 + #define I_MAX_VOLTAGE 127 + #define I_CHAIN_POS -1 + #define I_SLEW_RATE 1 + #endif + + #if AXIS_DRIVER_TYPE_J(L6470) + #define J_MICROSTEPS 128 + #define J_OVERCURRENT 2000 + #define J_STALLCURRENT 1500 + #define J_MAX_VOLTAGE 127 + #define J_CHAIN_POS -1 + #define J_SLEW_RATE 1 + #endif + + #if AXIS_DRIVER_TYPE_K(L6470) + #define K_MICROSTEPS 128 + #define K_OVERCURRENT 2000 + #define K_STALLCURRENT 1500 + #define K_MAX_VOLTAGE 127 + #define K_CHAIN_POS -1 + #define K_SLEW_RATE 1 + #endif + #if AXIS_IS_L64XX(E0) #define E0_MICROSTEPS 128 #define E0_OVERCURRENT 2000 @@ -3295,8 +3416,18 @@ #define SPINDLE_LASER_POWERDOWN_DELAY 50 // (ms) Delay to allow the spindle to stop #endif + + // + // Laser I2C Ammeter (High precision INA226 low/high side module) + // + //#define I2C_AMMETER + #if ENABLED(I2C_AMMETER) + #define I2C_AMMETER_IMAX 0.1 // (Amps) Calibration value for the expected current range + #define I2C_AMMETER_SHUNT_RESISTOR 0.1 // (Ohms) Calibration shunt resistor value + #endif + #endif -#endif +#endif // SPINDLE_FEATURE || LASER_FEATURE /** * Synchronous Laser Control with M106/M107 diff --git a/Marlin/Version.h b/Marlin/Version.h index 75dc54369b16e..2a5f451c79184 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -28,7 +28,7 @@ /** * Marlin release version identifier */ -//#define SHORT_BUILD_VERSION "2.0.8.1" +//#define SHORT_BUILD_VERSION "2.0.9.1" /** * Verbose version identifier which should contain a reference to the location @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2021-05-15" +//#define STRING_DISTRIBUTION_DATE "2021-06-27" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h index e24b923ef03a6..a5896a0e970fc 100644 --- a/Marlin/src/HAL/AVR/HAL.h +++ b/Marlin/src/HAL/AVR/HAL.h @@ -186,7 +186,7 @@ inline void HAL_adc_init() { #define GET_PIN_MAP_INDEX(pin) pin #define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) -#define HAL_SENSITIVE_PINS 0, 1 +#define HAL_SENSITIVE_PINS 0, 1, #ifdef __AVR_AT90USB1286__ #define JTAG_DISABLE() do{ MCUCR = 0x80; MCUCR = 0x80; }while(0) diff --git a/Marlin/src/HAL/AVR/endstop_interrupts.h b/Marlin/src/HAL/AVR/endstop_interrupts.h index 9fd9c38b86ad6..50f29c3356ce5 100644 --- a/Marlin/src/HAL/AVR/endstop_interrupts.h +++ b/Marlin/src/HAL/AVR/endstop_interrupts.h @@ -168,6 +168,51 @@ void setup_endstop_interrupts() { pciSetup(Z_MIN_PIN); #endif #endif + #if HAS_I_MAX + #if (digitalPinToInterrupt(I_MAX_PIN) != NOT_AN_INTERRUPT) + _ATTACH(I_MAX_PIN); + #else + static_assert(digitalPinHasPCICR(I_MAX_PIN), "I_MAX_PIN is not interrupt-capable"); + pciSetup(I_MAX_PIN); + #endif + #elif HAS_I_MIN + #if (digitalPinToInterrupt(I_MIN_PIN) != NOT_AN_INTERRUPT) + _ATTACH(I_MIN_PIN); + #else + static_assert(digitalPinHasPCICR(I_MIN_PIN), "I_MIN_PIN is not interrupt-capable"); + pciSetup(I_MIN_PIN); + #endif + #endif + #if HAS_J_MAX + #if (digitalPinToInterrupt(J_MAX_PIN) != NOT_AN_INTERRUPT) + _ATTACH(J_MAX_PIN); + #else + static_assert(digitalPinHasPCICR(J_MAX_PIN), "J_MAX_PIN is not interrupt-capable"); + pciSetup(J_MAX_PIN); + #endif + #elif HAS_J_MIN + #if (digitalPinToInterrupt(J_MIN_PIN) != NOT_AN_INTERRUPT) + _ATTACH(J_MIN_PIN); + #else + static_assert(digitalPinHasPCICR(J_MIN_PIN), "J_MIN_PIN is not interrupt-capable"); + pciSetup(J_MIN_PIN); + #endif + #endif + #if HAS_K_MAX + #if (digitalPinToInterrupt(K_MAX_PIN) != NOT_AN_INTERRUPT) + _ATTACH(K_MAX_PIN); + #else + static_assert(digitalPinHasPCICR(K_MAX_PIN), "K_MAX_PIN is not interrupt-capable"); + pciSetup(K_MAX_PIN); + #endif + #elif HAS_K_MIN + #if (digitalPinToInterrupt(K_MIN_PIN) != NOT_AN_INTERRUPT) + _ATTACH(K_MIN_PIN); + #else + static_assert(digitalPinHasPCICR(K_MIN_PIN), "K_MIN_PIN is not interrupt-capable"); + pciSetup(K_MIN_PIN); + #endif + #endif #if HAS_X2_MAX #if (digitalPinToInterrupt(X2_MAX_PIN) != NOT_AN_INTERRUPT) _ATTACH(X2_MAX_PIN); @@ -256,6 +301,5 @@ void setup_endstop_interrupts() { pciSetup(Z_MIN_PROBE_PIN); #endif #endif - // If we arrive here without raising an assertion, each pin has either an EXT-interrupt or a PCI. } diff --git a/Marlin/src/HAL/DUE/endstop_interrupts.h b/Marlin/src/HAL/DUE/endstop_interrupts.h index 999ada512761c..9c7e2104882ed 100644 --- a/Marlin/src/HAL/DUE/endstop_interrupts.h +++ b/Marlin/src/HAL/DUE/endstop_interrupts.h @@ -64,4 +64,10 @@ void setup_endstop_interrupts() { TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); + TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN)); + TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN)); + TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN)); + TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN)); + TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN)); + TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN)); } diff --git a/Marlin/src/HAL/ESP32/endstop_interrupts.h b/Marlin/src/HAL/ESP32/endstop_interrupts.h index 743ccd99c9044..4725df921b1ad 100644 --- a/Marlin/src/HAL/ESP32/endstop_interrupts.h +++ b/Marlin/src/HAL/ESP32/endstop_interrupts.h @@ -59,4 +59,10 @@ void setup_endstop_interrupts() { TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); + TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN)); + TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN)); + TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN)); + TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN)); + TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN)); + TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN)); } diff --git a/Marlin/src/HAL/LINUX/include/pinmapping.cpp b/Marlin/src/HAL/LINUX/include/pinmapping.cpp index 870ab3a96e5f7..5823668cd50dc 100644 --- a/Marlin/src/HAL/LINUX/include/pinmapping.cpp +++ b/Marlin/src/HAL/LINUX/include/pinmapping.cpp @@ -25,43 +25,6 @@ #include "../../../gcode/parser.h" -uint8_t analog_offset = NUM_DIGITAL_PINS - NUM_ANALOG_INPUTS; - -// Get the digital pin for an analog index -pin_t analogInputToDigitalPin(const int8_t p) { - return (WITHIN(p, 0, NUM_ANALOG_INPUTS) ? analog_offset + p : P_NC); -} - -// Return the index of a pin number -int16_t GET_PIN_MAP_INDEX(const pin_t pin) { - return pin; -} - -// Test whether the pin is valid -bool VALID_PIN(const pin_t p) { - return WITHIN(p, 0, NUM_DIGITAL_PINS); -} - -// Get the analog index for a digital pin -int8_t DIGITAL_PIN_TO_ANALOG_PIN(const pin_t p) { - return (WITHIN(p, analog_offset, NUM_DIGITAL_PINS) ? p - analog_offset : P_NC); -} - -// Test whether the pin is PWM -bool PWM_PIN(const pin_t p) { - return false; -} - -// Test whether the pin is interruptable -bool INTERRUPT_PIN(const pin_t p) { - return false; -} - -// Get the pin number at the given index -pin_t GET_PIN_MAP_PIN(const int16_t ind) { - return ind; -} - int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) { return parser.intval(code, dval); } diff --git a/Marlin/src/HAL/LINUX/include/pinmapping.h b/Marlin/src/HAL/LINUX/include/pinmapping.h index 98f4b812e8733..3751ae0027c79 100644 --- a/Marlin/src/HAL/LINUX/include/pinmapping.h +++ b/Marlin/src/HAL/LINUX/include/pinmapping.h @@ -34,26 +34,32 @@ constexpr uint8_t NUM_ANALOG_INPUTS = 16; #define HAL_SENSITIVE_PINS +constexpr uint8_t analog_offset = NUM_DIGITAL_PINS - NUM_ANALOG_INPUTS; + // Get the digital pin for an analog index -pin_t analogInputToDigitalPin(const int8_t p); +constexpr pin_t analogInputToDigitalPin(const int8_t p) { + return (WITHIN(p, 0, NUM_ANALOG_INPUTS) ? analog_offset + p : P_NC); +} + +// Get the analog index for a digital pin +constexpr int8_t DIGITAL_PIN_TO_ANALOG_PIN(const pin_t p) { + return (WITHIN(p, analog_offset, NUM_DIGITAL_PINS) ? p - analog_offset : P_NC); +} // Return the index of a pin number -int16_t GET_PIN_MAP_INDEX(const pin_t pin); +constexpr int16_t GET_PIN_MAP_INDEX(const pin_t pin) { return pin; } // Test whether the pin is valid -bool VALID_PIN(const pin_t p); - -// Get the analog index for a digital pin -int8_t DIGITAL_PIN_TO_ANALOG_PIN(const pin_t p); +constexpr bool VALID_PIN(const pin_t p) { return WITHIN(p, 0, NUM_DIGITAL_PINS); } // Test whether the pin is PWM -bool PWM_PIN(const pin_t p); +constexpr bool PWM_PIN(const pin_t p) { return false; } // Test whether the pin is interruptable -bool INTERRUPT_PIN(const pin_t p); +constexpr bool INTERRUPT_PIN(const pin_t p) { return false; } // Get the pin number at the given index -pin_t GET_PIN_MAP_PIN(const int16_t ind); +constexpr pin_t GET_PIN_MAP_PIN(const int16_t ind) { return ind; } // Parse a G-code word into a pin index int16_t PARSED_PIN_INDEX(const char code, const int16_t dval); diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h index 85e89339205f0..3f9cd2dfbd022 100644 --- a/Marlin/src/HAL/LPC1768/HAL.h +++ b/Marlin/src/HAL/LPC1768/HAL.h @@ -198,7 +198,7 @@ constexpr pin_t GET_PIN_MAP_PIN(const int16_t index) { // Parse a G-code word into a pin index int16_t PARSED_PIN_INDEX(const char code, const int16_t dval); // P0.6 thru P0.9 are for the onboard SD card -#define HAL_SENSITIVE_PINS P0_06, P0_07, P0_08, P0_09 +#define HAL_SENSITIVE_PINS P0_06, P0_07, P0_08, P0_09, #define HAL_IDLETASK 1 void HAL_idletask(); diff --git a/Marlin/src/HAL/LPC1768/HAL_SPI.cpp b/Marlin/src/HAL/LPC1768/HAL_SPI.cpp index 99db15f6e99cc..29f9b43afef06 100644 --- a/Marlin/src/HAL/LPC1768/HAL_SPI.cpp +++ b/Marlin/src/HAL/LPC1768/HAL_SPI.cpp @@ -66,11 +66,7 @@ #include - #ifndef HAL_SPI_SPEED - #define HAL_SPI_SPEED SPI_FULL_SPEED - #endif - - static uint8_t SPI_speed = HAL_SPI_SPEED; + static uint8_t SPI_speed = SPI_FULL_SPEED; static uint8_t spiTransfer(uint8_t b) { return swSpiTransfer(b, SPI_speed, SD_SCK_PIN, SD_MISO_PIN, SD_MOSI_PIN); @@ -106,15 +102,13 @@ #else - #ifndef HAL_SPI_SPEED - #ifdef SD_SPI_SPEED - #define HAL_SPI_SPEED SD_SPI_SPEED - #else - #define HAL_SPI_SPEED SPI_FULL_SPEED - #endif + #ifdef SD_SPI_SPEED + #define INIT_SPI_SPEED SD_SPI_SPEED + #else + #define INIT_SPI_SPEED SPI_FULL_SPEED #endif - void spiBegin() { spiInit(HAL_SPI_SPEED); } // Set up SCK, MOSI & MISO pins for SSP0 + void spiBegin() { spiInit(INIT_SPI_SPEED); } // Set up SCK, MOSI & MISO pins for SSP0 void spiInit(uint8_t spiRate) { #if SD_MISO_PIN == BOARD_SPI1_MISO_PIN diff --git a/Marlin/src/HAL/LPC1768/endstop_interrupts.h b/Marlin/src/HAL/LPC1768/endstop_interrupts.h index 126d6e7d5bb29..23bd0cc982b29 100644 --- a/Marlin/src/HAL/LPC1768/endstop_interrupts.h +++ b/Marlin/src/HAL/LPC1768/endstop_interrupts.h @@ -122,4 +122,37 @@ void setup_endstop_interrupts() { #endif _ATTACH(Z_MIN_PROBE_PIN); #endif + #if HAS_I_MAX + #if !LPC1768_PIN_INTERRUPT_M(I_MAX_PIN) + #error "I_MAX_PIN is not INTERRUPT-capable." + #endif + _ATTACH(I_MAX_PIN); + #elif HAS_I_MIN + #if !LPC1768_PIN_INTERRUPT_M(I_MIN_PIN) + #error "I_MIN_PIN is not INTERRUPT-capable." + #endif + _ATTACH(I_MIN_PIN); + #endif + #if HAS_J_MAX + #if !LPC1768_PIN_INTERRUPT_M(J_MAX_PIN) + #error "J_MAX_PIN is not INTERRUPT-capable." + #endif + _ATTACH(J_MAX_PIN); + #elif HAS_J_MIN + #if !LPC1768_PIN_INTERRUPT_M(J_MIN_PIN) + #error "J_MIN_PIN is not INTERRUPT-capable." + #endif + _ATTACH(J_MIN_PIN); + #endif + #if HAS_K_MAX + #if !LPC1768_PIN_INTERRUPT_M(K_MAX_PIN) + #error "K_MAX_PIN is not INTERRUPT-capable." + #endif + _ATTACH(K_MAX_PIN); + #elif HAS_K_MIN + #if !LPC1768_PIN_INTERRUPT_M(K_MIN_PIN) + #error "K_MIN_PIN is not INTERRUPT-capable." + #endif + _ATTACH(K_MIN_PIN); + #endif } diff --git a/Marlin/src/HAL/LPC1768/tft/xpt2046.h b/Marlin/src/HAL/LPC1768/tft/xpt2046.h index 65602bda0f409..aba0799e445f8 100644 --- a/Marlin/src/HAL/LPC1768/tft/xpt2046.h +++ b/Marlin/src/HAL/LPC1768/tft/xpt2046.h @@ -54,7 +54,7 @@ enum XPTCoordinate : uint8_t { XPT2046_Z2 = 0x40 | XPT2046_CONTROL | XPT2046_DFR_MODE, }; -#if !defined(XPT2046_Z1_THRESHOLD) +#ifndef XPT2046_Z1_THRESHOLD #define XPT2046_Z1_THRESHOLD 10 #endif diff --git a/Marlin/src/HAL/SAMD51/endstop_interrupts.h b/Marlin/src/HAL/SAMD51/endstop_interrupts.h index daac7733875b0..c46b6e072f905 100644 --- a/Marlin/src/HAL/SAMD51/endstop_interrupts.h +++ b/Marlin/src/HAL/SAMD51/endstop_interrupts.h @@ -47,80 +47,38 @@ #include "../../module/endstops.h" -#define MATCH_EILINE(P1,P2) (P1 != P2 && PIN_TO_EILINE(P1) == PIN_TO_EILINE(P2)) -#if HAS_X_MAX - #define MATCH_X_MAX_EILINE(P) MATCH_EILINE(P, X_MAX_PIN) -#else - #define MATCH_X_MAX_EILINE(P) false -#endif -#if HAS_X_MIN - #define MATCH_X_MIN_EILINE(P) MATCH_EILINE(P, X_MIN_PIN) -#else - #define MATCH_X_MIN_EILINE(P) false -#endif -#if HAS_Y_MAX - #define MATCH_Y_MAX_EILINE(P) MATCH_EILINE(P, Y_MAX_PIN) -#else - #define MATCH_Y_MAX_EILINE(P) false -#endif -#if HAS_Y_MIN - #define MATCH_Y_MIN_EILINE(P) MATCH_EILINE(P, Y_MIN_PIN) -#else - #define MATCH_Y_MIN_EILINE(P) false -#endif -#if HAS_Z_MAX - #define MATCH_Z_MAX_EILINE(P) MATCH_EILINE(P, Z_MAX_PIN) -#else - #define MATCH_Z_MAX_EILINE(P) false -#endif -#if HAS_Z_MIN - #define MATCH_Z_MIN_EILINE(P) MATCH_EILINE(P, Z_MIN_PIN) -#else - #define MATCH_Z_MIN_EILINE(P) false -#endif -#if HAS_Z2_MAX - #define MATCH_Z2_MAX_EILINE(P) MATCH_EILINE(P, Z2_MAX_PIN) -#else - #define MATCH_Z2_MAX_EILINE(P) false -#endif -#if HAS_Z2_MIN - #define MATCH_Z2_MIN_EILINE(P) MATCH_EILINE(P, Z2_MIN_PIN) -#else - #define MATCH_Z2_MIN_EILINE(P) false -#endif -#if HAS_Z3_MAX - #define MATCH_Z3_MAX_EILINE(P) MATCH_EILINE(P, Z3_MAX_PIN) -#else - #define MATCH_Z3_MAX_EILINE(P) false -#endif -#if HAS_Z3_MIN - #define MATCH_Z3_MIN_EILINE(P) MATCH_EILINE(P, Z3_MIN_PIN) -#else - #define MATCH_Z3_MIN_EILINE(P) false -#endif -#if HAS_Z4_MAX - #define MATCH_Z4_MAX_EILINE(P) MATCH_EILINE(P, Z4_MAX_PIN) -#else - #define MATCH_Z4_MAX_EILINE(P) false -#endif -#if HAS_Z4_MIN - #define MATCH_Z4_MIN_EILINE(P) MATCH_EILINE(P, Z4_MIN_PIN) -#else - #define MATCH_Z4_MIN_EILINE(P) false -#endif -#if HAS_Z_MIN_PROBE_PIN - #define MATCH_Z_MIN_PROBE_EILINE(P) MATCH_EILINE(P, Z_MIN_PROBE_PIN) -#else - #define MATCH_Z_MIN_PROBE_EILINE(P) false -#endif -#define AVAILABLE_EILINE(P) (PIN_TO_EILINE(P) != -1 \ - && !MATCH_X_MAX_EILINE(P) && !MATCH_X_MIN_EILINE(P) \ - && !MATCH_Y_MAX_EILINE(P) && !MATCH_Y_MIN_EILINE(P) \ - && !MATCH_Z_MAX_EILINE(P) && !MATCH_Z_MIN_EILINE(P) \ - && !MATCH_Z2_MAX_EILINE(P) && !MATCH_Z2_MIN_EILINE(P) \ - && !MATCH_Z3_MAX_EILINE(P) && !MATCH_Z3_MIN_EILINE(P) \ - && !MATCH_Z4_MAX_EILINE(P) && !MATCH_Z4_MIN_EILINE(P) \ - && !MATCH_Z_MIN_PROBE_EILINE(P)) +#define MATCH_EILINE(P1,P2) (P1 != P2 && PIN_TO_EILINE(P1) == PIN_TO_EILINE(P2)) +#define MATCH_X_MAX_EILINE(P) TERN0(HAS_X_MAX, DEFER4(MATCH_EILINE)(P, X_MAX_PIN)) +#define MATCH_X_MIN_EILINE(P) TERN0(HAS_X_MIN, DEFER4(MATCH_EILINE)(P, X_MIN_PIN)) +#define MATCH_Y_MAX_EILINE(P) TERN0(HAS_Y_MAX, DEFER4(MATCH_EILINE)(P, Y_MAX_PIN)) +#define MATCH_Y_MIN_EILINE(P) TERN0(HAS_Y_MIN, DEFER4(MATCH_EILINE)(P, Y_MIN_PIN)) +#define MATCH_Z_MAX_EILINE(P) TERN0(HAS_Z_MAX, DEFER4(MATCH_EILINE)(P, Z_MAX_PIN)) +#define MATCH_Z_MIN_EILINE(P) TERN0(HAS_Z_MIN, DEFER4(MATCH_EILINE)(P, Z_MIN_PIN)) +#define MATCH_I_MAX_EILINE(P) TERN0(HAS_I_MAX, DEFER4(MATCH_EILINE)(P, I_MAX_PIN)) +#define MATCH_I_MIN_EILINE(P) TERN0(HAS_I_MIN, DEFER4(MATCH_EILINE)(P, I_MIN_PIN)) +#define MATCH_J_MAX_EILINE(P) TERN0(HAS_J_MAX, DEFER4(MATCH_EILINE)(P, J_MAX_PIN)) +#define MATCH_J_MIN_EILINE(P) TERN0(HAS_J_MIN, DEFER4(MATCH_EILINE)(P, J_MIN_PIN)) +#define MATCH_K_MAX_EILINE(P) TERN0(HAS_K_MAX, DEFER4(MATCH_EILINE)(P, K_MAX_PIN)) +#define MATCH_K_MIN_EILINE(P) TERN0(HAS_K_MIN, DEFER4(MATCH_EILINE)(P, K_MIN_PIN)) +#define MATCH_Z2_MAX_EILINE(P) TERN0(HAS_Z2_MAX, DEFER4(MATCH_EILINE)(P, Z2_MAX_PIN)) +#define MATCH_Z2_MIN_EILINE(P) TERN0(HAS_Z2_MIN, DEFER4(MATCH_EILINE)(P, Z2_MIN_PIN)) +#define MATCH_Z3_MAX_EILINE(P) TERN0(HAS_Z3_MAX, DEFER4(MATCH_EILINE)(P, Z3_MAX_PIN)) +#define MATCH_Z3_MIN_EILINE(P) TERN0(HAS_Z3_MIN, DEFER4(MATCH_EILINE)(P, Z3_MIN_PIN)) +#define MATCH_Z4_MAX_EILINE(P) TERN0(HAS_Z4_MAX, DEFER4(MATCH_EILINE)(P, Z4_MAX_PIN)) +#define MATCH_Z4_MIN_EILINE(P) TERN0(HAS_Z4_MIN, DEFER4(MATCH_EILINE)(P, Z4_MIN_PIN)) +#define MATCH_Z_MIN_PROBE_EILINE(P) TERN0(HAS_Z_MIN_PROBE_PIN, DEFER4(MATCH_EILINE)(P, Z_MIN_PROBE_PIN)) + +#define AVAILABLE_EILINE(P) ( PIN_TO_EILINE(P) != -1 \ + && !MATCH_X_MAX_EILINE(P) && !MATCH_X_MIN_EILINE(P) \ + && !MATCH_Y_MAX_EILINE(P) && !MATCH_Y_MIN_EILINE(P) \ + && !MATCH_Z_MAX_EILINE(P) && !MATCH_Z_MIN_EILINE(P) \ + && !MATCH_I_MAX_EILINE(P) && !MATCH_I_MIN_EILINE(P) \ + && !MATCH_J_MAX_EILINE(P) && !MATCH_J_MIN_EILINE(P) \ + && !MATCH_K_MAX_EILINE(P) && !MATCH_K_MIN_EILINE(P) \ + && !MATCH_Z2_MAX_EILINE(P) && !MATCH_Z2_MIN_EILINE(P) \ + && !MATCH_Z3_MAX_EILINE(P) && !MATCH_Z3_MIN_EILINE(P) \ + && !MATCH_Z4_MAX_EILINE(P) && !MATCH_Z4_MIN_EILINE(P) \ + && !MATCH_Z_MIN_PROBE_EILINE(P) ) // One ISR for all EXT-Interrupts void endstop_ISR() { endstops.update(); } @@ -204,5 +162,37 @@ void setup_endstop_interrupts() { #error "Z_MIN_PROBE_PIN has no EXTINT line available." #endif _ATTACH(Z_MIN_PROBE_PIN); + #elif HAS_I_MAX + #if !AVAILABLE_EILINE(I_MAX_PIN) + #error "I_MAX_PIN has no EXTINT line available." + #endif + attachInterrupt(I_MAX_PIN, endstop_ISR, CHANGE); + #elif HAS_I_MIN + #if !AVAILABLE_EILINE(I_MIN_PIN) + #error "I_MIN_PIN has no EXTINT line available." + #endif + attachInterrupt(I_MIN_PIN, endstop_ISR, CHANGE); + #endif + #if HAS_J_MAX + #if !AVAILABLE_EILINE(J_MAX_PIN) + #error "J_MAX_PIN has no EXTINT line available." + #endif + attachInterrupt(J_MAX_PIN, endstop_ISR, CHANGE); + #elif HAS_J_MIN + #if !AVAILABLE_EILINE(J_MIN_PIN) + #error "J_MIN_PIN has no EXTINT line available." + #endif + attachInterrupt(J_MIN_PIN, endstop_ISR, CHANGE); + #endif + #if HAS_K_MAX + #if !AVAILABLE_EILINE(K_MAX_PIN) + #error "K_MAX_PIN has no EXTINT line available." + #endif + attachInterrupt(K_MAX_PIN, endstop_ISR, CHANGE); + #elif HAS_K_MIN + #if !AVAILABLE_EILINE(K_MIN_PIN) + #error "K_MIN_PIN has no EXTINT line available." + #endif + attachInterrupt(K_MIN_PIN, endstop_ISR, CHANGE); #endif } diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h index 2441c46eab0cc..02bee57ba3ac8 100644 --- a/Marlin/src/HAL/STM32/HAL.h +++ b/Marlin/src/HAL/STM32/HAL.h @@ -195,6 +195,7 @@ uint16_t HAL_adc_get_result(); #ifdef STM32F1xx #define JTAG_DISABLE() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_JTAGDISABLE) #define JTAGSWD_DISABLE() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_DISABLE) + #define JTAGSWD_RESET() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_RESET); // Reset: FULL SWD+JTAG #endif #define PLATFORM_M997_SUPPORT diff --git a/Marlin/src/HAL/STM32/HAL_SPI.cpp b/Marlin/src/HAL/STM32/HAL_SPI.cpp index 80347e115d553..bd36562de9ca1 100644 --- a/Marlin/src/HAL/STM32/HAL_SPI.cpp +++ b/Marlin/src/HAL/STM32/HAL_SPI.cpp @@ -163,11 +163,9 @@ static SPISettings spiConfig; } spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0); - #if ENABLED(CUSTOM_SPI_PINS) - SPI.setMISO(SD_MISO_PIN); - SPI.setMOSI(SD_MOSI_PIN); - SPI.setSCLK(SD_SCK_PIN); - #endif + SPI.setMISO(SD_MISO_PIN); + SPI.setMOSI(SD_MOSI_PIN); + SPI.setSCLK(SD_SCK_PIN); SPI.begin(); } diff --git a/Marlin/src/HAL/STM32/eeprom_bl24cxx.cpp b/Marlin/src/HAL/STM32/eeprom_bl24cxx.cpp new file mode 100644 index 0000000000000..165b3c6bab2e0 --- /dev/null +++ b/Marlin/src/HAL/STM32/eeprom_bl24cxx.cpp @@ -0,0 +1,82 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 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 . + * + */ +#ifdef STM32F1 + +/** + * PersistentStore for Arduino-style EEPROM interface + * with simple implementations supplied by Marlin. + */ + +#include "../../inc/MarlinConfig.h" + +#if ENABLED(IIC_BL24CXX_EEPROM) + +#include "../shared/eeprom_if.h" +#include "../shared/eeprom_api.h" + +// +// PersistentStore +// + +#ifndef MARLIN_EEPROM_SIZE + #error "MARLIN_EEPROM_SIZE is required for IIC_BL24CXX_EEPROM." +#endif + +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } + +bool PersistentStore::access_start() { eeprom_init(); return true; } +bool PersistentStore::access_finish() { return true; } + +bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + uint16_t written = 0; + while (size--) { + uint8_t v = *value; + uint8_t * const p = (uint8_t * const)pos; + if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed! + eeprom_write_byte(p, v); + if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes + if (eeprom_read_byte(p) != v) { + SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); + return true; + } + } + crc16(crc, &v, 1); + pos++; + value++; + } + return false; +} + +bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { + do { + uint8_t * const p = (uint8_t * const)pos; + uint8_t c = eeprom_read_byte(p); + if (writing) *value = c; + crc16(crc, &c, 1); + pos++; + value++; + } while (--size); + return false; +} + +#endif // IIC_BL24CXX_EEPROM +#endif // STM32F1 diff --git a/Marlin/src/HAL/STM32/eeprom_flash.cpp b/Marlin/src/HAL/STM32/eeprom_flash.cpp index 5862090f1ba4f..dfeae9e9e5e64 100644 --- a/Marlin/src/HAL/STM32/eeprom_flash.cpp +++ b/Marlin/src/HAL/STM32/eeprom_flash.cpp @@ -28,6 +28,10 @@ #include "../shared/eeprom_api.h" +// Better: "utility/stm32_eeprom.h", but only after updating stm32duino to 2.0.0 +// Use EEPROM.h for compatibility, for now. +#include + /** * The STM32 HAL supports chips that deal with "pages" and some with "sectors" and some that * even have multiple "banks" of flash. diff --git a/Marlin/src/HAL/STM32/eeprom_if_iic.cpp b/Marlin/src/HAL/STM32/eeprom_if_iic.cpp new file mode 100644 index 0000000000000..5c6cc802a6d0f --- /dev/null +++ b/Marlin/src/HAL/STM32/eeprom_if_iic.cpp @@ -0,0 +1,54 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2020 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 . + * + */ + +/** + * Platform-independent Arduino functions for I2C EEPROM. + * Enable USE_SHARED_EEPROM if not supplied by the framework. + */ + +#ifdef STM32F1 + +#include "../../inc/MarlinConfig.h" + +#if ENABLED(IIC_BL24CXX_EEPROM) + +#include "../../libs/BL24CXX.h" +#include "../shared/eeprom_if.h" + +void eeprom_init() { BL24CXX::init(); } + +// ------------------------ +// Public functions +// ------------------------ + +void eeprom_write_byte(uint8_t *pos, uint8_t value) { + const unsigned eeprom_address = (unsigned)pos; + return BL24CXX::writeOneByte(eeprom_address, value); +} + +uint8_t eeprom_read_byte(uint8_t *pos) { + const unsigned eeprom_address = (unsigned)pos; + return BL24CXX::readOneByte(eeprom_address); +} + +#endif // IIC_BL24CXX_EEPROM +#endif // STM32F1 diff --git a/Marlin/src/HAL/STM32/endstop_interrupts.h b/Marlin/src/HAL/STM32/endstop_interrupts.h index fdff8cc644cd7..90870881fe665 100644 --- a/Marlin/src/HAL/STM32/endstop_interrupts.h +++ b/Marlin/src/HAL/STM32/endstop_interrupts.h @@ -46,4 +46,10 @@ void setup_endstop_interrupts() { TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); + TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN)); + TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN)); + TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN)); + TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN)); + TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN)); + TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN)); } diff --git a/Marlin/src/HAL/STM32/inc/Conditionals_adv.h b/Marlin/src/HAL/STM32/inc/Conditionals_adv.h index 9c9a7014c7b44..451c94f25d1f8 100644 --- a/Marlin/src/HAL/STM32/inc/Conditionals_adv.h +++ b/Marlin/src/HAL/STM32/inc/Conditionals_adv.h @@ -21,7 +21,7 @@ */ #pragma once -#if defined(USBD_USE_CDC_MSC) && DISABLED(NO_SD_HOST_DRIVE) +#if BOTH(SDSUPPORT, USBD_USE_CDC_MSC) && DISABLED(NO_SD_HOST_DRIVE) #define HAS_SD_HOST_DRIVE 1 #endif @@ -30,3 +30,6 @@ #undef F_CPU #define F_CPU BOARD_F_CPU #endif + +// The Sensitive Pins array is not optimizable +#define RUNTIME_ONLY_ANALOG_TO_DIGITAL diff --git a/Marlin/src/HAL/STM32/msc_sd.cpp b/Marlin/src/HAL/STM32/msc_sd.cpp index cbfb837875c83..64f2533002d87 100644 --- a/Marlin/src/HAL/STM32/msc_sd.cpp +++ b/Marlin/src/HAL/STM32/msc_sd.cpp @@ -33,9 +33,9 @@ class Sd2CardUSBMscHandler : public USBMscHandler { DiskIODriver* diskIODriver() { #if ENABLED(MULTI_VOLUME) #if SHARED_VOLUME_IS(SD_ONBOARD) - return &card.media_sd_spi; + return &card.media_driver_sdcard; #elif SHARED_VOLUME_IS(USB_FLASH_DRIVE) - return &card.media_usbFlashDrive; + return &card.media_driver_usbFlash; #endif #else return card.diskIODriver(); diff --git a/Marlin/src/HAL/STM32/tft/tft_spi.cpp b/Marlin/src/HAL/STM32/tft/tft_spi.cpp index 32af67d158c41..6bfce81f1a539 100644 --- a/Marlin/src/HAL/STM32/tft/tft_spi.cpp +++ b/Marlin/src/HAL/STM32/tft/tft_spi.cpp @@ -125,12 +125,20 @@ void TFT_SPI::DataTransferBegin(uint16_t DataSize) { WRITE(TFT_CS_PIN, LOW); } +#ifdef TFT_DEFAULT_DRIVER + #include "../../../lcd/tft_io/tft_ids.h" +#endif + uint32_t TFT_SPI::GetID() { uint32_t id; id = ReadID(LCD_READ_ID); - - if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) + if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) { id = ReadID(LCD_READ_ID4); + #ifdef TFT_DEFAULT_DRIVER + if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) + id = TFT_DEFAULT_DRIVER; + #endif + } return id; } diff --git a/Marlin/src/HAL/STM32/tft/xpt2046.h b/Marlin/src/HAL/STM32/tft/xpt2046.h index 5b8acf4b87afc..2cff3e29d05be 100644 --- a/Marlin/src/HAL/STM32/tft/xpt2046.h +++ b/Marlin/src/HAL/STM32/tft/xpt2046.h @@ -56,7 +56,7 @@ enum XPTCoordinate : uint8_t { XPT2046_Z2 = 0x40 | XPT2046_CONTROL | XPT2046_DFR_MODE, }; -#if !defined(XPT2046_Z1_THRESHOLD) +#ifndef XPT2046_Z1_THRESHOLD #define XPT2046_Z1_THRESHOLD 10 #endif diff --git a/Marlin/src/HAL/STM32F1/MarlinSerial.cpp b/Marlin/src/HAL/STM32F1/MarlinSerial.cpp index fa8bb7eaa8022..6dabcde51ead6 100644 --- a/Marlin/src/HAL/STM32F1/MarlinSerial.cpp +++ b/Marlin/src/HAL/STM32F1/MarlinSerial.cpp @@ -167,6 +167,15 @@ constexpr bool IsSerialClassAllowed(const HardwareSerial&) { return false; } #if AXIS_HAS_HW_SERIAL(Z4) CHECK_AXIS_SERIAL(Z4); #endif +#if AXIS_HAS_HW_SERIAL(I) + CHECK_AXIS_SERIAL(I); +#endif +#if AXIS_HAS_HW_SERIAL(J) + CHECK_AXIS_SERIAL(J); +#endif +#if AXIS_HAS_HW_SERIAL(K) + CHECK_AXIS_SERIAL(K); +#endif #if AXIS_HAS_HW_SERIAL(E0) CHECK_AXIS_SERIAL(E0); #endif diff --git a/Marlin/src/HAL/STM32F1/build_flags.py b/Marlin/src/HAL/STM32F1/build_flags.py index c51fd4fa58fd1..d0848d1c64383 100755 --- a/Marlin/src/HAL/STM32F1/build_flags.py +++ b/Marlin/src/HAL/STM32F1/build_flags.py @@ -11,6 +11,7 @@ "-fsigned-char", "-fno-move-loop-invariants", "-fno-strict-aliasing", + "-fsingle-precision-constant", "--specs=nano.specs", "--specs=nosys.specs", diff --git a/Marlin/src/HAL/STM32F1/endstop_interrupts.h b/Marlin/src/HAL/STM32F1/endstop_interrupts.h index bcb07d991d75a..4d7edb9496c12 100644 --- a/Marlin/src/HAL/STM32F1/endstop_interrupts.h +++ b/Marlin/src/HAL/STM32F1/endstop_interrupts.h @@ -71,4 +71,10 @@ void setup_endstop_interrupts() { TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); + TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN)); + TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN)); + TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN)); + TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN)); + TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN)); + TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN)); } diff --git a/Marlin/src/HAL/STM32F1/onboard_sd.cpp b/Marlin/src/HAL/STM32F1/onboard_sd.cpp index 6092aea320544..e26947145d0ed 100644 --- a/Marlin/src/HAL/STM32F1/onboard_sd.cpp +++ b/Marlin/src/HAL/STM32F1/onboard_sd.cpp @@ -38,8 +38,8 @@ #define SPI_CLOCK_MAX SPI_BAUD_PCLK_DIV_2 #endif -#define CS_LOW() WRITE(ONBOARD_SD_CS_PIN, LOW) /* Set OnboardSPI cs low */ -#define CS_HIGH() WRITE(ONBOARD_SD_CS_PIN, HIGH) /* Set OnboardSPI cs high */ +#define CS_LOW() WRITE(ONBOARD_SD_CS_PIN, LOW) // Set OnboardSPI cs low +#define CS_HIGH() WRITE(ONBOARD_SD_CS_PIN, HIGH) // Set OnboardSPI cs high #define FCLK_FAST() ONBOARD_SD_SPI.setClockDivider(SPI_CLOCK_MAX) #define FCLK_SLOW() ONBOARD_SD_SPI.setClockDivider(SPI_BAUD_PCLK_DIV_256) @@ -49,32 +49,32 @@ ---------------------------------------------------------------------------*/ /* MMC/SD command */ -#define CMD0 (0) /* GO_IDLE_STATE */ -#define CMD1 (1) /* SEND_OP_COND (MMC) */ -#define ACMD41 (0x80+41) /* SEND_OP_COND (SDC) */ -#define CMD8 (8) /* SEND_IF_COND */ -#define CMD9 (9) /* SEND_CSD */ -#define CMD10 (10) /* SEND_CID */ -#define CMD12 (12) /* STOP_TRANSMISSION */ -#define ACMD13 (0x80+13) /* SD_STATUS (SDC) */ -#define CMD16 (16) /* SET_BLOCKLEN */ -#define CMD17 (17) /* READ_SINGLE_BLOCK */ -#define CMD18 (18) /* READ_MULTIPLE_BLOCK */ -#define CMD23 (23) /* SET_BLOCK_COUNT (MMC) */ -#define ACMD23 (0x80+23) /* SET_WR_BLK_ERASE_COUNT (SDC) */ -#define CMD24 (24) /* WRITE_BLOCK */ -#define CMD25 (25) /* WRITE_MULTIPLE_BLOCK */ -#define CMD32 (32) /* ERASE_ER_BLK_START */ -#define CMD33 (33) /* ERASE_ER_BLK_END */ -#define CMD38 (38) /* ERASE */ -#define CMD48 (48) /* READ_EXTR_SINGLE */ -#define CMD49 (49) /* WRITE_EXTR_SINGLE */ -#define CMD55 (55) /* APP_CMD */ -#define CMD58 (58) /* READ_OCR */ - -static volatile DSTATUS Stat = STA_NOINIT; /* Physical drive status */ +#define CMD0 (0) // GO_IDLE_STATE +#define CMD1 (1) // SEND_OP_COND (MMC) +#define ACMD41 (0x80+41) // SEND_OP_COND (SDC) +#define CMD8 (8) // SEND_IF_COND +#define CMD9 (9) // SEND_CSD +#define CMD10 (10) // SEND_CID +#define CMD12 (12) // STOP_TRANSMISSION +#define ACMD13 (0x80+13) // SD_STATUS (SDC) +#define CMD16 (16) // SET_BLOCKLEN +#define CMD17 (17) // READ_SINGLE_BLOCK +#define CMD18 (18) // READ_MULTIPLE_BLOCK +#define CMD23 (23) // SET_BLOCK_COUNT (MMC) +#define ACMD23 (0x80+23) // SET_WR_BLK_ERASE_COUNT (SDC) +#define CMD24 (24) // WRITE_BLOCK +#define CMD25 (25) // WRITE_MULTIPLE_BLOCK +#define CMD32 (32) // ERASE_ER_BLK_START +#define CMD33 (33) // ERASE_ER_BLK_END +#define CMD38 (38) // ERASE +#define CMD48 (48) // READ_EXTR_SINGLE +#define CMD49 (49) // WRITE_EXTR_SINGLE +#define CMD55 (55) // APP_CMD +#define CMD58 (58) // READ_OCR + +static volatile DSTATUS Stat = STA_NOINIT; // Physical drive status static volatile UINT timeout; -static BYTE CardType; /* Card type flags */ +static BYTE CardType; // Card type flags /*-----------------------------------------------------------------------*/ /* Send/Receive data to the MMC (Platform dependent) */ @@ -82,7 +82,7 @@ static BYTE CardType; /* Card type flags */ /* Exchange a byte */ static BYTE xchg_spi ( - BYTE dat /* Data to send */ + BYTE dat // Data to send ) { BYTE returnByte = ONBOARD_SD_SPI.transfer(dat); return returnByte; @@ -90,18 +90,18 @@ static BYTE xchg_spi ( /* Receive multiple byte */ static void rcvr_spi_multi ( - BYTE *buff, /* Pointer to data buffer */ - UINT btr /* Number of bytes to receive (16, 64 or 512) */ + BYTE *buff, // Pointer to data buffer + UINT btr // Number of bytes to receive (16, 64 or 512) ) { ONBOARD_SD_SPI.dmaTransfer(0, const_cast(buff), btr); } #if _DISKIO_WRITE - /* Send multiple bytes */ + // Send multiple bytes static void xmit_spi_multi ( - const BYTE *buff, /* Pointer to the data */ - UINT btx /* Number of bytes to send (multiple of 16) */ + const BYTE *buff, // Pointer to the data + UINT btx // Number of bytes to send (multiple of 16) ) { ONBOARD_SD_SPI.dmaSend(const_cast(buff), btx); } @@ -112,16 +112,15 @@ static void rcvr_spi_multi ( /* Wait for card ready */ /*-----------------------------------------------------------------------*/ -static int wait_ready ( /* 1:Ready, 0:Timeout */ - UINT wt /* Timeout [ms] */ +static int wait_ready ( // 1:Ready, 0:Timeout + UINT wt // Timeout [ms] ) { BYTE d; - timeout = millis() + wt; do { d = xchg_spi(0xFF); - /* This loop takes a while. Insert rot_rdq() here for multitask environment. */ - } while (d != 0xFF && (timeout > millis())); /* Wait for card goes ready or timeout */ + // This loop takes a while. Insert rot_rdq() here for multitask environment. + } while (d != 0xFF && (timeout > millis())); // Wait for card goes ready or timeout return (d == 0xFF) ? 1 : 0; } @@ -131,21 +130,21 @@ static int wait_ready ( /* 1:Ready, 0:Timeout */ /*-----------------------------------------------------------------------*/ static void deselect() { - CS_HIGH(); /* CS = H */ - xchg_spi(0xFF); /* Dummy clock (force DO hi-z for multiple slave SPI) */ + CS_HIGH(); // CS = H + xchg_spi(0xFF); // Dummy clock (force DO hi-z for multiple slave SPI) } /*-----------------------------------------------------------------------*/ /* Select card and wait for ready */ /*-----------------------------------------------------------------------*/ -static int select() { /* 1:OK, 0:Timeout */ - CS_LOW(); /* CS = L */ - xchg_spi(0xFF); /* Dummy clock (force DO enabled) */ +static int select() { // 1:OK, 0:Timeout + CS_LOW(); // CS = L + xchg_spi(0xFF); // Dummy clock (force DO enabled) - if (wait_ready(500)) return 1; /* Leading busy check: Wait for card ready */ + if (wait_ready(500)) return 1; // Leading busy check: Wait for card ready - deselect(); /* Timeout */ + deselect(); // Timeout return 0; } @@ -153,16 +152,18 @@ static int select() { /* 1:OK, 0:Timeout */ /* Control SPI module (Platform dependent) */ /*-----------------------------------------------------------------------*/ -static void power_on() { /* Enable SSP module and attach it to I/O pads */ +// Enable SSP module and attach it to I/O pads +static void sd_power_on() { ONBOARD_SD_SPI.setModule(ONBOARD_SPI_DEVICE); ONBOARD_SD_SPI.begin(); ONBOARD_SD_SPI.setBitOrder(MSBFIRST); ONBOARD_SD_SPI.setDataMode(SPI_MODE0); - OUT_WRITE(ONBOARD_SD_CS_PIN, HIGH); /* Set CS# high */ + OUT_WRITE(ONBOARD_SD_CS_PIN, HIGH); // Set CS# high } -static void power_off() { /* Disable SPI function */ - select(); /* Wait for card ready */ +// Disable SPI function +static void sd_power_off() { + select(); // Wait for card ready deselect(); } @@ -170,23 +171,23 @@ static void power_off() { /* Disable SPI function */ /* Receive a data packet from the MMC */ /*-----------------------------------------------------------------------*/ -static int rcvr_datablock ( /* 1:OK, 0:Error */ - BYTE *buff, /* Data buffer */ - UINT btr /* Data block length (byte) */ +static int rcvr_datablock ( // 1:OK, 0:Error + BYTE *buff, // Data buffer + UINT btr // Data block length (byte) ) { BYTE token; timeout = millis() + 200; - do { /* Wait for DataStart token in timeout of 200ms */ + do { // Wait for DataStart token in timeout of 200ms token = xchg_spi(0xFF); - /* This loop will take a while. Insert rot_rdq() here for multitask environment. */ + // This loop will take a while. Insert rot_rdq() here for multitask environment. } while ((token == 0xFF) && (timeout > millis())); - if (token != 0xFE) return 0; /* Function fails if invalid DataStart token or timeout */ + if (token != 0xFE) return 0; // Function fails if invalid DataStart token or timeout - rcvr_spi_multi(buff, btr); /* Store trailing data to the buffer */ - xchg_spi(0xFF); xchg_spi(0xFF); /* Discard CRC */ + rcvr_spi_multi(buff, btr); // Store trailing data to the buffer + xchg_spi(0xFF); xchg_spi(0xFF); // Discard CRC - return 1; /* Function succeeded */ + return 1; // Function succeeded } /*-----------------------------------------------------------------------*/ @@ -195,25 +196,25 @@ static int rcvr_datablock ( /* 1:OK, 0:Error */ #if _DISKIO_WRITE - static int xmit_datablock ( /* 1:OK, 0:Failed */ - const BYTE *buff, /* Ponter to 512 byte data to be sent */ - BYTE token /* Token */ + static int xmit_datablock( // 1:OK, 0:Failed + const BYTE *buff, // Pointer to 512 byte data to be sent + BYTE token // Token ) { BYTE resp; - if (!wait_ready(500)) return 0; /* Leading busy check: Wait for card ready to accept data block */ + if (!wait_ready(500)) return 0; // Leading busy check: Wait for card ready to accept data block - xchg_spi(token); /* Send token */ - if (token == 0xFD) return 1; /* Do not send data if token is StopTran */ + xchg_spi(token); // Send token + if (token == 0xFD) return 1; // Do not send data if token is StopTran - xmit_spi_multi(buff, 512); /* Data */ - xchg_spi(0xFF); xchg_spi(0xFF); /* Dummy CRC */ + xmit_spi_multi(buff, 512); // Data + xchg_spi(0xFF); xchg_spi(0xFF); // Dummy CRC - resp = xchg_spi(0xFF); /* Receive data resp */ + resp = xchg_spi(0xFF); // Receive data resp - return (resp & 0x1F) == 0x05 ? 1 : 0; /* Data was accepted or not */ + return (resp & 0x1F) == 0x05 ? 1 : 0; // Data was accepted or not - /* Busy check is done at next transmission */ + // Busy check is done at next transmission } #endif // _DISKIO_WRITE @@ -222,43 +223,43 @@ static int rcvr_datablock ( /* 1:OK, 0:Error */ /* Send a command packet to the MMC */ /*-----------------------------------------------------------------------*/ -static BYTE send_cmd ( /* Return value: R1 resp (bit7==1:Failed to send) */ - BYTE cmd, /* Command index */ - DWORD arg /* Argument */ +static BYTE send_cmd( // Return value: R1 resp (bit7==1:Failed to send) + BYTE cmd, // Command index + DWORD arg // Argument ) { BYTE n, res; - if (cmd & 0x80) { /* Send a CMD55 prior to ACMD */ + if (cmd & 0x80) { // Send a CMD55 prior to ACMD cmd &= 0x7F; res = send_cmd(CMD55, 0); if (res > 1) return res; } - /* Select the card and wait for ready except to stop multiple block read */ + // Select the card and wait for ready except to stop multiple block read if (cmd != CMD12) { deselect(); if (!select()) return 0xFF; } - /* Send command packet */ - xchg_spi(0x40 | cmd); /* Start + command index */ - xchg_spi((BYTE)(arg >> 24)); /* Argument[31..24] */ - xchg_spi((BYTE)(arg >> 16)); /* Argument[23..16] */ - xchg_spi((BYTE)(arg >> 8)); /* Argument[15..8] */ - xchg_spi((BYTE)arg); /* Argument[7..0] */ - n = 0x01; /* Dummy CRC + Stop */ - if (cmd == CMD0) n = 0x95; /* Valid CRC for CMD0(0) */ - if (cmd == CMD8) n = 0x87; /* Valid CRC for CMD8(0x1AA) */ + // Send command packet + xchg_spi(0x40 | cmd); // Start + command index + xchg_spi((BYTE)(arg >> 24)); // Argument[31..24] + xchg_spi((BYTE)(arg >> 16)); // Argument[23..16] + xchg_spi((BYTE)(arg >> 8)); // Argument[15..8] + xchg_spi((BYTE)arg); // Argument[7..0] + n = 0x01; // Dummy CRC + Stop + if (cmd == CMD0) n = 0x95; // Valid CRC for CMD0(0) + if (cmd == CMD8) n = 0x87; // Valid CRC for CMD8(0x1AA) xchg_spi(n); - /* Receive command resp */ - if (cmd == CMD12) xchg_spi(0xFF); /* Diacard following one byte when CMD12 */ - n = 10; /* Wait for response (10 bytes max) */ + // Receive command response + if (cmd == CMD12) xchg_spi(0xFF); // Discard the following byte when CMD12 + n = 10; // Wait for response (10 bytes max) do res = xchg_spi(0xFF); while ((res & 0x80) && --n); - return res; /* Return received response */ + return res; // Return received response } /*-------------------------------------------------------------------------- @@ -270,49 +271,52 @@ static BYTE send_cmd ( /* Return value: R1 resp (bit7==1:Failed to send) */ /*-----------------------------------------------------------------------*/ DSTATUS disk_initialize ( - BYTE drv /* Physical drive number (0) */ + BYTE drv // Physical drive number (0) ) { BYTE n, cmd, ty, ocr[4]; - if (drv) return STA_NOINIT; /* Supports only drive 0 */ - power_on(); /* Initialize SPI */ + if (drv) return STA_NOINIT; // Supports only drive 0 + sd_power_on(); // Initialize SPI - if (Stat & STA_NODISK) return Stat; /* Is a card existing in the soket? */ + if (Stat & STA_NODISK) return Stat; // Is a card existing in the soket? FCLK_SLOW(); - for (n = 10; n; n--) xchg_spi(0xFF); /* Send 80 dummy clocks */ + for (n = 10; n; n--) xchg_spi(0xFF); // Send 80 dummy clocks ty = 0; - if (send_cmd(CMD0, 0) == 1) { /* Put the card SPI state */ - timeout = millis() + 1000; /* Initialization timeout = 1 sec */ - if (send_cmd(CMD8, 0x1AA) == 1) { /* Is the catd SDv2? */ - for (n = 0; n < 4; n++) ocr[n] = xchg_spi(0xFF); /* Get 32 bit return value of R7 resp */ - if (ocr[2] == 0x01 && ocr[3] == 0xAA) { /* Does the card support 2.7-3.6V? */ - while ((timeout > millis()) && send_cmd(ACMD41, 1UL << 30)) ; /* Wait for end of initialization with ACMD41(HCS) */ - if ((timeout > millis()) && send_cmd(CMD58, 0) == 0) { /* Check CCS bit in the OCR */ + if (send_cmd(CMD0, 0) == 1) { // Put the card SPI state + timeout = millis() + 1000; // Initialization timeout = 1 sec + if (send_cmd(CMD8, 0x1AA) == 1) { // Is the catd SDv2? + for (n = 0; n < 4; n++) ocr[n] = xchg_spi(0xFF); // Get 32 bit return value of R7 resp + if (ocr[2] == 0x01 && ocr[3] == 0xAA) { // Does the card support 2.7-3.6V? + while ((timeout > millis()) && send_cmd(ACMD41, 1UL << 30)); // Wait for end of initialization with ACMD41(HCS) + if ((timeout > millis()) && send_cmd(CMD58, 0) == 0) { // Check CCS bit in the OCR for (n = 0; n < 4; n++) ocr[n] = xchg_spi(0xFF); - ty = (ocr[0] & 0x40) ? CT_SD2 | CT_BLOCK : CT_SD2; /* Check if the card is SDv2 */ + ty = (ocr[0] & 0x40) ? CT_SD2 | CT_BLOCK : CT_SD2; // Check if the card is SDv2 } } - } else { /* Not an SDv2 card */ - if (send_cmd(ACMD41, 0) <= 1) { /* SDv1 or MMCv3? */ - ty = CT_SD1; cmd = ACMD41; /* SDv1 (ACMD41(0)) */ - } else { - ty = CT_MMC; cmd = CMD1; /* MMCv3 (CMD1(0)) */ + } + else { // Not an SDv2 card + if (send_cmd(ACMD41, 0) <= 1) { // SDv1 or MMCv3? + ty = CT_SD1; cmd = ACMD41; // SDv1 (ACMD41(0)) + } + else { + ty = CT_MMC; cmd = CMD1; // MMCv3 (CMD1(0)) } - while ((timeout > millis()) && send_cmd(cmd, 0)) ; /* Wait for the card leaves idle state */ - if (!(timeout > millis()) || send_cmd(CMD16, 512) != 0) /* Set block length: 512 */ + while ((timeout > millis()) && send_cmd(cmd, 0)); // Wait for the card leaves idle state + if (!(timeout > millis()) || send_cmd(CMD16, 512) != 0) // Set block length: 512 ty = 0; } } - CardType = ty; /* Card type */ + CardType = ty; // Card type deselect(); - if (ty) { /* OK */ - FCLK_FAST(); /* Set fast clock */ - Stat &= ~STA_NOINIT; /* Clear STA_NOINIT flag */ - } else { /* Failed */ - power_off(); + if (ty) { // OK + FCLK_FAST(); // Set fast clock + Stat &= ~STA_NOINIT; // Clear STA_NOINIT flag + } + else { // Failed + sd_power_off(); Stat = STA_NOINIT; } @@ -324,10 +328,10 @@ DSTATUS disk_initialize ( /*-----------------------------------------------------------------------*/ DSTATUS disk_status ( - BYTE drv /* Physical drive number (0) */ + BYTE drv // Physical drive number (0) ) { - if (drv) return STA_NOINIT; /* Supports only drive 0 */ - return Stat; /* Return disk status */ + if (drv) return STA_NOINIT; // Supports only drive 0 + return Stat; // Return disk status } /*-----------------------------------------------------------------------*/ @@ -335,28 +339,28 @@ DSTATUS disk_status ( /*-----------------------------------------------------------------------*/ DRESULT disk_read ( - BYTE drv, /* Physical drive number (0) */ - BYTE *buff, /* Pointer to the data buffer to store read data */ - DWORD sector, /* Start sector number (LBA) */ - UINT count /* Number of sectors to read (1..128) */ + BYTE drv, // Physical drive number (0) + BYTE *buff, // Pointer to the data buffer to store read data + DWORD sector, // Start sector number (LBA) + UINT count // Number of sectors to read (1..128) ) { BYTE cmd; - if (drv || !count) return RES_PARERR; /* Check parameter */ - if (Stat & STA_NOINIT) return RES_NOTRDY; /* Check if drive is ready */ - if (!(CardType & CT_BLOCK)) sector *= 512; /* LBA ot BA conversion (byte addressing cards) */ + if (drv || !count) return RES_PARERR; // Check parameter + if (Stat & STA_NOINIT) return RES_NOTRDY; // Check if drive is ready + if (!(CardType & CT_BLOCK)) sector *= 512; // LBA ot BA conversion (byte addressing cards) FCLK_FAST(); - cmd = count > 1 ? CMD18 : CMD17; /* READ_MULTIPLE_BLOCK : READ_SINGLE_BLOCK */ + cmd = count > 1 ? CMD18 : CMD17; // READ_MULTIPLE_BLOCK : READ_SINGLE_BLOCK if (send_cmd(cmd, sector) == 0) { do { if (!rcvr_datablock(buff, 512)) break; buff += 512; } while (--count); - if (cmd == CMD18) send_cmd(CMD12, 0); /* STOP_TRANSMISSION */ + if (cmd == CMD18) send_cmd(CMD12, 0); // STOP_TRANSMISSION } deselect(); - return count ? RES_ERROR : RES_OK; /* Return result */ + return count ? RES_ERROR : RES_OK; // Return result } /*-----------------------------------------------------------------------*/ @@ -366,36 +370,36 @@ DRESULT disk_read ( #if _DISKIO_WRITE DRESULT disk_write( - BYTE drv, /* Physical drive number (0) */ - const BYTE *buff, /* Ponter to the data to write */ - DWORD sector, /* Start sector number (LBA) */ - UINT count /* Number of sectors to write (1..128) */ + BYTE drv, // Physical drive number (0) + const BYTE *buff, // Pointer to the data to write + DWORD sector, // Start sector number (LBA) + UINT count // Number of sectors to write (1..128) ) { - if (drv || !count) return RES_PARERR; /* Check parameter */ - if (Stat & STA_NOINIT) return RES_NOTRDY; /* Check drive status */ - if (Stat & STA_PROTECT) return RES_WRPRT; /* Check write protect */ + if (drv || !count) return RES_PARERR; // Check parameter + if (Stat & STA_NOINIT) return RES_NOTRDY; // Check drive status + if (Stat & STA_PROTECT) return RES_WRPRT; // Check write protect FCLK_FAST(); - if (!(CardType & CT_BLOCK)) sector *= 512; /* LBA ==> BA conversion (byte addressing cards) */ + if (!(CardType & CT_BLOCK)) sector *= 512; // LBA ==> BA conversion (byte addressing cards) - if (count == 1) { /* Single sector write */ - if ((send_cmd(CMD24, sector) == 0) /* WRITE_BLOCK */ + if (count == 1) { // Single sector write + if ((send_cmd(CMD24, sector) == 0) // WRITE_BLOCK && xmit_datablock(buff, 0xFE)) { count = 0; } } - else { /* Multiple sector write */ - if (CardType & CT_SDC) send_cmd(ACMD23, count); /* Predefine number of sectors */ - if (send_cmd(CMD25, sector) == 0) { /* WRITE_MULTIPLE_BLOCK */ + else { // Multiple sector write + if (CardType & CT_SDC) send_cmd(ACMD23, count); // Predefine number of sectors + if (send_cmd(CMD25, sector) == 0) { // WRITE_MULTIPLE_BLOCK do { if (!xmit_datablock(buff, 0xFC)) break; buff += 512; } while (--count); - if (!xmit_datablock(0, 0xFD)) count = 1; /* STOP_TRAN token */ + if (!xmit_datablock(0, 0xFD)) count = 1; // STOP_TRAN token } } deselect(); - return count ? RES_ERROR : RES_OK; /* Return result */ + return count ? RES_ERROR : RES_OK; // Return result } #endif // _DISKIO_WRITE @@ -407,9 +411,9 @@ DRESULT disk_read ( #if _DISKIO_IOCTL DRESULT disk_ioctl ( - BYTE drv, /* Physical drive number (0) */ - BYTE cmd, /* Control command code */ - void *buff /* Pointer to the conrtol data */ + BYTE drv, // Physical drive number (0) + BYTE cmd, // Control command code + void *buff // Pointer to the conrtol data ) { DRESULT res; BYTE n, csd[16], *ptr = (BYTE *)buff; @@ -420,22 +424,23 @@ DRESULT disk_read ( UINT dc; #endif - if (drv) return RES_PARERR; /* Check parameter */ - if (Stat & STA_NOINIT) return RES_NOTRDY; /* Check if drive is ready */ + if (drv) return RES_PARERR; // Check parameter + if (Stat & STA_NOINIT) return RES_NOTRDY; // Check if drive is ready res = RES_ERROR; FCLK_FAST(); switch (cmd) { - case CTRL_SYNC: /* Wait for end of internal write process of the drive */ + case CTRL_SYNC: // Wait for end of internal write process of the drive if (select()) res = RES_OK; break; - case GET_SECTOR_COUNT: /* Get drive capacity in unit of sector (DWORD) */ + case GET_SECTOR_COUNT: // Get drive capacity in unit of sector (DWORD) if ((send_cmd(CMD9, 0) == 0) && rcvr_datablock(csd, 16)) { - if ((csd[0] >> 6) == 1) { /* SDC ver 2.00 */ + if ((csd[0] >> 6) == 1) { // SDC ver 2.00 csize = csd[9] + ((WORD)csd[8] << 8) + ((DWORD)(csd[7] & 63) << 16) + 1; *(DWORD*)buff = csize << 10; - } else { /* SDC ver 1.XX or MMC ver 3 */ + } + else { // SDC ver 1.XX or MMC ver 3 n = (csd[5] & 15) + ((csd[10] & 128) >> 7) + ((csd[9] & 3) << 1) + 2; csize = (csd[8] >> 6) + ((WORD)csd[7] << 2) + ((WORD)(csd[6] & 3) << 10) + 1; *(DWORD*)buff = csize << (n - 9); @@ -444,21 +449,23 @@ DRESULT disk_read ( } break; - case GET_BLOCK_SIZE: /* Get erase block size in unit of sector (DWORD) */ - if (CardType & CT_SD2) { /* SDC ver 2.00 */ - if (send_cmd(ACMD13, 0) == 0) { /* Read SD status */ + case GET_BLOCK_SIZE: // Get erase block size in unit of sector (DWORD) + if (CardType & CT_SD2) { // SDC ver 2.00 + if (send_cmd(ACMD13, 0) == 0) { // Read SD status xchg_spi(0xFF); - if (rcvr_datablock(csd, 16)) { /* Read partial block */ - for (n = 64 - 16; n; n--) xchg_spi(0xFF); /* Purge trailing data */ + if (rcvr_datablock(csd, 16)) { // Read partial block + for (n = 64 - 16; n; n--) xchg_spi(0xFF); // Purge trailing data *(DWORD*)buff = 16UL << (csd[10] >> 4); res = RES_OK; } } - } else { /* SDC ver 1.XX or MMC */ - if ((send_cmd(CMD9, 0) == 0) && rcvr_datablock(csd, 16)) { /* Read CSD */ - if (CardType & CT_SD1) { /* SDC ver 1.XX */ + } + else { // SDC ver 1.XX or MMC + if ((send_cmd(CMD9, 0) == 0) && rcvr_datablock(csd, 16)) { // Read CSD + if (CardType & CT_SD1) { // SDC ver 1.XX *(DWORD*)buff = (((csd[10] & 63) << 1) + ((WORD)(csd[11] & 128) >> 7) + 1) << ((csd[13] >> 6) - 1); - } else { /* MMC */ + } + else { // MMC *(DWORD*)buff = ((WORD)((csd[10] & 124) >> 2) + 1) * (((csd[11] & 3) << 3) + ((csd[11] & 224) >> 5) + 1); } res = RES_OK; @@ -466,47 +473,47 @@ DRESULT disk_read ( } break; - case CTRL_TRIM: /* Erase a block of sectors (used when _USE_TRIM in ffconf.h is 1) */ - if (!(CardType & CT_SDC)) break; /* Check if the card is SDC */ - if (disk_ioctl(drv, MMC_GET_CSD, csd)) break; /* Get CSD */ - if (!(csd[0] >> 6) && !(csd[10] & 0x40)) break; /* Check if sector erase can be applied to the card */ - dp = (DWORD *)buff; st = dp[0]; ed = dp[1]; /* Load sector block */ + case CTRL_TRIM: // Erase a block of sectors (used when _USE_TRIM in ffconf.h is 1) + if (!(CardType & CT_SDC)) break; // Check if the card is SDC + if (disk_ioctl(drv, MMC_GET_CSD, csd)) break; // Get CSD + if (!(csd[0] >> 6) && !(csd[10] & 0x40)) break; // Check if sector erase can be applied to the card + dp = (DWORD *)buff; st = dp[0]; ed = dp[1]; // Load sector block if (!(CardType & CT_BLOCK)) { st *= 512; ed *= 512; } - if (send_cmd(CMD32, st) == 0 && send_cmd(CMD33, ed) == 0 && send_cmd(CMD38, 0) == 0 && wait_ready(30000)) { /* Erase sector block */ - res = RES_OK; /* FatFs does not check result of this command */ + if (send_cmd(CMD32, st) == 0 && send_cmd(CMD33, ed) == 0 && send_cmd(CMD38, 0) == 0 && wait_ready(30000)) { // Erase sector block + res = RES_OK; // FatFs does not check result of this command } break; - /* Following commands are never used by FatFs module */ + // The following commands are never used by FatFs module - case MMC_GET_TYPE: /* Get MMC/SDC type (BYTE) */ + case MMC_GET_TYPE: // Get MMC/SDC type (BYTE) *ptr = CardType; res = RES_OK; break; - case MMC_GET_CSD: /* Read CSD (16 bytes) */ - if (send_cmd(CMD9, 0) == 0 && rcvr_datablock(ptr, 16)) { /* READ_CSD */ + case MMC_GET_CSD: // Read CSD (16 bytes) + if (send_cmd(CMD9, 0) == 0 && rcvr_datablock(ptr, 16)) { res = RES_OK; } break; - case MMC_GET_CID: /* Read CID (16 bytes) */ - if (send_cmd(CMD10, 0) == 0 && rcvr_datablock(ptr, 16)) { /* READ_CID */ + case MMC_GET_CID: // Read CID (16 bytes) + if (send_cmd(CMD10, 0) == 0 && rcvr_datablock(ptr, 16)) { res = RES_OK; } break; - case MMC_GET_OCR: /* Read OCR (4 bytes) */ - if (send_cmd(CMD58, 0) == 0) { /* READ_OCR */ + case MMC_GET_OCR: // Read OCR (4 bytes) + if (send_cmd(CMD58, 0) == 0) { for (n = 4; n; n--) *ptr++ = xchg_spi(0xFF); res = RES_OK; } break; - case MMC_GET_SDSTAT: /* Read SD status (64 bytes) */ - if (send_cmd(ACMD13, 0) == 0) { /* SD_STATUS */ + case MMC_GET_SDSTAT: // Read SD status (64 bytes) + if (send_cmd(ACMD13, 0) == 0) { xchg_spi(0xFF); if (rcvr_datablock(ptr, 64)) res = RES_OK; } diff --git a/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp b/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp index 1095389946ad0..5edf96fe56be9 100644 --- a/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp +++ b/Marlin/src/HAL/STM32F1/tft/tft_spi.cpp @@ -90,12 +90,20 @@ void TFT_SPI::DataTransferBegin(uint16_t DataSize) { TFT_CS_L; } +#ifdef TFT_DEFAULT_DRIVER + #include "../../../lcd/tft_io/tft_ids.h" +#endif + uint32_t TFT_SPI::GetID() { uint32_t id; id = ReadID(LCD_READ_ID); - - if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) + if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) { id = ReadID(LCD_READ_ID4); + #ifdef TFT_DEFAULT_DRIVER + if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) + id = TFT_DEFAULT_DRIVER; + #endif + } return id; } diff --git a/Marlin/src/HAL/STM32F1/tft/xpt2046.h b/Marlin/src/HAL/STM32F1/tft/xpt2046.h index 65602bda0f409..aba0799e445f8 100644 --- a/Marlin/src/HAL/STM32F1/tft/xpt2046.h +++ b/Marlin/src/HAL/STM32F1/tft/xpt2046.h @@ -54,7 +54,7 @@ enum XPTCoordinate : uint8_t { XPT2046_Z2 = 0x40 | XPT2046_CONTROL | XPT2046_DFR_MODE, }; -#if !defined(XPT2046_Z1_THRESHOLD) +#ifndef XPT2046_Z1_THRESHOLD #define XPT2046_Z1_THRESHOLD 10 #endif diff --git a/Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h b/Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h index 999ada512761c..9c7e2104882ed 100644 --- a/Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h +++ b/Marlin/src/HAL/TEENSY31_32/endstop_interrupts.h @@ -64,4 +64,10 @@ void setup_endstop_interrupts() { TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); + TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN)); + TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN)); + TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN)); + TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN)); + TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN)); + TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN)); } diff --git a/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h b/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h index 87e6a7507abcf..a300248885357 100644 --- a/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h +++ b/Marlin/src/HAL/TEENSY35_36/endstop_interrupts.h @@ -63,4 +63,10 @@ void setup_endstop_interrupts() { TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); + TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN)); + TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN)); + TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN)); + TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN)); + TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN)); + TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN)); } diff --git a/Marlin/src/HAL/TEENSY40_41/endstop_interrupts.h b/Marlin/src/HAL/TEENSY40_41/endstop_interrupts.h index a05e911668a7e..4c3ddec9f1f1f 100644 --- a/Marlin/src/HAL/TEENSY40_41/endstop_interrupts.h +++ b/Marlin/src/HAL/TEENSY40_41/endstop_interrupts.h @@ -63,4 +63,10 @@ void setup_endstop_interrupts() { TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN)); TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN)); TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN)); + TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN)); + TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN)); + TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN)); + TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN)); + TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN)); + TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN)); } diff --git a/Marlin/src/HAL/shared/eeprom_if_i2c.cpp b/Marlin/src/HAL/shared/eeprom_if_i2c.cpp index 27f0233562436..6b559e234b4c7 100644 --- a/Marlin/src/HAL/shared/eeprom_if_i2c.cpp +++ b/Marlin/src/HAL/shared/eeprom_if_i2c.cpp @@ -61,11 +61,24 @@ static constexpr uint8_t eeprom_device_address = I2C_ADDRESS(EEPROM_DEVICE_ADDRE // Public functions // ------------------------ +#define SMALL_EEPROM (MARLIN_EEPROM_SIZE <= 2048) + +// Combine Address high bits into the device address on <=16Kbit (2K) and >512Kbit (64K) EEPROMs. +// Note: MARLIN_EEPROM_SIZE is specified in bytes, whereas EEPROM model numbers refer to bits. +// e.g., The "16" in BL24C16 indicates a 16Kbit (2KB) size. +static uint8_t _eeprom_calc_device_address(uint8_t * const pos) { + const unsigned eeprom_address = (unsigned)pos; + return (SMALL_EEPROM || MARLIN_EEPROM_SIZE > 65536) + ? uint8_t(eeprom_device_address | ((eeprom_address >> (SMALL_EEPROM ? 8 : 16)) & 0x07)) + : eeprom_device_address; +} + static void _eeprom_begin(uint8_t * const pos) { const unsigned eeprom_address = (unsigned)pos; - Wire.beginTransmission(eeprom_device_address); - Wire.write(int(eeprom_address >> 8)); // Address High - Wire.write(int(eeprom_address & 0xFF)); // Address Low + Wire.beginTransmission(_eeprom_calc_device_address(pos)); + if (!SMALL_EEPROM) + Wire.write(uint8_t((eeprom_address >> 8) & 0xFF)); // Address High, if needed + Wire.write(uint8_t(eeprom_address & 0xFF)); // Address Low } void eeprom_write_byte(uint8_t *pos, uint8_t value) { @@ -81,7 +94,7 @@ void eeprom_write_byte(uint8_t *pos, uint8_t value) { uint8_t eeprom_read_byte(uint8_t *pos) { _eeprom_begin(pos); Wire.endTransmission(); - Wire.requestFrom(eeprom_device_address, (byte)1); + Wire.requestFrom(_eeprom_calc_device_address(pos), (byte)1); return Wire.available() ? Wire.read() : 0xFF; } diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 5ef575a30f6ae..f77f3b2f0b816 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -282,12 +282,22 @@ bool wait_for_heatup = true; #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wnarrowing" +#ifndef RUNTIME_ONLY_ANALOG_TO_DIGITAL + template + constexpr pin_t OnlyPins<_SP_END, D...>::table[sizeof...(D)]; +#endif + bool pin_is_protected(const pin_t pin) { - static const pin_t sensitive_pins[] PROGMEM = SENSITIVE_PINS; - LOOP_L_N(i, COUNT(sensitive_pins)) { - pin_t sensitive_pin; - memcpy_P(&sensitive_pin, &sensitive_pins[i], sizeof(pin_t)); - if (pin == sensitive_pin) return true; + #ifdef RUNTIME_ONLY_ANALOG_TO_DIGITAL + static const pin_t sensitive_pins[] PROGMEM = { SENSITIVE_PINS }; + const size_t pincount = COUNT(sensitive_pins); + #else + static constexpr size_t pincount = OnlyPins::size; + static const pin_t (&sensitive_pins)[pincount] PROGMEM = OnlyPins::table; + #endif + LOOP_L_N(i, pincount) { + const pin_t * const pptr = &sensitive_pins[i]; + if (pin == (sizeof(pin_t) == 2 ? (pin_t)pgm_read_word(pptr) : (pin_t)pgm_read_byte(pptr))) return true; } return false; } @@ -304,6 +314,9 @@ void enable_all_steppers() { ENABLE_AXIS_X(); ENABLE_AXIS_Y(); ENABLE_AXIS_Z(); + ENABLE_AXIS_I(); // Marlin 6-axis support by DerAndere (https://github.com/DerAndere1/Marlin/wiki) + ENABLE_AXIS_J(); + ENABLE_AXIS_K(); enable_e_steppers(); TERN_(EXTENSIBLE_UI, ExtUI::onSteppersEnabled()); @@ -317,7 +330,7 @@ void disable_e_steppers() { void disable_e_stepper(const uint8_t e) { #define _CASE_DIS_E(N) case N: DISABLE_AXIS_E##N(); break; switch (e) { - REPEAT(EXTRUDERS, _CASE_DIS_E) + REPEAT(E_STEPPERS, _CASE_DIS_E) } } @@ -325,6 +338,9 @@ void disable_all_steppers() { DISABLE_AXIS_X(); DISABLE_AXIS_Y(); DISABLE_AXIS_Z(); + DISABLE_AXIS_I(); + DISABLE_AXIS_J(); + DISABLE_AXIS_K(); disable_e_steppers(); TERN_(EXTENSIBLE_UI, ExtUI::onSteppersDisabled()); @@ -408,19 +424,18 @@ void startOrResumeJob() { * - Check if an idle but hot extruder needs filament extruded (EXTRUDER_RUNOUT_PREVENT) * - Pulse FET_SAFETY_PIN if it exists */ -inline void manage_inactivity(const bool ignore_stepper_queue=false) { +inline void manage_inactivity(const bool no_stepper_sleep=false) { queue.get_available_commands(); const millis_t ms = millis(); - // Prevent steppers timing-out in the middle of M600 - // unless PAUSE_PARK_NO_STEPPER_TIMEOUT is disabled - const bool parked_or_ignoring = ignore_stepper_queue + // Prevent steppers timing-out + const bool do_reset_timeout = no_stepper_sleep || TERN0(PAUSE_PARK_NO_STEPPER_TIMEOUT, did_pause_print); // Reset both the M18/M84 activity timeout and the M85 max 'kill' timeout - if (parked_or_ignoring) gcode.reset_stepper_timeout(ms); + if (do_reset_timeout) gcode.reset_stepper_timeout(ms); if (gcode.stepper_max_timed_out(ms)) { SERIAL_ERROR_MSG(STR_KILL_INACTIVE_TIME, parser.command_ptr); @@ -436,7 +451,7 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) { // activity timeout and the M85 max 'kill' timeout if (planner.has_blocks_queued()) gcode.reset_stepper_timeout(ms); - else if (!parked_or_ignoring && gcode.stepper_inactive_timeout()) { + else if (!do_reset_timeout && gcode.stepper_inactive_timeout()) { if (!already_shutdown_steppers) { already_shutdown_steppers = true; // L6470 SPI will consume 99% of free time without this @@ -444,6 +459,9 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) { if (ENABLED(DISABLE_INACTIVE_X)) DISABLE_AXIS_X(); if (ENABLED(DISABLE_INACTIVE_Y)) DISABLE_AXIS_Y(); if (ENABLED(DISABLE_INACTIVE_Z)) DISABLE_AXIS_Z(); + if (ENABLED(DISABLE_INACTIVE_I)) DISABLE_AXIS_I(); + if (ENABLED(DISABLE_INACTIVE_J)) DISABLE_AXIS_J(); + if (ENABLED(DISABLE_INACTIVE_K)) DISABLE_AXIS_K(); if (ENABLED(DISABLE_INACTIVE_E)) disable_e_steppers(); TERN_(AUTO_BED_LEVELING_UBL, ubl.steppers_were_disabled()); @@ -716,14 +734,14 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) { * - Update the Průša MMU2 * - Handle Joystick jogging */ -void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep/*=false*/)) { +void idle(bool no_stepper_sleep/*=false*/) { #if ENABLED(MARLIN_DEV_MODE) static uint16_t idle_depth = 0; if (++idle_depth > 5) SERIAL_ECHOLNPAIR("idle() call depth: ", idle_depth); #endif // Core Marlin activities - manage_inactivity(TERN_(ADVANCED_PAUSE_FEATURE, no_stepper_sleep)); + manage_inactivity(no_stepper_sleep); // Manage Heaters (and Watchdog) thermalManager.manage_heater(); @@ -935,6 +953,15 @@ inline void tmc_standby_setup() { #if PIN_EXISTS(Z4_STDBY) SET_INPUT_PULLDOWN(Z4_STDBY_PIN); #endif + #if PIN_EXISTS(I_STDBY) + SET_INPUT_PULLDOWN(I_STDBY_PIN); + #endif + #if PIN_EXISTS(J_STDBY) + SET_INPUT_PULLDOWN(J_STDBY_PIN); + #endif + #if PIN_EXISTS(K_STDBY) + SET_INPUT_PULLDOWN(K_STDBY_PIN); + #endif #if PIN_EXISTS(E0_STDBY) SET_INPUT_PULLDOWN(E0_STDBY_PIN); #endif @@ -1073,11 +1100,17 @@ void setup() { while (!MYSERIAL1.connected() && PENDING(millis(), serial_connect_timeout)) { /*nada*/ } #if HAS_MULTI_SERIAL && !HAS_ETHERNET - MYSERIAL2.begin(BAUDRATE); + #ifndef BAUDRATE_2 + #define BAUDRATE_2 BAUDRATE + #endif + MYSERIAL2.begin(BAUDRATE_2); serial_connect_timeout = millis() + 1000UL; while (!MYSERIAL2.connected() && PENDING(millis(), serial_connect_timeout)) { /*nada*/ } #ifdef SERIAL_PORT_3 - MYSERIAL3.begin(BAUDRATE); + #ifndef BAUDRATE_3 + #define BAUDRATE_3 BAUDRATE + #endif + MYSERIAL3.begin(BAUDRATE_3); serial_connect_timeout = millis() + 1000UL; while (!MYSERIAL3.connected() && PENDING(millis(), serial_connect_timeout)) { /*nada*/ } #endif @@ -1095,6 +1128,7 @@ void setup() { #endif #if HAS_FREEZE_PIN + SETUP_LOG("FREEZE_PIN"); SET_INPUT_PULLUP(FREEZE_PIN); #endif @@ -1103,11 +1137,19 @@ void setup() { OUT_WRITE(SUICIDE_PIN, !SUICIDE_PIN_INVERTING); #endif + #ifdef JTAGSWD_RESET + SETUP_LOG("JTAGSWD_RESET"); + JTAGSWD_RESET(); + #endif + #if EITHER(DISABLE_DEBUG, DISABLE_JTAG) + delay(10); // Disable any hardware debug to free up pins for IO #if ENABLED(DISABLE_DEBUG) && defined(JTAGSWD_DISABLE) + SETUP_LOG("JTAGSWD_DISABLE"); JTAGSWD_DISABLE(); #elif defined(JTAG_DISABLE) + SETUP_LOG("JTAG_DISABLE"); JTAG_DISABLE(); #else #error "DISABLE_(DEBUG|JTAG) is not supported for the selected MCU/Board." @@ -1126,10 +1168,10 @@ void setup() { SETUP_RUN(HAL_init()); // Init and disable SPI thermocouples; this is still needed - #if TEMP_SENSOR_0_IS_MAX_TC + #if TEMP_SENSOR_0_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 0) OUT_WRITE(MAX6675_SS_PIN, HIGH); // Disable #endif - #if TEMP_SENSOR_1_IS_MAX_TC + #if TEMP_SENSOR_1_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 1) OUT_WRITE(MAX6675_SS2_PIN, HIGH); // Disable #endif @@ -1417,10 +1459,7 @@ void setup() { #endif #if HAS_PRUSA_MMU1 - SETUP_LOG("Prusa MMU1"); - SET_OUTPUT(E_MUX0_PIN); - SET_OUTPUT(E_MUX1_PIN); - SET_OUTPUT(E_MUX2_PIN); + SETUP_RUN(mmu_init()); #endif #if HAS_FANMUX diff --git a/Marlin/src/MarlinCore.h b/Marlin/src/MarlinCore.h index ce1b106bfad59..01a1be4d594f6 100644 --- a/Marlin/src/MarlinCore.h +++ b/Marlin/src/MarlinCore.h @@ -34,8 +34,8 @@ void stop(); // Pass true to keep steppers from timing out -void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep=false)); -inline void idle_no_sleep() { idle(TERN_(ADVANCED_PAUSE_FEATURE, true)); } +void idle(bool no_stepper_sleep=false); +inline void idle_no_sleep() { idle(true); } #if ENABLED(G38_PROBE_TARGET) extern uint8_t G38_move; // Flag to tell the ISR that G38 is in progress, and the type diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 20aeac654dae8..9dc951e229c60 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -159,6 +159,7 @@ #define BOARD_PICA_REVB 1324 // PICA Shield (original version) #define BOARD_PICA 1325 // PICA Shield (rev C or later) #define BOARD_INTAMSYS40 1326 // Intamsys 4.0 (Funmat HT) +#define BOARD_MALYAN_M180 1327 // Malyan M180 Mainboard Version 2 (no display function, direct gcode only) // // ATmega1281, ATmega2561 @@ -320,7 +321,7 @@ #define BOARD_BTT_SKR_MINI_V1_1 4023 // BigTreeTech SKR Mini v1.1 (STM32F103RC) #define BOARD_BTT_SKR_MINI_E3_V1_0 4024 // BigTreeTech SKR Mini E3 (STM32F103RC) #define BOARD_BTT_SKR_MINI_E3_V1_2 4025 // BigTreeTech SKR Mini E3 V1.2 (STM32F103RC) -#define BOARD_BTT_SKR_MINI_E3_V2_0 4026 // BigTreeTech SKR Mini E3 V2.0 (STM32F103RC) +#define BOARD_BTT_SKR_MINI_E3_V2_0 4026 // BigTreeTech SKR Mini E3 V2.0 (STM32F103RC / STM32F103RE) #define BOARD_BTT_SKR_MINI_MZ_V1_0 4027 // BigTreeTech SKR Mini MZ V1.0 (STM32F103RC) #define BOARD_BTT_SKR_E3_DIP 4028 // BigTreeTech SKR E3 DIP V1.0 (STM32F103RC / STM32F103RE) #define BOARD_BTT_SKR_CR6 4029 // BigTreeTech SKR CR6 v1.0 (STM32F103RE) @@ -371,20 +372,21 @@ #define BOARD_BTT_SKR_V2_0_REV_B 4212 // BigTreeTech SKR v2.0 Rev B (STM32F407VGT6) #define BOARD_BTT_GTR_V1_0 4213 // BigTreeTech GTR v1.0 (STM32F407IGT) #define BOARD_BTT_OCTOPUS_V1_0 4214 // BigTreeTech Octopus v1.0 (STM32F446ZET6) -#define BOARD_LERDGE_K 4215 // Lerdge K (STM32F407ZG) -#define BOARD_LERDGE_S 4216 // Lerdge S (STM32F407VE) -#define BOARD_LERDGE_X 4217 // Lerdge X (STM32F407VE) -#define BOARD_VAKE403D 4218 // VAkE 403D (STM32F446VET6) -#define BOARD_FYSETC_S6 4219 // FYSETC S6 (STM32F446VET6) -#define BOARD_FYSETC_S6_V2_0 4220 // FYSETC S6 v2.0 (STM32F446VET6) -#define BOARD_FYSETC_SPIDER 4221 // FYSETC Spider (STM32F446VET6) -#define BOARD_FLYF407ZG 4222 // FLYF407ZG (STM32F407ZG) -#define BOARD_MKS_ROBIN2 4223 // MKS_ROBIN2 (STM32F407ZE) -#define BOARD_MKS_ROBIN_PRO_V2 4224 // MKS Robin Pro V2 (STM32F407VE) -#define BOARD_MKS_ROBIN_NANO_V3 4225 // MKS Robin Nano V3 (STM32F407VG) -#define BOARD_ANET_ET4 4226 // ANET ET4 V1.x (STM32F407VGT6) -#define BOARD_ANET_ET4P 4227 // ANET ET4P V1.x (STM32F407VGT6) -#define BOARD_FYSETC_CHEETAH_V20 4228 // FYSETC Cheetah V2.0 +#define BOARD_BTT_OCTOPUS_V1_1 4215 // BigTreeTech Octopus v1.1 (STM32F446ZET6) +#define BOARD_LERDGE_K 4216 // Lerdge K (STM32F407ZG) +#define BOARD_LERDGE_S 4217 // Lerdge S (STM32F407VE) +#define BOARD_LERDGE_X 4218 // Lerdge X (STM32F407VE) +#define BOARD_VAKE403D 4219 // VAkE 403D (STM32F446VET6) +#define BOARD_FYSETC_S6 4220 // FYSETC S6 (STM32F446VET6) +#define BOARD_FYSETC_S6_V2_0 4221 // FYSETC S6 v2.0 (STM32F446VET6) +#define BOARD_FYSETC_SPIDER 4222 // FYSETC Spider (STM32F446VET6) +#define BOARD_FLYF407ZG 4223 // FLYF407ZG (STM32F407ZG) +#define BOARD_MKS_ROBIN2 4224 // MKS_ROBIN2 (STM32F407ZE) +#define BOARD_MKS_ROBIN_PRO_V2 4225 // MKS Robin Pro V2 (STM32F407VE) +#define BOARD_MKS_ROBIN_NANO_V3 4226 // MKS Robin Nano V3 (STM32F407VG) +#define BOARD_ANET_ET4 4227 // ANET ET4 V1.x (STM32F407VGT6) +#define BOARD_ANET_ET4P 4228 // ANET ET4P V1.x (STM32F407VGT6) +#define BOARD_FYSETC_CHEETAH_V20 4229 // FYSETC Cheetah V2.0 // diff --git a/Marlin/src/core/drivers.h b/Marlin/src/core/drivers.h index 3a0e620923ada..0a76410274bb7 100644 --- a/Marlin/src/core/drivers.h +++ b/Marlin/src/core/drivers.h @@ -60,6 +60,9 @@ #define AXIS_DRIVER_TYPE_X(T) _AXIS_DRIVER_TYPE(X,T) #define AXIS_DRIVER_TYPE_Y(T) _AXIS_DRIVER_TYPE(Y,T) #define AXIS_DRIVER_TYPE_Z(T) _AXIS_DRIVER_TYPE(Z,T) +#define AXIS_DRIVER_TYPE_I(T) _AXIS_DRIVER_TYPE(I,T) +#define AXIS_DRIVER_TYPE_J(T) _AXIS_DRIVER_TYPE(J,T) +#define AXIS_DRIVER_TYPE_K(T) _AXIS_DRIVER_TYPE(K,T) #define AXIS_DRIVER_TYPE_X2(T) (EITHER(X_DUAL_STEPPER_DRIVERS, DUAL_X_CARRIAGE) && _AXIS_DRIVER_TYPE(X2,T)) #define AXIS_DRIVER_TYPE_Y2(T) (ENABLED(Y_DUAL_STEPPER_DRIVERS) && _AXIS_DRIVER_TYPE(Y2,T)) @@ -83,6 +86,7 @@ #define HAS_E_DRIVER(T) (0 RREPEAT2(E_STEPPERS, _OR_ADTE, T)) #define HAS_DRIVER(T) ( AXIS_DRIVER_TYPE_X(T) || AXIS_DRIVER_TYPE_Y(T) || AXIS_DRIVER_TYPE_Z(T) \ + || AXIS_DRIVER_TYPE_I(T) || AXIS_DRIVER_TYPE_J(T) || AXIS_DRIVER_TYPE_K(T) \ || AXIS_DRIVER_TYPE_X2(T) || AXIS_DRIVER_TYPE_Y2(T) || AXIS_DRIVER_TYPE_Z2(T) \ || AXIS_DRIVER_TYPE_Z3(T) || AXIS_DRIVER_TYPE_Z4(T) || HAS_E_DRIVER(T) ) @@ -153,9 +157,11 @@ #define _OR_EAH(N,T) || AXIS_HAS_##T(E##N) #define E_AXIS_HAS(T) (0 _OR_EAH(0,T) _OR_EAH(1,T) _OR_EAH(2,T) _OR_EAH(3,T) _OR_EAH(4,T) _OR_EAH(5,T) _OR_EAH(6,T) _OR_EAH(7,T)) -#define ANY_AXIS_HAS(T) ( AXIS_HAS_##T(X) || AXIS_HAS_##T(Y) || AXIS_HAS_##T(Z) \ - || AXIS_HAS_##T(X2) || AXIS_HAS_##T(Y2) || AXIS_HAS_##T(Z2) \ - || AXIS_HAS_##T(Z3) || AXIS_HAS_##T(Z4) || E_AXIS_HAS(T) ) +#define ANY_AXIS_HAS(T) ( AXIS_HAS_##T(X) || AXIS_HAS_##T(X2) \ + || AXIS_HAS_##T(Y) || AXIS_HAS_##T(Y2) \ + || AXIS_HAS_##T(Z) || AXIS_HAS_##T(Z2) || AXIS_HAS_##T(Z3) || AXIS_HAS_##T(Z4) \ + || AXIS_HAS_##T(I) || AXIS_HAS_##T(J) || AXIS_HAS_##T(K) \ + || E_AXIS_HAS(T) ) #if ANY_AXIS_HAS(STEALTHCHOP) #define HAS_STEALTHCHOP 1 diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h index df6821cb1cafb..8e97ec66a9816 100644 --- a/Marlin/src/core/language.h +++ b/Marlin/src/core/language.h @@ -266,18 +266,25 @@ #define STR_X_MAX "x_max" #define STR_X2_MIN "x2_min" #define STR_X2_MAX "x2_max" -#define STR_Y_MIN "y_min" -#define STR_Y_MAX "y_max" -#define STR_Y2_MIN "y2_min" -#define STR_Y2_MAX "y2_max" -#define STR_Z_MIN "z_min" -#define STR_Z_MAX "z_max" -#define STR_Z2_MIN "z2_min" -#define STR_Z2_MAX "z2_max" -#define STR_Z3_MIN "z3_min" -#define STR_Z3_MAX "z3_max" -#define STR_Z4_MIN "z4_min" -#define STR_Z4_MAX "z4_max" + +#if HAS_Y_AXIS + #define STR_Y_MIN "y_min" + #define STR_Y_MAX "y_max" + #define STR_Y2_MIN "y2_min" + #define STR_Y2_MAX "y2_max" +#endif + +#if HAS_Z_AXIS + #define STR_Z_MIN "z_min" + #define STR_Z_MAX "z_max" + #define STR_Z2_MIN "z2_min" + #define STR_Z2_MAX "z2_max" + #define STR_Z3_MIN "z3_min" + #define STR_Z3_MAX "z3_max" + #define STR_Z4_MIN "z4_min" + #define STR_Z4_MAX "z4_max" +#endif + #define STR_Z_PROBE "z_probe" #define STR_PROBE_EN "probe_en" #define STR_FILAMENT_RUNOUT_SENSOR "filament" @@ -286,6 +293,9 @@ #define STR_X "X" #define STR_Y "Y" #define STR_Z "Z" +#define STR_I AXIS4_STR +#define STR_J AXIS5_STR +#define STR_K AXIS6_STR #define STR_E "E" #if IS_KINEMATIC #define STR_A "A" @@ -305,8 +315,114 @@ #define LCD_STR_A STR_A #define LCD_STR_B STR_B #define LCD_STR_C STR_C +#define LCD_STR_I STR_I +#define LCD_STR_J STR_J +#define LCD_STR_K STR_K #define LCD_STR_E STR_E +// Extra Axis and Endstop Names +#if LINEAR_AXES >= 4 + #if AXIS4_NAME == 'A' + #define AXIS4_STR "A" + #define STR_I_MIN "a_min" + #define STR_I_MAX "a_max" + #elif AXIS4_NAME == 'B' + #define AXIS4_STR "B" + #define STR_I_MIN "b_min" + #define STR_I_MAX "b_max" + #elif AXIS4_NAME == 'C' + #define AXIS4_STR "C" + #define STR_I_MIN "c_min" + #define STR_I_MAX "c_max" + #elif AXIS4_NAME == 'U' + #define AXIS4_STR "U" + #define STR_I_MIN "u_min" + #define STR_I_MAX "u_max" + #elif AXIS4_NAME == 'V' + #define AXIS4_STR "V" + #define STR_I_MIN "v_min" + #define STR_I_MAX "v_max" + #elif AXIS4_NAME == 'W' + #define AXIS4_STR "W" + #define STR_I_MIN "w_min" + #define STR_I_MAX "w_max" + #else + #define AXIS4_STR "A" + #define STR_I_MIN "a_min" + #define STR_I_MAX "a_max" + #endif +#else + #define AXIS4_STR "" +#endif + +#if LINEAR_AXES >= 5 + #if AXIS5_NAME == 'A' + #define AXIS5_STR "A" + #define STR_J_MIN "a_min" + #define STR_J_MAX "a_max" + #elif AXIS5_NAME == 'B' + #define AXIS5_STR "B" + #define STR_J_MIN "b_min" + #define STR_J_MAX "b_max" + #elif AXIS5_NAME == 'C' + #define AXIS5_STR "C" + #define STR_J_MIN "c_min" + #define STR_J_MAX "c_max" + #elif AXIS5_NAME == 'U' + #define AXIS5_STR "U" + #define STR_J_MIN "u_min" + #define STR_J_MAX "u_max" + #elif AXIS5_NAME == 'V' + #define AXIS5_STR "V" + #define STR_J_MIN "v_min" + #define STR_J_MAX "v_max" + #elif AXIS5_NAME == 'W' + #define AXIS5_STR "W" + #define STR_J_MIN "w_min" + #define STR_J_MAX "w_max" + #else + #define AXIS5_STR "B" + #define STR_J_MIN "b_min" + #define STR_J_MAX "b_max" + #endif +#else + #define AXIS5_STR "" +#endif + +#if LINEAR_AXES >= 6 + #if AXIS6_NAME == 'A' + #define AXIS6_STR "A" + #define STR_K_MIN "a_min" + #define STR_K_MAX "a_max" + #elif AXIS6_NAME == 'B' + #define AXIS6_STR "B" + #define STR_K_MIN "b_min" + #define STR_K_MAX "b_max" + #elif AXIS6_NAME == 'C' + #define AXIS6_STR "C" + #define STR_K_MIN "c_min" + #define STR_K_MAX "c_max" + #elif AXIS6_NAME == 'U' + #define AXIS6_STR "U" + #define STR_K_MIN "u_min" + #define STR_K_MAX "u_max" + #elif AXIS6_NAME == 'V' + #define AXIS6_STR "V" + #define STR_K_MIN "v_min" + #define STR_K_MAX "v_max" + #elif AXIS6_NAME == 'W' + #define AXIS6_STR "W" + #define STR_K_MIN "w_min" + #define STR_K_MAX "w_max" + #else + #define AXIS6_STR "C" + #define STR_K_MIN "c_min" + #define STR_K_MAX "c_max" + #endif +#else + #define AXIS6_STR "" +#endif + #if EITHER(HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL) // Custom characters defined in the first 8 characters of the LCD diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index 566087b76b2e0..295eee9bcfa82 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -36,12 +36,21 @@ #define _XMIN_ 100 #define _YMIN_ 200 #define _ZMIN_ 300 +#define _IMIN_ 500 +#define _JMIN_ 600 +#define _KMIN_ 700 #define _XMAX_ 101 #define _YMAX_ 201 #define _ZMAX_ 301 +#define _IMAX_ 501 +#define _JMAX_ 601 +#define _KMAX_ 701 #define _XDIAG_ 102 #define _YDIAG_ 202 #define _ZDIAG_ 302 +#define _IDIAG_ 502 +#define _JDIAG_ 602 +#define _KDIAG_ 702 #define _E0DIAG_ 400 #define _E1DIAG_ 401 #define _E2DIAG_ 402 @@ -195,6 +204,11 @@ #define __TERN(T,V...) ___TERN(_CAT(_NO,T),V) // Prepend '_NO' to get '_NOT_0' or '_NOT_1' #define ___TERN(P,V...) THIRD(P,V) // If first argument has a comma, A. Else B. +#define _OPTARG(A) , A +#define OPTARG(O,A) TERN_(O,DEFER4(_OPTARG)(A)) +#define _OPTCODE(A) A; +#define OPTCODE(O,A) TERN_(O,DEFER4(_OPTCODE)(A)) + // Macros to avoid 'f + 0.0' which is not always optimized away. Minus included for symmetry. // Compiler flags -fno-signed-zeros -ffinite-math-only also cover 'f * 1.0', 'f - f', etc. #define PLUS_TERN0(O,A) _TERN(_ENA_1(O),,+ (A)) // OPTION ? '+ (A)' : '' diff --git a/Marlin/src/core/serial.cpp b/Marlin/src/core/serial.cpp index b4184fcd623bd..2e3a39b66a72e 100644 --- a/Marlin/src/core/serial.cpp +++ b/Marlin/src/core/serial.cpp @@ -36,6 +36,10 @@ PGMSTR(X_LBL, "X:"); PGMSTR(Y_LBL, "Y:"); PGMSTR(Z_LBL, "Z:"); PGMST PGMSTR(SP_A_STR, " A"); PGMSTR(SP_B_STR, " B"); PGMSTR(SP_C_STR, " C"); PGMSTR(SP_X_STR, " X"); PGMSTR(SP_Y_STR, " Y"); PGMSTR(SP_Z_STR, " Z"); PGMSTR(SP_E_STR, " E"); PGMSTR(SP_X_LBL, " X:"); PGMSTR(SP_Y_LBL, " Y:"); PGMSTR(SP_Z_LBL, " Z:"); PGMSTR(SP_E_LBL, " E:"); +PGMSTR(I_STR, AXIS4_STR); PGMSTR(J_STR, AXIS5_STR); PGMSTR(K_STR, AXIS6_STR); +PGMSTR(I_LBL, AXIS4_STR ":"); PGMSTR(J_LBL, AXIS5_STR ":"); PGMSTR(K_LBL, AXIS6_STR ":"); +PGMSTR(SP_I_STR, " " AXIS4_STR); PGMSTR(SP_J_STR, " " AXIS5_STR); PGMSTR(SP_K_STR, " " AXIS6_STR); +PGMSTR(SP_I_LBL, " " AXIS4_STR ":"); PGMSTR(SP_J_LBL, " " AXIS5_STR ":"); PGMSTR(SP_K_LBL, " " AXIS6_STR ":"); // Hook Meatpack if it's enabled on the first leaf #if ENABLED(MEATPACK_ON_SERIAL_PORT_1) @@ -101,8 +105,10 @@ void print_bin(uint16_t val) { } } -void print_pos(const_float_t x, const_float_t y, const_float_t z, PGM_P const prefix/*=nullptr*/, PGM_P const suffix/*=nullptr*/) { +void print_pos(LINEAR_AXIS_ARGS(const_float_t), PGM_P const prefix/*=nullptr*/, PGM_P const suffix/*=nullptr*/) { if (prefix) serialprintPGM(prefix); - SERIAL_ECHOPAIR_P(SP_X_STR, x, SP_Y_STR, y, SP_Z_STR, z); + SERIAL_ECHOPAIR_P( + LIST_N(DOUBLE(LINEAR_AXES), SP_X_STR, x, SP_Y_STR, y, SP_Z_STR, z, SP_I_STR, i, SP_J_STR, j, SP_K_STR, k) + ); if (suffix) serialprintPGM(suffix); else SERIAL_EOL(); } diff --git a/Marlin/src/core/serial.h b/Marlin/src/core/serial.h index 74b96dbb6476c..a5afb9d895d27 100644 --- a/Marlin/src/core/serial.h +++ b/Marlin/src/core/serial.h @@ -29,12 +29,16 @@ #endif // Commonly-used strings in serial output -extern const char NUL_STR[], SP_P_STR[], SP_T_STR[], +extern const char NUL_STR[], + SP_X_STR[], SP_Y_STR[], SP_Z_STR[], + SP_A_STR[], SP_B_STR[], SP_C_STR[], SP_E_STR[], + SP_X_LBL[], SP_Y_LBL[], SP_Z_LBL[], SP_E_LBL[], + SP_I_STR[], SP_J_STR[], SP_K_STR[], + SP_I_LBL[], SP_J_LBL[], SP_K_LBL[], + SP_P_STR[], SP_T_STR[], X_STR[], Y_STR[], Z_STR[], E_STR[], X_LBL[], Y_LBL[], Z_LBL[], E_LBL[], - SP_A_STR[], SP_B_STR[], SP_C_STR[], - SP_X_STR[], SP_Y_STR[], SP_Z_STR[], SP_E_STR[], - SP_X_LBL[], SP_Y_LBL[], SP_Z_LBL[], SP_E_LBL[]; + I_LBL[], J_LBL[], K_LBL[]; // // Debugging flags for use by M111 @@ -310,10 +314,10 @@ void serialprint_truefalse(const bool tf); void serial_spaces(uint8_t count); void print_bin(const uint16_t val); -void print_pos(const_float_t x, const_float_t y, const_float_t z, PGM_P const prefix=nullptr, PGM_P const suffix=nullptr); +void print_pos(LINEAR_AXIS_ARGS(const_float_t), PGM_P const prefix=nullptr, PGM_P const suffix=nullptr); inline void print_pos(const xyz_pos_t &xyz, PGM_P const prefix=nullptr, PGM_P const suffix=nullptr) { - print_pos(xyz.x, xyz.y, xyz.z, prefix, suffix); + print_pos(LINEAR_AXIS_ELEM(xyz), prefix, suffix); } #define SERIAL_POS(SUFFIX,VAR) do { print_pos(VAR, PSTR(" " STRINGIFY(VAR) "="), PSTR(" : " SUFFIX "\n")); }while(0) diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h index b7ae85eb2ee12..833167a7a1967 100644 --- a/Marlin/src/core/types.h +++ b/Marlin/src/core/types.h @@ -39,6 +39,32 @@ struct IF { typedef R type; }; template struct IF { typedef L type; }; +#define LINEAR_AXIS_GANG(V...) GANG_N(LINEAR_AXES, V) +#define LINEAR_AXIS_CODE(V...) CODE_N(LINEAR_AXES, V) +#define LINEAR_AXIS_LIST(V...) LIST_N(LINEAR_AXES, V) +#define LINEAR_AXIS_ARRAY(V...) { LINEAR_AXIS_LIST(V) } +#define LINEAR_AXIS_ARGS(T...) LINEAR_AXIS_LIST(T x, T y, T z, T i, T j, T k) +#define LINEAR_AXIS_ELEM(O) LINEAR_AXIS_LIST(O.x, O.y, O.z, O.i, O.j, O.k) +#define LINEAR_AXIS_DEFS(T,V) LINEAR_AXIS_LIST(T x=V, T y=V, T z=V, T i=V, T j=V, T k=V) + +#define LOGICAL_AXIS_GANG(E,V...) LINEAR_AXIS_GANG(V) GANG_ITEM_E(E) +#define LOGICAL_AXIS_CODE(E,V...) LINEAR_AXIS_CODE(V) CODE_ITEM_E(E) +#define LOGICAL_AXIS_LIST(E,V...) LINEAR_AXIS_LIST(V) LIST_ITEM_E(E) +#define LOGICAL_AXIS_ARRAY(E,V...) { LOGICAL_AXIS_LIST(E,V) } +#define LOGICAL_AXIS_ARGS(T...) LOGICAL_AXIS_LIST(T e, T x, T y, T z, T i, T j, T k) +#define LOGICAL_AXIS_ELEM(O) LOGICAL_AXIS_LIST(O.e, O.x, O.y, O.z, O.i, O.j, O.k) +#define LOGICAL_AXIS_DECL(T,V) LOGICAL_AXIS_LIST(T e=V, T x=V, T y=V, T z=V, T i=V, T j=V, T k=V) + +#if HAS_EXTRUDERS + #define LIST_ITEM_E(N) , N + #define CODE_ITEM_E(N) ; N + #define GANG_ITEM_E(N) N +#else + #define LIST_ITEM_E(N) + #define CODE_ITEM_E(N) + #define GANG_ITEM_E(N) +#endif + // // Enumerated axis indices // @@ -47,16 +73,43 @@ struct IF { typedef L type; }; // - X_HEAD, Y_HEAD, and Z_HEAD should be used for Steppers on Core kinematics // enum AxisEnum : uint8_t { - X_AXIS = 0, A_AXIS = X_AXIS, - Y_AXIS = 1, B_AXIS = Y_AXIS, - Z_AXIS = 2, C_AXIS = Z_AXIS, - E_AXIS, - X_HEAD, Y_HEAD, Z_HEAD, - E0_AXIS = E_AXIS, - E1_AXIS, E2_AXIS, E3_AXIS, E4_AXIS, E5_AXIS, E6_AXIS, E7_AXIS, - ALL_AXES_ENUM = 0xFE, NO_AXIS_ENUM = 0xFF + + // Linear axes may be controlled directly or indirectly + LINEAR_AXIS_LIST(X_AXIS, Y_AXIS, Z_AXIS, I_AXIS, J_AXIS, K_AXIS) + + // Extruder axes may be considered distinctly + #define _EN_ITEM(N) , E##N##_AXIS + REPEAT(EXTRUDERS, _EN_ITEM) + #undef _EN_ITEM + + // Core also keeps toolhead directions + #if EITHER(IS_CORE, MARKFORGED_XY) + , X_HEAD, Y_HEAD, Z_HEAD + #endif + + // Distinct axes, including all E and Core + , NUM_AXIS_ENUMS + + // Most of the time we refer only to the single E_AXIS + #if HAS_EXTRUDERS + , E_AXIS = E0_AXIS + #endif + + // A, B, and C are for DELTA, SCARA, etc. + , A_AXIS = X_AXIS + #if LINEAR_AXES >= 2 + , B_AXIS = Y_AXIS + #endif + #if LINEAR_AXES >= 3 + , C_AXIS = Z_AXIS + #endif + + // To refer to all or none + , ALL_AXES_ENUM = 0xFE, NO_AXIS_ENUM = 0xFF }; +typedef IF<(NUM_AXIS_ENUMS > 8), uint16_t, uint8_t>::type axis_bits_t; + // // Loop over axes // @@ -185,7 +238,7 @@ void toNative(xyz_pos_t &raw); void toNative(xyze_pos_t &raw); // -// XY coordinates, counters, etc. +// Paired XY coordinates, counters, flags, etc. // template struct XYval { @@ -194,18 +247,34 @@ struct XYval { struct { T a, b; }; T pos[2]; }; + + // Set all to 0 + FI void reset() { x = y = 0; } + + // Setters taking struct types and arrays 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 (&arr)[XY]) { x = arr[0]; y = arr[1]; } - FI void set(const T (&arr)[XYZ]) { x = arr[0]; y = arr[1]; } - FI void set(const T (&arr)[XYZE]) { x = arr[0]; y = arr[1]; } - #if DISTINCT_AXES > LOGICAL_AXES - FI void set(const T (&arr)[DISTINCT_AXES]) { x = arr[0]; y = arr[1]; } + #if HAS_Y_AXIS + FI void set(const T px, const T py) { x = px; y = py; } + FI void set(const T (&arr)[XY]) { x = arr[0]; y = arr[1]; } #endif - FI void reset() { x = y = 0; } + #if LINEAR_AXES > XY + FI void set(const T (&arr)[LINEAR_AXES]) { x = arr[0]; y = arr[1]; } + #endif + #if LOGICAL_AXES > LINEAR_AXES + FI void set(const T (&arr)[LOGICAL_AXES]) { x = arr[0]; y = arr[1]; } + #if DISTINCT_AXES > LOGICAL_AXES + FI void set(const T (&arr)[DISTINCT_AXES]) { x = arr[0]; y = arr[1]; } + #endif + #endif + + // Length reduced to one dimension FI T magnitude() const { return (T)sqrtf(x*x + y*y); } + // Pointer to the data as a simple array FI operator T* () { return pos; } + // If any element is true then it's true FI operator bool() { return x || y; } + + // Explicit copy and copies with conversion 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) }; } @@ -217,17 +286,27 @@ struct XYval { FI XYval asFloat() { return { static_cast(x), static_cast(y) }; } FI XYval asFloat() const { return { static_cast(x), static_cast(y) }; } FI XYval reciprocal() const { return { _RECIP(x), _RECIP(y) }; } + + // Marlin workspace shifting is done with G92 and M206 FI XYval asLogical() const { XYval o = asFloat(); toLogical(o); return o; } FI XYval asNative() const { XYval o = asFloat(); toNative(o); return o; } + + // Cast to a type with more fields by making a new object 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]; } + + // Accessor via an AxisEnum (or any integer) [index] + FI T& operator[](const int n) { return pos[n]; } + FI const T& operator[](const int n) const { return pos[n]; } + + // Assignment operator overrides do the expected thing 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; } + + // Override other operators to get intuitive behaviors 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; } @@ -264,6 +343,10 @@ struct XYval { 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 const XYval operator-() const { XYval o = *this; o.x = -x; o.y = -y; return o; } + FI XYval operator-() { XYval o = *this; o.x = -x; o.y = -y; return o; } + + // Modifier operators 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; } @@ -277,6 +360,8 @@ struct XYval { 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; } + + // Exact comparisons. For floats a "NEAR" operation may be better. 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; } @@ -289,224 +374,291 @@ struct XYval { FI bool operator!=(const XYval &rs) const { return !operator==(rs); } FI bool operator!=(const XYZval &rs) const { return !operator==(rs); } FI bool operator!=(const XYZEval &rs) const { return !operator==(rs); } - 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. +// Linear Axes coordinates, counters, flags, etc. // template struct XYZval { union { - struct { T x, y, z; }; - struct { T a, b, c; }; - T pos[3]; + struct { T LINEAR_AXIS_ARGS(); }; + struct { T LINEAR_AXIS_LIST(a, b, c, u, v, w); }; + T pos[LINEAR_AXES]; }; + + // Set all to 0 + FI void reset() { LINEAR_AXIS_GANG(x =, y =, z =, i =, j =, k =) 0; } + + // Setters taking struct types and arrays 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 set(const XYval pxy) { x = pxy.x; y = pxy.y; } + FI void set(const XYval pxy, const T pz) { LINEAR_AXIS_CODE(x = pxy.x, y = pxy.y, z = pz, NOOP, NOOP, NOOP); } FI void set(const T (&arr)[XY]) { x = arr[0]; y = arr[1]; } - FI void set(const T (&arr)[XYZ]) { x = arr[0]; y = arr[1]; z = arr[2]; } - FI void set(const T (&arr)[XYZE]) { x = arr[0]; y = arr[1]; z = arr[2]; } - #if DISTINCT_AXES > XYZE - FI void set(const T (&arr)[DISTINCT_AXES]) { x = arr[0]; y = arr[1]; z = arr[2]; } + #if HAS_Z_AXIS + FI void set(const T (&arr)[LINEAR_AXES]) { LINEAR_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5]); } + FI void set(LINEAR_AXIS_ARGS(const T)) { LINEAR_AXIS_CODE(a = x, b = y, c = z, u = i, v = j, w = k ); } + #endif + #if LOGICAL_AXES > LINEAR_AXES + FI void set(const T (&arr)[LOGICAL_AXES]) { LINEAR_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5]); } + FI void set(LOGICAL_AXIS_ARGS(const T)) { LINEAR_AXIS_CODE(a = x, b = y, c = z, u = i, v = j, w = k ); } + #if DISTINCT_AXES > LOGICAL_AXES + FI void set(const T (&arr)[DISTINCT_AXES]) { LINEAR_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5]); } + #endif + #endif + #if LINEAR_AXES >= 4 + FI void set(const T px, const T py, const T pz) { x = px; y = py; z = pz; } + #endif + #if LINEAR_AXES >= 5 + FI void set(const T px, const T py, const T pz, const T pi) { x = px; y = py; z = pz; i = pi; } #endif - FI void reset() { x = y = z = 0; } - FI T magnitude() const { return (T)sqrtf(x*x + y*y + z*z); } + #if LINEAR_AXES >= 6 + FI void set(const T px, const T py, const T pz, const T pi, const T pj) { x = px; y = py; z = pz; i = pi; j = pj; } + #endif + + // Length reduced to one dimension + FI T magnitude() const { return (T)sqrtf(LINEAR_AXIS_GANG(x*x, + y*y, + z*z, + i*i, + j*j, + k*k)); } + // Pointer to the data as a simple array FI operator T* () { return pos; } - FI operator bool() { return z || x || y; } + // If any element is true then it's true + FI operator bool() { return LINEAR_AXIS_GANG(x, || y, || z, || i, || j, || k); } + + // Explicit copy and copies with conversion 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 ROUNDL() { return { int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)) }; } - FI XYZval ROUNDL() const { return { int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)) }; } - FI XYZval asFloat() { return { static_cast(x), static_cast(y), static_cast(z) }; } - FI XYZval asFloat() const { return { static_cast(x), static_cast(y), static_cast(z) }; } - FI XYZval reciprocal() const { return { _RECIP(x), _RECIP(y), _RECIP(z) }; } + FI XYZval ABS() const { return LINEAR_AXIS_ARRAY(T(_ABS(x)), T(_ABS(y)), T(_ABS(z)), T(_ABS(i)), T(_ABS(j)), T(_ABS(k))); } + FI XYZval asInt() { return LINEAR_AXIS_ARRAY(int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k)); } + FI XYZval asInt() const { return LINEAR_AXIS_ARRAY(int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k)); } + FI XYZval asLong() { return LINEAR_AXIS_ARRAY(int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k)); } + FI XYZval asLong() const { return LINEAR_AXIS_ARRAY(int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k)); } + FI XYZval ROUNDL() { return LINEAR_AXIS_ARRAY(int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(i)), int32_t(LROUND(j)), int32_t(LROUND(k))); } + FI XYZval ROUNDL() const { return LINEAR_AXIS_ARRAY(int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(i)), int32_t(LROUND(j)), int32_t(LROUND(k))); } + FI XYZval asFloat() { return LINEAR_AXIS_ARRAY(static_cast(x), static_cast(y), static_cast(z), static_cast(i), static_cast(j), static_cast(k)); } + FI XYZval asFloat() const { return LINEAR_AXIS_ARRAY(static_cast(x), static_cast(y), static_cast(z), static_cast(i), static_cast(j), static_cast(k)); } + FI XYZval reciprocal() const { return LINEAR_AXIS_ARRAY(_RECIP(x), _RECIP(y), _RECIP(z), _RECIP(i), _RECIP(j), _RECIP(k)); } + + // Marlin workspace shifting is done with G92 and M206 FI XYZval asLogical() const { XYZval o = asFloat(); toLogical(o); return o; } FI XYZval asNative() const { XYZval o = asFloat(); toNative(o); return o; } + + // In-place cast to types having fewer fields 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; } + + // Cast to a type with more fields by making a new object + FI operator XYZEval() const { return LINEAR_AXIS_ARRAY(x, y, z, i, j, k); } + + // Accessor via an AxisEnum (or any integer) [index] + FI T& operator[](const int n) { return pos[n]; } + FI const T& operator[](const int n) const { return pos[n]; } + + // Assignment operator overrides do the expected thing + FI XYZval& operator= (const T v) { set(ARRAY_N_1(LINEAR_AXES, 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 *= v; return ls; } - FI XYZval operator* (const float &v) { XYZval ls = *this; ls.x *= v; ls.y *= v; ls.z *= v; return ls; } - FI XYZval operator* (const int &v) const { XYZval ls = *this; ls.x *= v; ls.y *= v; ls.z *= v; return ls; } - FI XYZval operator* (const int &v) { XYZval ls = *this; ls.x *= v; ls.y *= v; ls.z *= v; return ls; } - FI XYZval operator/ (const float &v) const { XYZval ls = *this; ls.x /= v; ls.y /= v; ls.z /= v; return ls; } - FI XYZval operator/ (const float &v) { XYZval ls = *this; ls.x /= v; ls.y /= v; ls.z /= v; return ls; } - FI XYZval operator/ (const int &v) const { XYZval ls = *this; ls.x /= v; ls.y /= v; ls.z /= v; return ls; } - FI XYZval operator/ (const int &v) { XYZval ls = *this; ls.x /= v; ls.y /= v; ls.z /= v; 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 XYZval& operator= (const XYZEval &rs) { set(LINEAR_AXIS_ELEM(rs)); return *this; } + + // Override other operators to get intuitive behaviors + FI XYZval operator+ (const XYval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, NOOP , NOOP , NOOP , NOOP ); return ls; } + FI XYZval operator+ (const XYval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, NOOP , NOOP , NOOP , NOOP ); return ls; } + FI XYZval operator- (const XYval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, NOOP , NOOP , NOOP , NOOP ); return ls; } + FI XYZval operator- (const XYval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, NOOP , NOOP , NOOP , NOOP ); return ls; } + FI XYZval operator* (const XYval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, NOOP , NOOP , NOOP , NOOP ); return ls; } + FI XYZval operator* (const XYval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, NOOP , NOOP , NOOP , NOOP ); return ls; } + FI XYZval operator/ (const XYval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, NOOP , NOOP , NOOP , NOOP ); return ls; } + FI XYZval operator/ (const XYval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, NOOP , NOOP , NOOP , NOOP ); return ls; } + FI XYZval operator+ (const XYZval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k); return ls; } + FI XYZval operator+ (const XYZval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k); return ls; } + FI XYZval operator- (const XYZval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k); return ls; } + FI XYZval operator- (const XYZval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k); return ls; } + FI XYZval operator* (const XYZval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k); return ls; } + FI XYZval operator* (const XYZval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k); return ls; } + FI XYZval operator/ (const XYZval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k); return ls; } + FI XYZval operator/ (const XYZval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k); return ls; } + FI XYZval operator+ (const XYZEval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k); return ls; } + FI XYZval operator+ (const XYZEval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k); return ls; } + FI XYZval operator- (const XYZEval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k); return ls; } + FI XYZval operator- (const XYZEval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k); return ls; } + FI XYZval operator* (const XYZEval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k); return ls; } + FI XYZval operator* (const XYZEval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k); return ls; } + FI XYZval operator/ (const XYZEval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k); return ls; } + FI XYZval operator/ (const XYZEval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k); return ls; } + FI XYZval operator* (const float &v) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v ); return ls; } + FI XYZval operator* (const float &v) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v ); return ls; } + FI XYZval operator* (const int &v) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v ); return ls; } + FI XYZval operator* (const int &v) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v ); return ls; } + FI XYZval operator/ (const float &v) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v ); return ls; } + FI XYZval operator/ (const float &v) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v ); return ls; } + FI XYZval operator/ (const int &v) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v ); return ls; } + FI XYZval operator/ (const int &v) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v ); return ls; } + FI XYZval operator>>(const int &v) const { XYZval ls = *this; LINEAR_AXIS_CODE(_RS(ls.x), _RS(ls.y), _RS(ls.z), _RS(ls.i), _RS(ls.j), _RS(ls.k) ); return ls; } + FI XYZval operator>>(const int &v) { XYZval ls = *this; LINEAR_AXIS_CODE(_RS(ls.x), _RS(ls.y), _RS(ls.z), _RS(ls.i), _RS(ls.j), _RS(ls.k) ); return ls; } + FI XYZval operator<<(const int &v) const { XYZval ls = *this; LINEAR_AXIS_CODE(_LS(ls.x), _LS(ls.y), _LS(ls.z), _LS(ls.i), _LS(ls.j), _LS(ls.k) ); return ls; } + FI XYZval operator<<(const int &v) { XYZval ls = *this; LINEAR_AXIS_CODE(_LS(ls.x), _LS(ls.y), _LS(ls.z), _LS(ls.i), _LS(ls.j), _LS(ls.k) ); return ls; } + FI const XYZval operator-() const { XYZval o = *this; LINEAR_AXIS_CODE(o.x = -x, o.y = -y, o.z = -z, o.i = -i, o.j = -j, o.k = -k); return o; } + FI XYZval operator-() { XYZval o = *this; LINEAR_AXIS_CODE(o.x = -x, o.y = -y, o.z = -z, o.i = -i, o.j = -j, o.k = -k); return o; } + + // Modifier operators + FI XYZval& operator+=(const XYval &rs) { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, NOOP, NOOP, NOOP, NOOP ); return *this; } + FI XYZval& operator-=(const XYval &rs) { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, NOOP, NOOP, NOOP, NOOP ); return *this; } + FI XYZval& operator*=(const XYval &rs) { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, NOOP, NOOP, NOOP, NOOP ); return *this; } + FI XYZval& operator/=(const XYval &rs) { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, NOOP, NOOP, NOOP, NOOP ); return *this; } + FI XYZval& operator+=(const XYZval &rs) { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k); return *this; } + FI XYZval& operator-=(const XYZval &rs) { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k); return *this; } + FI XYZval& operator*=(const XYZval &rs) { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k); return *this; } + FI XYZval& operator/=(const XYZval &rs) { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k); return *this; } + FI XYZval& operator+=(const XYZEval &rs) { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k); return *this; } + FI XYZval& operator-=(const XYZEval &rs) { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k); return *this; } + FI XYZval& operator*=(const XYZEval &rs) { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k); return *this; } + FI XYZval& operator/=(const XYZEval &rs) { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k); return *this; } + FI XYZval& operator*=(const float &v) { LINEAR_AXIS_CODE(x *= v, y *= v, z *= v, i *= v, j *= v, k *= v); return *this; } + FI XYZval& operator*=(const int &v) { LINEAR_AXIS_CODE(x *= v, y *= v, z *= v, i *= v, j *= v, k *= v); return *this; } + FI XYZval& operator>>=(const int &v) { LINEAR_AXIS_CODE(_RS(x), _RS(y), _RS(z), _RS(i), _RS(j), _RS(k)); return *this; } + FI XYZval& operator<<=(const int &v) { LINEAR_AXIS_CODE(_LS(x), _LS(y), _LS(z), _LS(i), _LS(j), _LS(k)); return *this; } + + // Exact comparisons. For floats a "NEAR" operation may be better. + FI bool operator==(const XYZEval &rs) { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k); } + FI bool operator==(const XYZEval &rs) const { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k); } 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. +// Logical Axes coordinates, counters, etc. // template struct XYZEval { union { - struct{ T x, y, z, e; }; - struct{ T a, b, c; }; - T pos[4]; + struct { T LOGICAL_AXIS_ARGS(); }; + struct { T LOGICAL_AXIS_LIST(_e, a, b, c, u, v, w); }; + T pos[LOGICAL_AXES]; }; - 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 void set(const T (&arr)[XY]) { x = arr[0]; y = arr[1]; } - FI void set(const T (&arr)[XYZ]) { x = arr[0]; y = arr[1]; z = arr[2]; } - FI void set(const T (&arr)[XYZE]) { x = arr[0]; y = arr[1]; z = arr[2]; e = arr[3]; } - #if DISTINCT_AXES > XYZE - FI void set(const T (&arr)[DISTINCT_AXES]) { x = arr[0]; y = arr[1]; z = arr[2]; e = arr[3]; } + // Reset all to 0 + FI void reset() { LOGICAL_AXIS_GANG(e =, x =, y =, z =, i =, j =, k =) 0; } + + // Setters taking struct types and arrays + 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 XYval pxy) { x = pxy.x; y = pxy.y; } + FI void set(const XYZval pxyz) { set(LINEAR_AXIS_ELEM(pxyz)); } + #if HAS_Z_AXIS + FI void set(LINEAR_AXIS_ARGS(const T)) { LINEAR_AXIS_CODE(a = x, b = y, c = z, u = i, v = j, w = k); } #endif - 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() { return { int32_t(x), int32_t(y), int32_t(z), int32_t(e) }; } - FI XYZEval asLong() const { return { int32_t(x), int32_t(y), int32_t(z), int32_t(e) }; } - FI XYZEval ROUNDL() { return { int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(e)) }; } - FI XYZEval ROUNDL() const { return { int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(e)) }; } - FI XYZEval asFloat() { return { static_cast(x), static_cast(y), static_cast(z), static_cast(e) }; } - FI XYZEval asFloat() const { return { static_cast(x), static_cast(y), static_cast(z), static_cast(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 }; } + #if LOGICAL_AXES > LINEAR_AXES + FI void set(const XYval pxy, const T pe) { set(pxy); e = pe; } + FI void set(const XYZval pxyz, const T pe) { set(pxyz); e = pe; } + FI void set(LOGICAL_AXIS_ARGS(const T)) { LOGICAL_AXIS_CODE(_e = e, a = x, b = y, c = z, u = i, v = j, w = k); } + #endif + #if LINEAR_AXES >= 4 + FI void set(const T px, const T py, const T pz) { x = px; y = py; z = pz; } + #endif + #if LINEAR_AXES >= 5 + FI void set(const T px, const T py, const T pz, const T pi) { x = px; y = py; z = pz; i = pi; } + #endif + #if LINEAR_AXES >= 6 + FI void set(const T px, const T py, const T pz, const T pi, const T pj) { x = px; y = py; z = pz; i = pi; j = pj; } + #endif + + // Length reduced to one dimension + FI T magnitude() const { return (T)sqrtf(LOGICAL_AXIS_GANG(+ e*e, + x*x, + y*y, + z*z, + i*i, + j*j, + k*k)); } + // Pointer to the data as a simple array + FI operator T* () { return pos; } + // If any element is true then it's true + FI operator bool() { return 0 LOGICAL_AXIS_GANG(|| e, || x, || y, || z, || i, || j, || k); } + + // Explicit copy and copies with conversion + FI XYZEval copy() const { XYZEval o = *this; return o; } + FI XYZEval ABS() const { return LOGICAL_AXIS_ARRAY(T(_ABS(e)), T(_ABS(x)), T(_ABS(y)), T(_ABS(z)), T(_ABS(i)), T(_ABS(j)), T(_ABS(k))); } + FI XYZEval asInt() { return LOGICAL_AXIS_ARRAY(int16_t(e), int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k)); } + FI XYZEval asInt() const { return LOGICAL_AXIS_ARRAY(int16_t(e), int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k)); } + FI XYZEval asLong() { return LOGICAL_AXIS_ARRAY(int32_t(e), int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k)); } + FI XYZEval asLong() const { return LOGICAL_AXIS_ARRAY(int32_t(e), int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k)); } + FI XYZEval ROUNDL() { return LOGICAL_AXIS_ARRAY(int32_t(LROUND(e)), int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(i)), int32_t(LROUND(j)), int32_t(LROUND(k))); } + FI XYZEval ROUNDL() const { return LOGICAL_AXIS_ARRAY(int32_t(LROUND(e)), int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(i)), int32_t(LROUND(j)), int32_t(LROUND(k))); } + FI XYZEval asFloat() { return LOGICAL_AXIS_ARRAY(static_cast(e), static_cast(x), static_cast(y), static_cast(z), static_cast(i), static_cast(j), static_cast(k)); } + FI XYZEval asFloat() const { return LOGICAL_AXIS_ARRAY(static_cast(e), static_cast(x), static_cast(y), static_cast(z), static_cast(i), static_cast(j), static_cast(k)); } + FI XYZEval reciprocal() const { return LOGICAL_AXIS_ARRAY(_RECIP(e), _RECIP(x), _RECIP(y), _RECIP(z), _RECIP(i), _RECIP(j), _RECIP(k)); } + + // Marlin workspace shifting is done with G92 and M206 + FI XYZEval asLogical() const { XYZEval o = asFloat(); toLogical(o); return o; } + FI XYZEval asNative() const { XYZEval o = asFloat(); toNative(o); return o; } + + // In-place cast to types having fewer fields + 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; } + + // Accessor via an AxisEnum (or any integer) [index] + FI T& operator[](const int n) { return pos[n]; } + FI const T& operator[](const int n) const { return pos[n]; } + + // Assignment operator overrides do the expected thing + FI XYZEval& operator= (const T v) { set(LIST_N_1(LINEAR_AXES, v)); return *this; } + FI XYZEval& operator= (const XYval &rs) { set(rs.x, rs.y); return *this; } + FI XYZEval& operator= (const XYZval &rs) { set(LINEAR_AXIS_ELEM(rs)); return *this; } + + // Override other operators to get intuitive behaviors + 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 { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k); return ls; } + FI XYZEval operator+ (const XYZval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k); return ls; } + FI XYZEval operator- (const XYZval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k); return ls; } + FI XYZEval operator- (const XYZval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k); return ls; } + FI XYZEval operator* (const XYZval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k); return ls; } + FI XYZEval operator* (const XYZval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k); return ls; } + FI XYZEval operator/ (const XYZval &rs) const { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k); return ls; } + FI XYZEval operator/ (const XYZval &rs) { XYZval ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k); return ls; } + FI XYZEval operator+ (const XYZEval &rs) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e += rs.e, ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k); return ls; } + FI XYZEval operator+ (const XYZEval &rs) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e += rs.e, ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k); return ls; } + FI XYZEval operator- (const XYZEval &rs) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e -= rs.e, ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k); return ls; } + FI XYZEval operator- (const XYZEval &rs) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e -= rs.e, ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k); return ls; } + FI XYZEval operator* (const XYZEval &rs) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= rs.e, ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k); return ls; } + FI XYZEval operator* (const XYZEval &rs) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= rs.e, ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k); return ls; } + FI XYZEval operator/ (const XYZEval &rs) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= rs.e, ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k); return ls; } + FI XYZEval operator/ (const XYZEval &rs) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= rs.e, ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k); return ls; } + FI XYZEval operator* (const float &v) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v ); return ls; } + FI XYZEval operator* (const float &v) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v ); return ls; } + FI XYZEval operator* (const int &v) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v ); return ls; } + FI XYZEval operator* (const int &v) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v ); return ls; } + FI XYZEval operator/ (const float &v) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v ); return ls; } + FI XYZEval operator/ (const float &v) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v ); return ls; } + FI XYZEval operator/ (const int &v) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v ); return ls; } + FI XYZEval operator/ (const int &v) { XYZEval ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v ); return ls; } + FI XYZEval operator>>(const int &v) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(_RS(ls.e), _RS(ls.x), _RS(ls.y), _RS(ls.z), _RS(ls.i), _RS(ls.j), _RS(ls.k) ); return ls; } + FI XYZEval operator>>(const int &v) { XYZEval ls = *this; LOGICAL_AXIS_CODE(_RS(ls.e), _RS(ls.x), _RS(ls.y), _RS(ls.z), _RS(ls.i), _RS(ls.j), _RS(ls.k) ); return ls; } + FI XYZEval operator<<(const int &v) const { XYZEval ls = *this; LOGICAL_AXIS_CODE(_LS(ls.e), _LS(ls.x), _LS(ls.y), _LS(ls.z), _LS(ls.i), _LS(ls.j), _LS(ls.k) ); return ls; } + FI XYZEval operator<<(const int &v) { XYZEval ls = *this; LOGICAL_AXIS_CODE(_LS(ls.e), _LS(ls.x), _LS(ls.y), _LS(ls.z), _LS(ls.i), _LS(ls.j), _LS(ls.k) ); return ls; } + FI const XYZEval operator-() const { return LOGICAL_AXIS_ARRAY(-e, -x, -y, -z, -i, -j, -k); } + FI XYZEval operator-() { return LOGICAL_AXIS_ARRAY(-e, -x, -y, -z, -i, -j, -k); } + + // Modifier operators + 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) { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k); return *this; } + FI XYZEval& operator-=(const XYZval &rs) { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k); return *this; } + FI XYZEval& operator*=(const XYZval &rs) { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k); return *this; } + FI XYZEval& operator/=(const XYZval &rs) { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k); return *this; } + FI XYZEval& operator+=(const XYZEval &rs) { LOGICAL_AXIS_CODE(e += rs.e, x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k); return *this; } + FI XYZEval& operator-=(const XYZEval &rs) { LOGICAL_AXIS_CODE(e -= rs.e, x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k); return *this; } + FI XYZEval& operator*=(const XYZEval &rs) { LOGICAL_AXIS_CODE(e *= rs.e, x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k); return *this; } + FI XYZEval& operator/=(const XYZEval &rs) { LOGICAL_AXIS_CODE(e /= rs.e, x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k); return *this; } + FI XYZEval& operator*=(const T &v) { LOGICAL_AXIS_CODE(e *= v, x *= v, y *= v, z *= v, i *= v, j *= v, k *= v); return *this; } + FI XYZEval& operator>>=(const int &v) { LOGICAL_AXIS_CODE(_RS(e), _RS(x), _RS(y), _RS(z), _RS(i), _RS(j), _RS(k)); return *this; } + FI XYZEval& operator<<=(const int &v) { LOGICAL_AXIS_CODE(_LS(e), _LS(x), _LS(y), _LS(z), _LS(i), _LS(j), _LS(k)); return *this; } + + // Exact comparisons. For floats a "NEAR" operation may be better. + FI bool operator==(const XYZval &rs) { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k); } + FI bool operator==(const XYZval &rs) const { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k); } + FI bool operator!=(const XYZval &rs) { return !operator==(rs); } + FI bool operator!=(const XYZval &rs) const { return !operator==(rs); } }; #undef _RECIP @@ -514,6 +666,3 @@ struct XYZEval { #undef _LS #undef _RS #undef FI - -const xyze_char_t axis_codes { 'X', 'Y', 'Z', 'E' }; -#define AXIS_CHAR(A) ((char)('X' + A)) diff --git a/Marlin/src/core/utility.cpp b/Marlin/src/core/utility.cpp index f4cdef43c8080..b810855d52266 100644 --- a/Marlin/src/core/utility.cpp +++ b/Marlin/src/core/utility.cpp @@ -122,7 +122,7 @@ void safe_delay(millis_t ms) { SERIAL_ECHOLNPAIR("Z Fade: ", planner.z_fade_height); #endif #if ABL_PLANAR - SERIAL_ECHOPGM("ABL Adjustment X"); + SERIAL_ECHOPGM("ABL Adjustment"); LOOP_LINEAR_AXES(a) { const float v = planner.get_axis_position_mm(AxisEnum(a)) - current_position[a]; SERIAL_CHAR(' ', AXIS_CHAR(a)); diff --git a/Marlin/src/core/utility.h b/Marlin/src/core/utility.h index d774b007b6d5e..d248091ce5752 100644 --- a/Marlin/src/core/utility.h +++ b/Marlin/src/core/utility.h @@ -76,3 +76,11 @@ class restorer { // Converts from an uint8_t in the range of 0-255 to an uint8_t // in the range 0-100 while avoiding rounding artifacts constexpr uint8_t ui8_to_percent(const uint8_t i) { return (int(i) * 100 + 127) / 255; } + +const xyze_char_t axis_codes LOGICAL_AXIS_ARRAY('E', 'X', 'Y', 'Z', AXIS4_NAME, AXIS5_NAME, AXIS6_NAME); + +#if LINEAR_AXES <= XYZ + #define AXIS_CHAR(A) ((char)('X' + A)) +#else + #define AXIS_CHAR(A) axis_codes[A] +#endif diff --git a/Marlin/src/feature/ammeter.cpp b/Marlin/src/feature/ammeter.cpp new file mode 100644 index 0000000000000..71b84f1121a0d --- /dev/null +++ b/Marlin/src/feature/ammeter.cpp @@ -0,0 +1,54 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 . + * + */ + +#include "../inc/MarlinConfig.h" + +#if ENABLED(I2C_AMMETER) + +#include "ammeter.h" + +#ifndef I2C_AMMETER_IMAX + #define I2C_AMMETER_IMAX 0.500 // Calibration range 500 Milliamps +#endif + +INA226 ina; + +Ammeter ammeter; + +float Ammeter::scale; +float Ammeter::current; + +void Ammeter::init() { + ina.begin(); + ina.configure(INA226_AVERAGES_16, INA226_BUS_CONV_TIME_1100US, INA226_SHUNT_CONV_TIME_1100US, INA226_MODE_SHUNT_BUS_CONT); + ina.calibrate(I2C_AMMETER_SHUNT_RESISTOR, I2C_AMMETER_IMAX); +} + +float Ammeter::read() { + scale = 1; + current = ina.readShuntCurrent(); + if (current <= 0.0001f) current = 0; // Clean up least-significant-bit amplification errors + if (current < 0.1f) scale = 1000; + return current * scale; +} + +#endif // I2C_AMMETER diff --git a/Marlin/src/feature/ammeter.h b/Marlin/src/feature/ammeter.h new file mode 100644 index 0000000000000..86f09bb9a197c --- /dev/null +++ b/Marlin/src/feature/ammeter.h @@ -0,0 +1,39 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 "../inc/MarlinConfigPre.h" + +#include +#include + +class Ammeter { +private: + static float scale; + +public: + static float current; + static void init(); + static float read(); +}; + +extern Ammeter ammeter; diff --git a/Marlin/src/feature/bedlevel/bedlevel.h b/Marlin/src/feature/bedlevel/bedlevel.h index 9bab2fbd2fa92..63f032eee87bc 100644 --- a/Marlin/src/feature/bedlevel/bedlevel.h +++ b/Marlin/src/feature/bedlevel/bedlevel.h @@ -24,7 +24,7 @@ #include "../../inc/MarlinConfigPre.h" #if EITHER(RESTORE_LEVELING_AFTER_G28, ENABLE_LEVELING_AFTER_G28) - #define G28_L0_ENSURES_LEVELING_OFF 1 + #define CAN_SET_LEVELING_AFTER_G28 1 #endif #if ENABLED(PROBE_MANUALLY) diff --git a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h index 1ae8135458f3c..cc54695771893 100644 --- a/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h +++ b/Marlin/src/feature/bedlevel/mbl/mesh_bed_leveling.h @@ -103,9 +103,7 @@ class mesh_bed_leveling { } static float get_z(const xy_pos_t &pos - #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - , const_float_t factor=1.0f - #endif + OPTARG(ENABLE_LEVELING_FADE_HEIGHT, const_float_t factor=1.0f) ) { #if DISABLED(ENABLE_LEVELING_FADE_HEIGHT) constexpr float factor = 1.0f; diff --git a/Marlin/src/feature/bedlevel/ubl/ubl.cpp b/Marlin/src/feature/bedlevel/ubl/ubl.cpp index b7a2c380ce89b..37c8be5bd8f53 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl.cpp @@ -164,7 +164,7 @@ static void serial_echo_column_labels(const uint8_t sp) { * 2: TODO: Display on Graphical LCD * 4: Compact Human-Readable */ -void unified_bed_leveling::display_map(const int map_type) { +void unified_bed_leveling::display_map(const uint8_t map_type) { const bool was = gcode.set_autoreport_paused(true); constexpr uint8_t eachsp = 1 + 6 + 1, // [-3.567] @@ -263,7 +263,7 @@ bool unified_bed_leveling::sanity_check() { void GcodeSuite::M1004() { #define ALIGN_GCODE TERN(Z_STEPPER_AUTO_ALIGN, "G34", "") - #define PROBE_GCODE TERN(HAS_BED_PROBE, "G29P1\nG29P3", "G29P4R255") + #define PROBE_GCODE TERN(HAS_BED_PROBE, "G29P1\nG29P3", "G29P4R") #if HAS_HOTEND if (parser.seenval('H')) { // Handle H# parameter to set Hotend temp diff --git a/Marlin/src/feature/bedlevel/ubl/ubl.h b/Marlin/src/feature/bedlevel/ubl/ubl.h index 562f15f74b9d4..cf00a282cfdd1 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl.h +++ b/Marlin/src/feature/bedlevel/ubl/ubl.h @@ -47,10 +47,10 @@ struct mesh_index_pair; typedef struct { bool C_seen; - int8_t V_verbosity, + int8_t KLS_storage_slot; + uint8_t R_repetition, + V_verbosity, P_phase, - R_repetition, - KLS_storage_slot, T_map_type; float B_shim_thickness, C_constant; @@ -98,7 +98,7 @@ class unified_bed_leveling { static void report_state(); static void save_ubl_active_state_and_disable(); static void restore_ubl_active_state_and_leave(); - static void display_map(const int) _O0; + static void display_map(const uint8_t) _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(); diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index b5773b0d46043..e144390c8de74 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -305,7 +305,7 @@ void unified_bed_leveling::G29() { bool probe_deployed = false; if (G29_parse_parameters()) return; // Abort on parameter error - const int8_t p_val = parser.intval('P', -1); + const uint8_t p_val = parser.byteval('P'); const bool may_move = p_val == 1 || p_val == 2 || p_val == 4 || parser.seen_test('J'); #if ENABLED(HAS_MULTI_HOTEND) const uint8_t old_tool_index = active_extruder; @@ -321,7 +321,7 @@ void unified_bed_leveling::G29() { // Invalidate one or more nearby mesh points, possibly all. if (parser.seen('I')) { - int16_t count = parser.has_value() ? parser.value_int() : 1; + uint8_t count = parser.has_value() ? parser.value_byte() : 1; bool invalidate_all = count >= GRID_MAX_POINTS; if (!invalidate_all) { while (count--) { @@ -345,7 +345,7 @@ void unified_bed_leveling::G29() { } if (parser.seen('Q')) { - const int test_pattern = parser.has_value() ? parser.value_int() : -99; + const int16_t test_pattern = parser.has_value() ? parser.value_int() : -99; if (!WITHIN(test_pattern, -1, 2)) { SERIAL_ECHOLNPGM("Invalid test_pattern value. (-1 to 2)\n"); return; @@ -592,7 +592,7 @@ void unified_bed_leveling::G29() { // if (parser.seen('L')) { // Load Current Mesh Data - param.KLS_storage_slot = parser.has_value() ? parser.value_int() : storage_slot; + param.KLS_storage_slot = parser.has_value() ? (int8_t)parser.value_int() : storage_slot; int16_t a = settings.calc_num_meshes(); @@ -617,10 +617,10 @@ void unified_bed_leveling::G29() { // if (parser.seen('S')) { // Store (or Save) Current Mesh Data - param.KLS_storage_slot = parser.has_value() ? parser.value_int() : storage_slot; + param.KLS_storage_slot = parser.has_value() ? (int8_t)parser.value_int() : storage_slot; - if (param.KLS_storage_slot == -1) // Special case, the user wants to 'Export' the mesh to the - return report_current_mesh(); // host program to be saved on the user's computer + if (param.KLS_storage_slot == -1) // Special case: 'Export' the mesh to the + return report_current_mesh(); // host so it can be saved in a file. int16_t a = settings.calc_num_meshes(); @@ -673,7 +673,7 @@ void unified_bed_leveling::G29() { */ void unified_bed_leveling::adjust_mesh_to_mean(const bool cflag, const_float_t offset) { float sum = 0; - int n = 0; + uint8_t n = 0; GRID_LOOP(x, y) if (!isnan(z_values[x][y])) { sum += z_values[x][y]; @@ -734,7 +734,7 @@ void unified_bed_leveling::shift_mesh_height() { do { if (do_ubl_mesh_map) display_map(param.T_map_type); - const int point_num = (GRID_MAX_POINTS) - count + 1; + const uint8_t point_num = (GRID_MAX_POINTS - count) + 1; SERIAL_ECHOLNPAIR("Probing mesh point ", point_num, "/", GRID_MAX_POINTS, "."); TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_MESH), point_num, int(GRID_MAX_POINTS))); @@ -1025,7 +1025,7 @@ void set_message_with_feedback(PGM_P const msg_P) { SET_SOFT_ENDSTOP_LOOSE(true); do { - idle(); + idle_no_sleep(); new_z = ui.ubl_mesh_value(); TERN_(UBL_MESH_EDIT_MOVES_Z, do_blocking_move_to_z(h_offset + new_z)); // Move the nozzle as the point is edited SERIAL_FLUSH(); // Prevent host M105 buffer overrun. @@ -1083,7 +1083,7 @@ bool unified_bed_leveling::G29_parse_parameters() { param.R_repetition = 0; if (parser.seen('R')) { - param.R_repetition = parser.has_value() ? parser.value_int() : GRID_MAX_POINTS; + param.R_repetition = parser.has_value() ? parser.value_byte() : GRID_MAX_POINTS; NOMORE(param.R_repetition, GRID_MAX_POINTS); if (param.R_repetition < 1) { SERIAL_ECHOLNPGM("?(R)epetition count invalid (1+).\n"); @@ -1091,14 +1091,14 @@ bool unified_bed_leveling::G29_parse_parameters() { } } - param.V_verbosity = parser.intval('V'); + param.V_verbosity = parser.byteval('V'); if (!WITHIN(param.V_verbosity, 0, 4)) { SERIAL_ECHOLNPGM("?(V)erbose level implausible (0-4).\n"); err_flag = true; } if (parser.seen('P')) { - const int pv = parser.value_int(); + const uint8_t pv = parser.value_byte(); #if !HAS_BED_PROBE if (pv == 1) { SERIAL_ECHOLNPGM("G29 P1 requires a probe.\n"); @@ -1181,7 +1181,7 @@ bool unified_bed_leveling::G29_parse_parameters() { } #endif - param.T_map_type = parser.intval('T'); + param.T_map_type = parser.byteval('T'); if (!WITHIN(param.T_map_type, 0, 2)) { SERIAL_ECHOLNPGM("Invalid map type.\n"); return UBL_ERR; @@ -1833,7 +1833,7 @@ void unified_bed_leveling::smart_fill_mesh() { return; } - param.KLS_storage_slot = parser.value_int(); + param.KLS_storage_slot = (int8_t)parser.value_int(); float tmp_z_values[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y]; settings.load_mesh(param.KLS_storage_slot, &tmp_z_values); diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp index 3ebc5fc2bdaf5..20408d8d1e81f 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp @@ -113,20 +113,22 @@ const xy_float_t ad = sign * dist; const bool use_x_dist = ad.x > ad.y; - float on_axis_distance = use_x_dist ? dist.x : dist.y, - e_position = end.e - start.e, - z_position = end.z - start.z; + float on_axis_distance = use_x_dist ? dist.x : dist.y; - const float e_normalized_dist = e_position / on_axis_distance, // Allow divide by zero - z_normalized_dist = z_position / on_axis_distance; + const float z_normalized_dist = (end.z - start.z) / on_axis_distance; // Allow divide by zero + #if HAS_EXTRUDERS + const float e_normalized_dist = (end.e - start.e) / on_axis_distance; + const bool inf_normalized_flag = isinf(e_normalized_dist); + #endif xy_int8_t icell = istart; 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), - inf_ratio_flag = isinf(ratio); + const bool inf_ratio_flag = isinf(ratio); + + xyze_pos_t dest; // Stores XYZE for segmented moves /** * Handle vertical lines that stay within one column. @@ -143,34 +145,36 @@ * For others the next X is the same so this can continue. * Calculate X at the next Y mesh line. */ - const float rx = inf_ratio_flag ? start.x : (next_mesh_line_y - c) / ratio; + dest.x = inf_ratio_flag ? start.x : (next_mesh_line_y - c) / ratio; - float z0 = z_correction_for_x_on_horizontal_mesh_line(rx, icell.x, icell.y) + float z0 = z_correction_for_x_on_horizontal_mesh_line(dest.x, 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(icell.y); + dest.y = 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) { + if (dest.y != 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; + on_axis_distance = use_x_dist ? dest.x - start.x : dest.y - start.y; + TERN_(HAS_EXTRUDERS, dest.e = start.e + on_axis_distance * e_normalized_dist); + dest.z = start.z + on_axis_distance * z_normalized_dist; } else { - e_position = end.e; - z_position = end.z; + TERN_(HAS_EXTRUDERS, dest.e = end.e); + dest.z = end.z; } - planner.buffer_segment(rx, ry, z_position + z0, e_position, scaled_fr_mm_s, extruder); + dest.z += z0; + planner.buffer_segment(dest, scaled_fr_mm_s, extruder); + } //else printf("FIRST MOVE PRUNED "); } @@ -188,12 +192,13 @@ */ 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 + dest.x = mesh_index_to_xpos(icell.x); + dest.y = ratio * dest.x + c; // Calculate Y at the next X mesh line - float z0 = z_correction_for_y_on_vertical_mesh_line(ry, icell.x, icell.y) + float z0 = z_correction_for_y_on_vertical_mesh_line(dest.y, icell.x, icell.y) * planner.fade_scaling_factor_for_z(end.z); // Undefined parts of the Mesh in z_values[][] are NAN. @@ -205,19 +210,20 @@ * 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) { + if (dest.x != start.x) { if (!inf_normalized_flag) { - 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; + on_axis_distance = use_x_dist ? dest.x - start.x : dest.y - start.y; + TERN_(HAS_EXTRUDERS, dest.e = start.e + on_axis_distance * e_normalized_dist); // Based on X or Y because the move is horizontal + dest.z = start.z + on_axis_distance * z_normalized_dist; } else { - e_position = end.e; - z_position = end.z; + TERN_(HAS_EXTRUDERS, dest.e = end.e); + dest.z = end.z; } - if (!planner.buffer_segment(rx, ry, z_position + z0, e_position, scaled_fr_mm_s, extruder)) - break; + dest.z += z0; + if (!planner.buffer_segment(dest, scaled_fr_mm_s, extruder)) break; + } //else printf("FIRST MOVE PRUNED "); } @@ -239,57 +245,65 @@ while (cnt) { 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 (neg.x == (rx > next_mesh_line_x)) { // Check if we hit the Y line first + next_mesh_line_y = mesh_index_to_ypos(icell.y + iadd.y); + + dest.y = ratio * next_mesh_line_x + c; // Calculate Y at the next X mesh line + dest.x = (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 (neg.x == (dest.x > 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, icell.x - ineg.x, icell.y + iadd.y) + float z0 = z_correction_for_x_on_horizontal_mesh_line(dest.x, 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; + dest.y = next_mesh_line_y; + if (!inf_normalized_flag) { - 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; + on_axis_distance = use_x_dist ? dest.x - start.x : dest.y - start.y; + TERN_(HAS_EXTRUDERS, dest.e = start.e + on_axis_distance * e_normalized_dist); + dest.z = start.z + on_axis_distance * z_normalized_dist; } else { - e_position = end.e; - z_position = end.z; + TERN_(HAS_EXTRUDERS, dest.e = end.e); + dest.z = end.z; } - if (!planner.buffer_segment(rx, next_mesh_line_y, z_position + z0, e_position, scaled_fr_mm_s, extruder)) - break; + + dest.z += z0; + if (!planner.buffer_segment(dest, scaled_fr_mm_s, extruder)) break; + 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, icell.x + iadd.x, icell.y - ineg.y) + float z0 = z_correction_for_y_on_vertical_mesh_line(dest.y, 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; + dest.x = next_mesh_line_x; + if (!inf_normalized_flag) { - 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; + on_axis_distance = use_x_dist ? dest.x - start.x : dest.y - start.y; + TERN_(HAS_EXTRUDERS, dest.e = start.e + on_axis_distance * e_normalized_dist); + dest.z = start.z + on_axis_distance * z_normalized_dist; } else { - e_position = end.e; - z_position = end.z; + TERN_(HAS_EXTRUDERS, dest.e = end.e); + dest.z = end.z; } - if (!planner.buffer_segment(next_mesh_line_x, ry, z_position + z0, e_position, scaled_fr_mm_s, extruder)) - break; + dest.z += z0; + if (!planner.buffer_segment(dest, scaled_fr_mm_s, extruder)) break; + icell.x += iadd.x; cnt.x--; } @@ -362,15 +376,11 @@ while (--segments) { raw += diff; planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, segment_xyz_mm - #if ENABLED(SCARA_FEEDRATE_SCALING) - , inv_duration - #endif + OPTARG(SCARA_FEEDRATE_SCALING, inv_duration) ); } planner.buffer_line(destination, scaled_fr_mm_s, active_extruder, segment_xyz_mm - #if ENABLED(SCARA_FEEDRATE_SCALING) - , inv_duration - #endif + OPTARG(SCARA_FEEDRATE_SCALING, inv_duration) ); return false; // Did not set current from destination } @@ -442,11 +452,9 @@ #endif ; - 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 - ); + const float oldz = raw.z; raw.z += z_cxcy; + planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, segment_xyz_mm OPTARG(SCARA_FEEDRATE_SCALING, inv_duration) ); + raw.z = oldz; if (segments == 0) // done with last segment return false; // didn't set current from destination diff --git a/Marlin/src/feature/binary_stream.h b/Marlin/src/feature/binary_stream.h index 9eb151b27fdbe..2ad7f236a174d 100644 --- a/Marlin/src/feature/binary_stream.h +++ b/Marlin/src/feature/binary_stream.h @@ -24,9 +24,11 @@ #include "../inc/MarlinConfig.h" #define BINARY_STREAM_COMPRESSION - #if ENABLED(BINARY_STREAM_COMPRESSION) #include "../libs/heatshrink/heatshrink_decoder.h" + // STM32 (and others?) require a word-aligned buffer for SD card transfers via DMA + static __attribute__((aligned(sizeof(size_t)))) uint8_t decode_buffer[512] = {}; + static heatshrink_decoder hsd; #endif inline bool bs_serial_data_available(const serial_index_t index) { @@ -37,16 +39,6 @@ inline int bs_read_serial(const serial_index_t index) { return SERIAL_IMPL.read(index); } -#if ENABLED(BINARY_STREAM_COMPRESSION) - static heatshrink_decoder hsd; - #if BOTH(ARDUINO_ARCH_STM32F1, SDIO_SUPPORT) - // STM32 requires a word-aligned buffer for SD card transfers via DMA - static __attribute__((aligned(sizeof(size_t)))) uint8_t decode_buffer[512] = {}; - #else - static uint8_t decode_buffer[512] = {}; - #endif -#endif - class SDFileTransferProtocol { private: struct Packet { diff --git a/Marlin/src/feature/caselight.cpp b/Marlin/src/feature/caselight.cpp index 5a4e2b2579dd4..1baef6d46845b 100644 --- a/Marlin/src/feature/caselight.cpp +++ b/Marlin/src/feature/caselight.cpp @@ -41,7 +41,7 @@ bool CaseLight::on = CASE_LIGHT_DEFAULT_ON; #if CASE_LIGHT_IS_COLOR_LED #include "leds/leds.h" constexpr uint8_t init_case_light[] = CASE_LIGHT_DEFAULT_COLOR; - LEDColor CaseLight::color = { init_case_light[0], init_case_light[1], init_case_light[2], TERN_(HAS_WHITE_LED, init_case_light[3]) }; + LEDColor CaseLight::color = { init_case_light[0], init_case_light[1], init_case_light[2] OPTARG(HAS_WHITE_LED, init_case_light[3]) }; #endif void CaseLight::update(const bool sflag) { @@ -65,9 +65,7 @@ void CaseLight::update(const bool sflag) { #endif #if CASE_LIGHT_IS_COLOR_LED - - leds.set_color(MakeLEDColor(color.r, color.g, color.b, color.w, n10ct)); - + leds.set_color(LEDColor(color.r, color.g, color.b OPTARG(HAS_WHITE_LED, color.w), n10ct)); #else // !CASE_LIGHT_IS_COLOR_LED #if CASELIGHT_USES_BRIGHTNESS diff --git a/Marlin/src/feature/dac/stepper_dac.cpp b/Marlin/src/feature/dac/stepper_dac.cpp index 1cb0813daa6c0..3abaece443597 100644 --- a/Marlin/src/feature/dac/stepper_dac.cpp +++ b/Marlin/src/feature/dac/stepper_dac.cpp @@ -85,10 +85,16 @@ void StepperDAC::print_values() { if (!dac_present) return; SERIAL_ECHO_MSG("Stepper current values in % (Amps):"); SERIAL_ECHO_START(); - SERIAL_ECHOPAIR_P( SP_X_LBL, dac_perc(X_AXIS), PSTR(" ("), dac_amps(X_AXIS), PSTR(")")); - SERIAL_ECHOPAIR_P( SP_Y_LBL, dac_perc(Y_AXIS), PSTR(" ("), dac_amps(Y_AXIS), PSTR(")")); - SERIAL_ECHOPAIR_P( SP_Z_LBL, dac_perc(Z_AXIS), PSTR(" ("), dac_amps(Z_AXIS), PSTR(")")); - SERIAL_ECHOLNPAIR_P(SP_E_LBL, dac_perc(E_AXIS), PSTR(" ("), dac_amps(E_AXIS), PSTR(")")); + SERIAL_ECHOPAIR_P(SP_X_LBL, dac_perc(X_AXIS), PSTR(" ("), dac_amps(X_AXIS), PSTR(")")); + #if HAS_Y_AXIS + SERIAL_ECHOPAIR_P(SP_Y_LBL, dac_perc(Y_AXIS), PSTR(" ("), dac_amps(Y_AXIS), PSTR(")")); + #endif + #if HAS_Z_AXIS + SERIAL_ECHOPAIR_P(SP_Z_LBL, dac_perc(Z_AXIS), PSTR(" ("), dac_amps(Z_AXIS), PSTR(")")); + #endif + #if HAS_EXTRUDERS + SERIAL_ECHOLNPAIR_P(SP_E_LBL, dac_perc(E_AXIS), PSTR(" ("), dac_amps(E_AXIS), PSTR(")")); + #endif } void StepperDAC::commit_eeprom() { diff --git a/Marlin/src/feature/encoder_i2c.cpp b/Marlin/src/feature/encoder_i2c.cpp index d6c88613fd816..c6881591b6b91 100644 --- a/Marlin/src/feature/encoder_i2c.cpp +++ b/Marlin/src/feature/encoder_i2c.cpp @@ -327,7 +327,7 @@ int32_t I2CPositionEncoder::get_raw_count() { } bool I2CPositionEncoder::test_axis() { - //only works on XYZ cartesian machines for the time being + // Only works on XYZ Cartesian machines for the time being if (!(encoderAxis == X_AXIS || encoderAxis == Y_AXIS || encoderAxis == Z_AXIS)) return false; const float startPosition = soft_endstop.min[encoderAxis] + 10, @@ -344,11 +344,14 @@ bool I2CPositionEncoder::test_axis() { startCoord[encoderAxis] = startPosition; endCoord[encoderAxis] = endPosition; - planner.synchronize(); - startCoord.e = planner.get_axis_position_mm(E_AXIS); - planner.buffer_line(startCoord, fr_mm_s, 0); planner.synchronize(); + #if HAS_EXTRUDERS + startCoord.e = planner.get_axis_position_mm(E_AXIS); + planner.buffer_line(startCoord, fr_mm_s, 0); + planner.synchronize(); + #endif + // if the module isn't currently trusted, wait until it is (or until it should be if things are working) if (!trusted) { int32_t startWaitingTime = millis(); @@ -357,7 +360,7 @@ bool I2CPositionEncoder::test_axis() { } if (trusted) { // if trusted, commence test - endCoord.e = planner.get_axis_position_mm(E_AXIS); + TERN_(HAS_EXTRUDERS, endCoord.e = planner.get_axis_position_mm(E_AXIS)); planner.buffer_line(endCoord, fr_mm_s, 0); planner.synchronize(); } @@ -402,7 +405,7 @@ void I2CPositionEncoder::calibrate_steps_mm(const uint8_t iter) { planner.synchronize(); LOOP_L_N(i, iter) { - startCoord.e = planner.get_axis_position_mm(E_AXIS); + TERN_(HAS_EXTRUDERS, startCoord.e = planner.get_axis_position_mm(E_AXIS)); planner.buffer_line(startCoord, fr_mm_s, 0); planner.synchronize(); @@ -411,7 +414,7 @@ void I2CPositionEncoder::calibrate_steps_mm(const uint8_t iter) { //do_blocking_move_to(endCoord); - endCoord.e = planner.get_axis_position_mm(E_AXIS); + TERN_(HAS_EXTRUDERS, endCoord.e = planner.get_axis_position_mm(E_AXIS)); planner.buffer_line(endCoord, fr_mm_s, 0); planner.synchronize(); @@ -497,9 +500,7 @@ void I2CPositionEncodersMgr::init() { encoders[i].set_active(encoders[i].passes_test(true)); - #if I2CPE_ENC_1_AXIS == E_AXIS - encoders[i].set_homed(); - #endif + TERN_(HAS_EXTRUDERS, if (I2CPE_ENC_1_AXIS == E_AXIS) encoders[i].set_homed()); #endif #if I2CPE_ENCODER_CNT > 1 @@ -528,9 +529,7 @@ void I2CPositionEncodersMgr::init() { encoders[i].set_active(encoders[i].passes_test(true)); - #if I2CPE_ENC_2_AXIS == E_AXIS - encoders[i].set_homed(); - #endif + TERN_(HAS_EXTRUDERS, if (I2CPE_ENC_2_AXIS == E_AXIS) encoders[i].set_homed()); #endif #if I2CPE_ENCODER_CNT > 2 @@ -557,11 +556,9 @@ void I2CPositionEncodersMgr::init() { encoders[i].set_ec_threshold(I2CPE_ENC_3_EC_THRESH); #endif - encoders[i].set_active(encoders[i].passes_test(true)); + encoders[i].set_active(encoders[i].passes_test(true)); - #if I2CPE_ENC_3_AXIS == E_AXIS - encoders[i].set_homed(); - #endif + TERN_(HAS_EXTRUDERS, if (I2CPE_ENC_3_AXIS == E_AXIS) encoders[i].set_homed()); #endif #if I2CPE_ENCODER_CNT > 3 @@ -590,9 +587,7 @@ void I2CPositionEncodersMgr::init() { encoders[i].set_active(encoders[i].passes_test(true)); - #if I2CPE_ENC_4_AXIS == E_AXIS - encoders[i].set_homed(); - #endif + TERN_(HAS_EXTRUDERS, if (I2CPE_ENC_4_AXIS == E_AXIS) encoders[i].set_homed()); #endif #if I2CPE_ENCODER_CNT > 4 @@ -621,9 +616,7 @@ void I2CPositionEncodersMgr::init() { encoders[i].set_active(encoders[i].passes_test(true)); - #if I2CPE_ENC_5_AXIS == E_AXIS - encoders[i].set_homed(); - #endif + TERN_(HAS_EXTRUDERS, if (I2CPE_ENC_5_AXIS == E_AXIS) encoders[i].set_homed()); #endif #if I2CPE_ENCODER_CNT > 5 @@ -652,9 +645,7 @@ void I2CPositionEncodersMgr::init() { encoders[i].set_active(encoders[i].passes_test(true)); - #if I2CPE_ENC_6_AXIS == E_AXIS - encoders[i].set_homed(); - #endif + TERN_(HAS_EXTRUDERS, if (I2CPE_ENC_6_AXIS == E_AXIS) encoders[i].set_homed()); #endif } diff --git a/Marlin/src/feature/fwretract.cpp b/Marlin/src/feature/fwretract.cpp index d133d6060c755..41dbf430e829d 100644 --- a/Marlin/src/feature/fwretract.cpp +++ b/Marlin/src/feature/fwretract.cpp @@ -91,11 +91,7 @@ void FWRetract::reset() { * Note: Auto-retract will apply the set Z hop in addition to any Z hop * included in the G-code. Use M207 Z0 to to prevent double hop. */ -void FWRetract::retract(const bool retracting - #if HAS_MULTI_EXTRUDER - , bool swapping/*=false*/ - #endif -) { +void FWRetract::retract(const bool retracting OPTARG(HAS_MULTI_EXTRUDER, bool swapping/*=false*/)) { // Prevent two retracts or recovers in a row if (retracted[active_extruder] == retracting) return; diff --git a/Marlin/src/feature/fwretract.h b/Marlin/src/feature/fwretract.h index 4fa64ad83b80d..cd93e9cf39ede 100644 --- a/Marlin/src/feature/fwretract.h +++ b/Marlin/src/feature/fwretract.h @@ -74,11 +74,7 @@ class FWRetract { #endif } - static void retract(const bool retracting - #if HAS_MULTI_EXTRUDER - , bool swapping = false - #endif - ); + static void retract(const bool retracting OPTARG(HAS_MULTI_EXTRUDER, bool swapping = false)); static void M207(); static void M207_report(const bool forReplay=false); diff --git a/Marlin/src/feature/leds/leds.cpp b/Marlin/src/feature/leds/leds.cpp index 8349049a00cc8..328daa626d462 100644 --- a/Marlin/src/feature/leds/leds.cpp +++ b/Marlin/src/feature/leds/leds.cpp @@ -47,9 +47,10 @@ #endif #if ENABLED(LED_COLOR_PRESETS) - const LEDColor LEDLights::defaultLEDColor = MakeLEDColor( - LED_USER_PRESET_RED, LED_USER_PRESET_GREEN, LED_USER_PRESET_BLUE, - LED_USER_PRESET_WHITE, LED_USER_PRESET_BRIGHTNESS + const LEDColor LEDLights::defaultLEDColor = LEDColor( + LED_USER_PRESET_RED, LED_USER_PRESET_GREEN, LED_USER_PRESET_BLUE + OPTARG(HAS_WHITE_LED, LED_USER_PRESET_WHITE) + OPTARG(NEOPIXEL_LED, LED_USER_PRESET_BRIGHTNESS) ); #endif @@ -75,36 +76,35 @@ void LEDLights::setup() { } void LEDLights::set_color(const LEDColor &incol - #if ENABLED(NEOPIXEL_LED) - , bool isSequence/*=false*/ - #endif + OPTARG(NEOPIXEL_IS_SEQUENTIAL, bool isSequence/*=false*/) ) { #if ENABLED(NEOPIXEL_LED) const uint32_t neocolor = LEDColorWhite() == incol ? neo.Color(NEO_WHITE) - : neo.Color(incol.r, incol.g, incol.b, incol.w); - static uint16_t nextLed = 0; - - #ifdef NEOPIXEL_BKGD_LED_INDEX - if (NEOPIXEL_BKGD_LED_INDEX == nextLed) { - neo.set_color_background(); - if (++nextLed >= neo.pixels()) { - nextLed = 0; - return; + : neo.Color(incol.r, incol.g, incol.b OPTARG(HAS_WHITE_LED, incol.w)); + + #if ENABLED(NEOPIXEL_IS_SEQUENTIAL) + static uint16_t nextLed = 0; + #ifdef NEOPIXEL_BKGD_INDEX_FIRST + while (WITHIN(nextLed, NEOPIXEL_BKGD_INDEX_FIRST, NEOPIXEL_BKGD_INDEX_LAST)) { + neo.reset_background_color(); + if (++nextLed >= neo.pixels()) { nextLed = 0; return; } } - } + #endif #endif neo.set_brightness(incol.i); - if (isSequence) { - neo.set_pixel_color(nextLed, neocolor); - neo.show(); - if (++nextLed >= neo.pixels()) nextLed = 0; - return; - } + #if ENABLED(NEOPIXEL_IS_SEQUENTIAL) + if (isSequence) { + neo.set_pixel_color(nextLed, neocolor); + neo.show(); + if (++nextLed >= neo.pixels()) nextLed = 0; + return; + } + #endif neo.set_color(neocolor); @@ -169,9 +169,10 @@ void LEDLights::set_color(const LEDColor &incol #if ENABLED(NEOPIXEL2_SEPARATE) #if ENABLED(NEO2_COLOR_PRESETS) - const LEDColor LEDLights2::defaultLEDColor = MakeLEDColor( - NEO2_USER_PRESET_RED, NEO2_USER_PRESET_GREEN, NEO2_USER_PRESET_BLUE, - NEO2_USER_PRESET_WHITE, NEO2_USER_PRESET_BRIGHTNESS + const LEDColor LEDLights2::defaultLEDColor = LEDColor( + LED_USER_PRESET_RED, LED_USER_PRESET_GREEN, LED_USER_PRESET_BLUE + OPTARG(HAS_WHITE_LED2, LED_USER_PRESET_WHITE) + OPTARG(NEOPIXEL_LED, LED_USER_PRESET_BRIGHTNESS) ); #endif @@ -190,7 +191,7 @@ void LEDLights::set_color(const LEDColor &incol void LEDLights2::set_color(const LEDColor &incol) { const uint32_t neocolor = LEDColorWhite() == incol ? neo2.Color(NEO2_WHITE) - : neo2.Color(incol.r, incol.g, incol.b, incol.w); + : neo2.Color(incol.r, incol.g, incol.b OPTARG(HAS_WHITE_LED2, incol.w)); neo2.set_brightness(incol.i); neo2.set_color(neocolor); diff --git a/Marlin/src/feature/leds/leds.h b/Marlin/src/feature/leds/leds.h index cec95102d7619..74964b51a8e46 100644 --- a/Marlin/src/feature/leds/leds.h +++ b/Marlin/src/feature/leds/leds.h @@ -29,60 +29,37 @@ #include -#if ENABLED(NEOPIXEL_LED) - #include "neopixel.h" -#endif - // A white component can be passed -#if ANY(RGBW_LED, NEOPIXEL_LED, PCA9632_RGBW) +#if EITHER(RGBW_LED, PCA9632_RGBW) #define HAS_WHITE_LED 1 #endif +#if ENABLED(NEOPIXEL_LED) + #define _NEOPIXEL_INCLUDE_ + #include "neopixel.h" + #undef _NEOPIXEL_INCLUDE_ +#endif + /** * LEDcolor type for use with leds.set_color */ typedef struct LEDColor { uint8_t r, g, b - #if HAS_WHITE_LED - , w - #if ENABLED(NEOPIXEL_LED) - , i - #endif - #endif + OPTARG(HAS_WHITE_LED, w) + OPTARG(NEOPIXEL_LED, i) ; LEDColor() : r(255), g(255), b(255) - #if HAS_WHITE_LED - , w(255) - #if ENABLED(NEOPIXEL_LED) - , i(NEOPIXEL_BRIGHTNESS) - #endif - #endif + OPTARG(HAS_WHITE_LED, w(255)) + OPTARG(NEOPIXEL_LED, i(NEOPIXEL_BRIGHTNESS)) {} - LEDColor(uint8_t r, uint8_t g, uint8_t b - #if HAS_WHITE_LED - , uint8_t w=0 - #if ENABLED(NEOPIXEL_LED) - , uint8_t i=NEOPIXEL_BRIGHTNESS - #endif - #endif - ) : r(r), g(g), b(b) - #if HAS_WHITE_LED - , w(w) - #if ENABLED(NEOPIXEL_LED) - , i(i) - #endif - #endif - {} + LEDColor(uint8_t r, uint8_t g, uint8_t b OPTARG(HAS_WHITE_LED, uint8_t w=0) OPTARG(NEOPIXEL_LED, uint8_t i=NEOPIXEL_BRIGHTNESS)) + : r(r), g(g), b(b) OPTARG(HAS_WHITE_LED, w(w)) OPTARG(NEOPIXEL_LED, i(i)) {} LEDColor(const uint8_t (&rgbw)[4]) : r(rgbw[0]), g(rgbw[1]), b(rgbw[2]) - #if HAS_WHITE_LED - , w(rgbw[3]) - #if ENABLED(NEOPIXEL_LED) - , i(NEOPIXEL_BRIGHTNESS) - #endif - #endif + OPTARG(HAS_WHITE_LED, w(rgbw[3])) + OPTARG(NEOPIXEL_LED, i(NEOPIXEL_BRIGHTNESS)) {} LEDColor& operator=(const uint8_t (&rgbw)[4]) { @@ -109,17 +86,8 @@ typedef struct LEDColor { } LEDColor; /** - * Color helpers and presets + * Color presets */ -#if HAS_WHITE_LED - #if ENABLED(NEOPIXEL_LED) - #define MakeLEDColor(R,G,B,W,I) LEDColor(R, G, B, W, I) - #else - #define MakeLEDColor(R,G,B,W,I) LEDColor(R, G, B, W) - #endif -#else - #define MakeLEDColor(R,G,B,W,I) LEDColor(R, G, B) -#endif #define LEDColorOff() LEDColor( 0, 0, 0) #define LEDColorRed() LEDColor(255, 0, 0) @@ -147,25 +115,15 @@ class LEDLights { static void setup(); // init() static void set_color(const LEDColor &color - #if ENABLED(NEOPIXEL_LED) - , bool isSequence=false - #endif + OPTARG(NEOPIXEL_IS_SEQUENTIAL, bool isSequence=false) ); static inline void set_color(uint8_t r, uint8_t g, uint8_t b - #if HAS_WHITE_LED - , uint8_t w=0 - #endif - #if ENABLED(NEOPIXEL_LED) - , uint8_t i=NEOPIXEL_BRIGHTNESS - , bool isSequence=false - #endif + OPTARG(HAS_WHITE_LED, uint8_t w=0) + OPTARG(NEOPIXEL_LED, uint8_t i=NEOPIXEL_BRIGHTNESS) + OPTARG(NEOPIXEL_IS_SEQUENTIAL, bool isSequence=false) ) { - set_color(MakeLEDColor(r, g, b, w, i) - #if ENABLED(NEOPIXEL_LED) - , isSequence - #endif - ); + set_color(LEDColor(r, g, b OPTARG(HAS_WHITE_LED, w) OPTARG(NEOPIXEL_LED, i)) OPTARG(NEOPIXEL_IS_SEQUENTIAL, isSequence)); } static inline void set_off() { set_color(LEDColorOff()); } @@ -223,8 +181,14 @@ extern LEDLights leds; static void set_color(const LEDColor &color); - inline void set_color(uint8_t r, uint8_t g, uint8_t b, uint8_t w=0, uint8_t i=NEOPIXEL2_BRIGHTNESS) { - set_color(MakeLEDColor(r, g, b, w, i)); + static inline void set_color(uint8_t r, uint8_t g, uint8_t b + OPTARG(HAS_WHITE_LED, uint8_t w=0) + OPTARG(NEOPIXEL_LED, uint8_t i=NEOPIXEL_BRIGHTNESS) + ) { + set_color(LEDColor(r, g, b + OPTARG(HAS_WHITE_LED, w) + OPTARG(NEOPIXEL_LED, i) + )); } static inline void set_off() { set_color(LEDColorOff()); } diff --git a/Marlin/src/feature/leds/neopixel.cpp b/Marlin/src/feature/leds/neopixel.cpp index bdd22837ada5f..2654e9a1df5a6 100644 --- a/Marlin/src/feature/leds/neopixel.cpp +++ b/Marlin/src/feature/leds/neopixel.cpp @@ -28,7 +28,7 @@ #if ENABLED(NEOPIXEL_LED) -#include "neopixel.h" +#include "leds.h" #if EITHER(NEOPIXEL_STARTUP_TEST, NEOPIXEL2_STARTUP_TEST) #include "../../core/utility.h" @@ -37,17 +37,21 @@ Marlin_NeoPixel neo; int8_t Marlin_NeoPixel::neoindex; -Adafruit_NeoPixel Marlin_NeoPixel::adaneo1(NEOPIXEL_PIXELS, NEOPIXEL_PIN, NEOPIXEL_TYPE + NEO_KHZ800) - #if CONJOINED_NEOPIXEL - , Marlin_NeoPixel::adaneo2(NEOPIXEL_PIXELS, NEOPIXEL2_PIN, NEOPIXEL2_TYPE + NEO_KHZ800) - #endif -; +Adafruit_NeoPixel Marlin_NeoPixel::adaneo1(NEOPIXEL_PIXELS, NEOPIXEL_PIN, NEOPIXEL_TYPE + NEO_KHZ800); +#if CONJOINED_NEOPIXEL + Adafruit_NeoPixel Marlin_NeoPixel::adaneo2(NEOPIXEL_PIXELS, NEOPIXEL2_PIN, NEOPIXEL2_TYPE + NEO_KHZ800); +#endif -#ifdef NEOPIXEL_BKGD_LED_INDEX +#ifdef NEOPIXEL_BKGD_INDEX_FIRST + + void Marlin_NeoPixel::set_background_color(uint8_t r, uint8_t g, uint8_t b, uint8_t w) { + for (int background_led = NEOPIXEL_BKGD_INDEX_FIRST; background_led <= NEOPIXEL_BKGD_INDEX_LAST; background_led++) + set_pixel_color(background_led, adaneo1.Color(r, g, b, w)); + } - void Marlin_NeoPixel::set_color_background() { - uint8_t background_color[4] = NEOPIXEL_BKGD_COLOR; - set_pixel_color(NEOPIXEL_BKGD_LED_INDEX, adaneo1.Color(background_color[0], background_color[1], background_color[2], background_color[3])); + void Marlin_NeoPixel::reset_background_color() { + constexpr uint8_t background_color[4] = NEOPIXEL_BKGD_COLOR; + set_background_color(background_color[0], background_color[1], background_color[2], background_color[3]); } #endif @@ -59,9 +63,10 @@ void Marlin_NeoPixel::set_color(const uint32_t color) { } else { for (uint16_t i = 0; i < pixels(); ++i) { - #ifdef NEOPIXEL_BKGD_LED_INDEX - if (i == NEOPIXEL_BKGD_LED_INDEX && TERN(NEOPIXEL_BKGD_ALWAYS_ON, true, color != 0x000000)) { - set_color_background(); + #ifdef NEOPIXEL_BKGD_INDEX_FIRST + if (i == NEOPIXEL_BKGD_INDEX_FIRST && TERN(NEOPIXEL_BKGD_ALWAYS_ON, true, color != 0x000000)) { + reset_background_color(); + i += NEOPIXEL_BKGD_INDEX_LAST - (NEOPIXEL_BKGD_INDEX_FIRST); continue; } #endif @@ -90,35 +95,22 @@ void Marlin_NeoPixel::init() { safe_delay(500); set_color_startup(adaneo1.Color(0, 0, 255, 0)); // blue safe_delay(500); + #if HAS_WHITE_LED + set_color_startup(adaneo1.Color(0, 0, 0, 255)); // white + safe_delay(500); + #endif #endif - #ifdef NEOPIXEL_BKGD_LED_INDEX - set_color_background(); - #endif - - #if ENABLED(LED_USER_PRESET_STARTUP) - set_color(adaneo1.Color(LED_USER_PRESET_RED, LED_USER_PRESET_GREEN, LED_USER_PRESET_BLUE, LED_USER_PRESET_WHITE)); - #else - set_color(adaneo1.Color(0, 0, 0, 0)); + #ifdef NEOPIXEL_BKGD_INDEX_FIRST + reset_background_color(); #endif -} -#if 0 -bool Marlin_NeoPixel::set_led_color(const uint8_t r, const uint8_t g, const uint8_t b, const uint8_t w, const uint8_t p) { - const uint32_t color = adaneo1.Color(r, g, b, w); - set_brightness(p); - #if DISABLED(NEOPIXEL_IS_SEQUENTIAL) - set_color(color); - return false; - #else - static uint16_t nextLed = 0; - set_pixel_color(nextLed, color); - show(); - if (++nextLed >= pixels()) nextLed = 0; - return true; - #endif + set_color(adaneo1.Color + TERN(LED_USER_PRESET_STARTUP, + (LED_USER_PRESET_RED, LED_USER_PRESET_GREEN, LED_USER_PRESET_BLUE, LED_USER_PRESET_WHITE), + (0, 0, 0, 0)) + ); } -#endif #if ENABLED(NEOPIXEL2_SEPARATE) @@ -158,13 +150,17 @@ bool Marlin_NeoPixel::set_led_color(const uint8_t r, const uint8_t g, const uint safe_delay(500); set_color_startup(adaneo.Color(0, 0, 255, 0)); // blue safe_delay(500); + #if HAS_WHITE_LED2 + set_color_startup(adaneo.Color(0, 0, 0, 255)); // white + safe_delay(500); + #endif #endif - #if ENABLED(NEO2_USER_PRESET_STARTUP) - set_color(adaneo.Color(NEO2_USER_PRESET_RED, NEO2_USER_PRESET_GREEN, NEO2_USER_PRESET_BLUE, NEO2_USER_PRESET_WHITE)); - #else - set_color(adaneo.Color(0, 0, 0, 0)); - #endif + set_color(adaneo.Color + TERN(NEO2_USER_PRESET_STARTUP, + (NEO2_USER_PRESET_RED, NEO2_USER_PRESET_GREEN, NEO2_USER_PRESET_BLUE, NEO2_USER_PRESET_WHITE), + (0, 0, 0, 0)) + ); } #endif // NEOPIXEL2_SEPARATE diff --git a/Marlin/src/feature/leds/neopixel.h b/Marlin/src/feature/leds/neopixel.h index acf2e7f54d3b2..b2c16459f5046 100644 --- a/Marlin/src/feature/leds/neopixel.h +++ b/Marlin/src/feature/leds/neopixel.h @@ -25,6 +25,10 @@ * NeoPixel support */ +#ifndef _NEOPIXEL_INCLUDE_ + #error "Always include 'leds.h' and not 'neopixel.h' directly." +#endif + // ------------------------ // Includes // ------------------------ @@ -38,24 +42,24 @@ // Defines // ------------------------ -#if defined(NEOPIXEL2_TYPE) && NEOPIXEL2_TYPE != NEOPIXEL_TYPE && DISABLED(NEOPIXEL2_SEPARATE) - #define MULTIPLE_NEOPIXEL_TYPES 1 -#endif +#define _NEO_IS_RGB(N) (N == NEO_RGB || N == NEO_RBG || N == NEO_GRB || N == NEO_GBR || N == NEO_BRG || N == NEO_BGR) -#if EITHER(MULTIPLE_NEOPIXEL_TYPES, NEOPIXEL2_INSERIES) - #define CONJOINED_NEOPIXEL 1 +#if !_NEO_IS_RGB(NEOPIXEL_TYPE) + #define HAS_WHITE_LED 1 #endif -#if NEOPIXEL_TYPE == NEO_RGB || NEOPIXEL_TYPE == NEO_RBG || NEOPIXEL_TYPE == NEO_GRB || NEOPIXEL_TYPE == NEO_GBR || NEOPIXEL_TYPE == NEO_BRG || NEOPIXEL_TYPE == NEO_BGR - #define NEOPIXEL_IS_RGB 1 +#if HAS_WHITE_LED + #define NEO_WHITE 0, 0, 0, 255 #else - #define NEOPIXEL_IS_RGBW 1 + #define NEO_WHITE 255, 255, 255 #endif -#if NEOPIXEL_IS_RGB - #define NEO_WHITE 255, 255, 255, 0 -#else - #define NEO_WHITE 0, 0, 0, 255 +#if defined(NEOPIXEL2_TYPE) && NEOPIXEL2_TYPE != NEOPIXEL_TYPE && DISABLED(NEOPIXEL2_SEPARATE) + #define MULTIPLE_NEOPIXEL_TYPES 1 +#endif + +#if EITHER(MULTIPLE_NEOPIXEL_TYPES, NEOPIXEL2_INSERIES) + #define CONJOINED_NEOPIXEL 1 #endif // ------------------------ @@ -64,11 +68,10 @@ class Marlin_NeoPixel { private: - static Adafruit_NeoPixel adaneo1 - #if CONJOINED_NEOPIXEL - , adaneo2 - #endif - ; + static Adafruit_NeoPixel adaneo1; + #if CONJOINED_NEOPIXEL + static Adafruit_NeoPixel adaneo2; + #endif public: static int8_t neoindex; @@ -78,8 +81,9 @@ class Marlin_NeoPixel { static void set_color(const uint32_t c); - #ifdef NEOPIXEL_BKGD_LED_INDEX - static void set_color_background(); + #ifdef NEOPIXEL_BKGD_INDEX_FIRST + static void set_background_color(uint8_t r, uint8_t g, uint8_t b, uint8_t w); + static void reset_background_color(); #endif static inline void begin() { @@ -93,9 +97,7 @@ class Marlin_NeoPixel { else adaneo1.setPixelColor(n, c); #else adaneo1.setPixelColor(n, c); - #if MULTIPLE_NEOPIXEL_TYPES - adaneo2.setPixelColor(n, c); - #endif + TERN_(MULTIPLE_NEOPIXEL_TYPES, adaneo2.setPixelColor(n, c)); #endif } @@ -112,7 +114,6 @@ class Marlin_NeoPixel { #if CONJOINED_NEOPIXEL adaneo2.show(); #else - IF_DISABLED(NEOPIXEL2_SEPARATE, adaneo1.setPin(NEOPIXEL2_PIN)); adaneo1.show(); adaneo1.setPin(NEOPIXEL_PIN); #endif @@ -120,15 +121,13 @@ class Marlin_NeoPixel { TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT()); } - #if 0 - bool set_led_color(const uint8_t r, const uint8_t g, const uint8_t b, const uint8_t w, const uint8_t p); - #endif - // Accessors - static inline uint16_t pixels() { TERN(NEOPIXEL2_INSERIES, return adaneo1.numPixels() * 2, return adaneo1.numPixels()); } + static inline uint16_t pixels() { return adaneo1.numPixels() * TERN1(NEOPIXEL2_INSERIES, 2); } + static inline uint8_t brightness() { return adaneo1.getBrightness(); } - static inline uint32_t Color(uint8_t r, uint8_t g, uint8_t b, uint8_t w) { - return adaneo1.Color(r, g, b, w); + + static inline uint32_t Color(uint8_t r, uint8_t g, uint8_t b OPTARG(HAS_WHITE_LED, uint8_t w)) { + return adaneo1.Color(r, g, b OPTARG(HAS_WHITE_LED, w)); } }; @@ -137,15 +136,12 @@ extern Marlin_NeoPixel neo; // Neo pixel channel 2 #if ENABLED(NEOPIXEL2_SEPARATE) - #if NEOPIXEL2_TYPE == NEO_RGB || NEOPIXEL2_TYPE == NEO_RBG || NEOPIXEL2_TYPE == NEO_GRB || NEOPIXEL2_TYPE == NEO_GBR || NEOPIXEL2_TYPE == NEO_BRG || NEOPIXEL2_TYPE == NEO_BGR + #if _NEO_IS_RGB(NEOPIXEL2_TYPE) #define NEOPIXEL2_IS_RGB 1 + #define NEO2_WHITE 255, 255, 255 #else #define NEOPIXEL2_IS_RGBW 1 - #endif - - #if NEOPIXEL2_IS_RGB - #define NEO2_WHITE 255, 255, 255, 0 - #else + #define HAS_WHITE_LED2 1 // A white component can be passed for NEOPIXEL2 #define NEO2_WHITE 0, 0, 0, 255 #endif @@ -172,11 +168,13 @@ extern Marlin_NeoPixel neo; // Accessors static inline uint16_t pixels() { return adaneo.numPixels();} static inline uint8_t brightness() { return adaneo.getBrightness(); } - static inline uint32_t Color(uint8_t r, uint8_t g, uint8_t b, uint8_t w) { - return adaneo.Color(r, g, b, w); + static inline uint32_t Color(uint8_t r, uint8_t g, uint8_t b OPTARG(HAS_WHITE_LED2, uint8_t w)) { + return adaneo.Color(r, g, b OPTARG(HAS_WHITE_LED2, w)); } }; extern Marlin_NeoPixel2 neo2; #endif // NEOPIXEL2_SEPARATE + +#undef _NEO_IS_RGB diff --git a/Marlin/src/feature/leds/pca9632.cpp b/Marlin/src/feature/leds/pca9632.cpp index bb30e0b48b0ee..abea988004519 100644 --- a/Marlin/src/feature/leds/pca9632.cpp +++ b/Marlin/src/feature/leds/pca9632.cpp @@ -93,9 +93,7 @@ static void PCA9632_WriteRegister(const byte addr, const byte regadd, const byte } static void PCA9632_WriteAllRegisters(const byte addr, const byte regadd, const byte vr, const byte vg, const byte vb - #if ENABLED(PCA9632_RGBW) - , const byte vw - #endif + OPTARG(PCA9632_RGBW, const byte vw) ) { #if DISABLED(PCA9632_NO_AUTO_INC) uint8_t data[4]; @@ -143,9 +141,7 @@ void PCA9632_set_led_color(const LEDColor &color) { ; PCA9632_WriteAllRegisters(PCA9632_ADDRESS,PCA9632_PWM0, color.r, color.g, color.b - #if ENABLED(PCA9632_RGBW) - , color.w - #endif + OPTARG(PCA9632_RGBW, color.w) ); PCA9632_WriteRegister(PCA9632_ADDRESS,PCA9632_LEDOUT, LEDOUT); } diff --git a/Marlin/src/feature/leds/printer_event_leds.cpp b/Marlin/src/feature/leds/printer_event_leds.cpp index 4765f82e56f65..e6407a6320a55 100644 --- a/Marlin/src/feature/leds/printer_event_leds.cpp +++ b/Marlin/src/feature/leds/printer_event_leds.cpp @@ -45,12 +45,10 @@ PrinterEventLEDs printerEventLEDs; return (uint8_t)map(constrain(current, start, target), start, target, 0, 255); } - inline void pel_set_rgb(const uint8_t r, const uint8_t g, const uint8_t b) { + inline void pel_set_rgb(const uint8_t r, const uint8_t g, const uint8_t b OPTARG(HAS_WHITE_LED, const uint8_t w=0)) { leds.set_color( - MakeLEDColor(r, g, b, 0, neo.brightness()) - #if ENABLED(NEOPIXEL_IS_SEQUENTIAL) - , true - #endif + LEDColor(r, g, b OPTARG(HAS_WHITE_LED, w) OPTARG(NEOPIXEL_LED, neo.brightness())) + OPTARG(NEOPIXEL_IS_SEQUENTIAL, true) ); } diff --git a/Marlin/src/feature/mmu/mmu.cpp b/Marlin/src/feature/mmu/mmu.cpp index 9a448296bbe24..718972313844e 100644 --- a/Marlin/src/feature/mmu/mmu.cpp +++ b/Marlin/src/feature/mmu/mmu.cpp @@ -24,7 +24,14 @@ #if HAS_PRUSA_MMU1 -#include "../module/stepper.h" +#include "../MarlinCore.h" +#include "../module/planner.h" + +void mmu_init() { + SET_OUTPUT(E_MUX0_PIN); + SET_OUTPUT(E_MUX1_PIN); + SET_OUTPUT(E_MUX2_PIN); +} void select_multiplexed_stepper(const uint8_t e) { planner.synchronize(); diff --git a/Marlin/src/feature/mmu/mmu.h b/Marlin/src/feature/mmu/mmu.h index 10805c8e26b7e..23742d00c61e8 100644 --- a/Marlin/src/feature/mmu/mmu.h +++ b/Marlin/src/feature/mmu/mmu.h @@ -21,4 +21,5 @@ */ #pragma once +void mmu_init(); void select_multiplexed_stepper(const uint8_t e); diff --git a/Marlin/src/feature/power.cpp b/Marlin/src/feature/power.cpp index fb2f1312e0658..87f0e9a7a1ba2 100644 --- a/Marlin/src/feature/power.cpp +++ b/Marlin/src/feature/power.cpp @@ -81,7 +81,10 @@ bool Power::is_power_needed() { #endif ) return true; - HOTEND_LOOP() if (thermalManager.degTargetHotend(e) > 0 || thermalManager.temp_hotend[e].soft_pwm_amount > 0) return true; + #if HAS_HOTEND + HOTEND_LOOP() if (thermalManager.degTargetHotend(e) > 0 || thermalManager.temp_hotend[e].soft_pwm_amount > 0) return true; + #endif + if (TERN0(HAS_HEATED_BED, thermalManager.degTargetBed() > 0 || thermalManager.temp_bed.soft_pwm_amount > 0)) return true; #if HAS_HOTEND && AUTO_POWER_E_TEMP @@ -105,12 +108,12 @@ bool Power::is_power_needed() { void Power::check() { static millis_t nextPowerCheck = 0; - millis_t ms = millis(); - if (ELAPSED(ms, nextPowerCheck)) { - nextPowerCheck = ms + 2500UL; + millis_t now = millis(); + if (ELAPSED(now, nextPowerCheck)) { + nextPowerCheck = now + 2500UL; if (is_power_needed()) power_on(); - else if (!lastPowerOn || (POWER_TIMEOUT > 0 && ELAPSED(ms, lastPowerOn + SEC_TO_MS(POWER_TIMEOUT)))) + else if (!lastPowerOn || (POWER_TIMEOUT > 0 && ELAPSED(now, lastPowerOn + SEC_TO_MS(POWER_TIMEOUT)))) power_off(); } } diff --git a/Marlin/src/feature/powerloss.h b/Marlin/src/feature/powerloss.h index 0fa9172fcf0b6..55180e539023f 100644 --- a/Marlin/src/feature/powerloss.h +++ b/Marlin/src/feature/powerloss.h @@ -88,7 +88,7 @@ typedef struct { uint8_t fan_speed[FAN_COUNT]; #endif - #if ENABLED(HAS_LEVELING) + #if HAS_LEVELING float fade; #endif @@ -120,7 +120,7 @@ typedef struct { bool raised:1; // Raised before saved bool dryrun:1; // M111 S8 bool allow_cold_extrusion:1; // M302 P1 - #if ENABLED(HAS_LEVELING) + #if HAS_LEVELING bool leveling:1; // M420 S #endif #if DISABLED(NO_VOLUMETRICS) diff --git a/Marlin/src/feature/probe_temp_comp.h b/Marlin/src/feature/probe_temp_comp.h index 2eeb7f47ec01e..f5f922410c171 100644 --- a/Marlin/src/feature/probe_temp_comp.h +++ b/Marlin/src/feature/probe_temp_comp.h @@ -47,7 +47,7 @@ typedef struct { // Probe temperature calibration constants #ifndef PTC_SAMPLE_COUNT - #define PTC_SAMPLE_COUNT 10U + #define PTC_SAMPLE_COUNT 10 #endif #ifndef PTC_SAMPLE_RES #define PTC_SAMPLE_RES 5 @@ -55,22 +55,22 @@ typedef struct { #ifndef PTC_SAMPLE_START #define PTC_SAMPLE_START 30 #endif -#define PTC_SAMPLE_END ((PTC_SAMPLE_START) + (PTC_SAMPLE_COUNT) * (PTC_SAMPLE_RES)) +#define PTC_SAMPLE_END (PTC_SAMPLE_START + (PTC_SAMPLE_COUNT) * PTC_SAMPLE_RES) // Bed temperature calibration constants #ifndef BTC_PROBE_TEMP #define BTC_PROBE_TEMP 30 #endif #ifndef BTC_SAMPLE_COUNT - #define BTC_SAMPLE_COUNT 10U + #define BTC_SAMPLE_COUNT 10 #endif -#ifndef BTC_SAMPLE_STEP +#ifndef BTC_SAMPLE_RES #define BTC_SAMPLE_RES 5 #endif #ifndef BTC_SAMPLE_START #define BTC_SAMPLE_START 60 #endif -#define BTC_SAMPLE_END ((BTC_SAMPLE_START) + (BTC_SAMPLE_COUNT) * (BTC_SAMPLE_RES)) +#define BTC_SAMPLE_END (BTC_SAMPLE_START + (BTC_SAMPLE_COUNT) * BTC_SAMPLE_RES) #ifndef PTC_PROBE_HEATING_OFFSET #define PTC_PROBE_HEATING_OFFSET 0.5f diff --git a/Marlin/src/feature/spindle_laser.cpp b/Marlin/src/feature/spindle_laser.cpp index 100b7c4b265fd..539fafeb34989 100644 --- a/Marlin/src/feature/spindle_laser.cpp +++ b/Marlin/src/feature/spindle_laser.cpp @@ -34,6 +34,10 @@ #include "../module/servo.h" #endif +#if ENABLED(I2C_AMMETER) + #include "../feature/ammeter.h" +#endif + SpindleLaser cutter; uint8_t SpindleLaser::power; #if ENABLED(LASER_FEATURE) @@ -74,6 +78,9 @@ void SpindleLaser::init() { #if ENABLED(AIR_ASSIST) OUT_WRITE(AIR_ASSIST_PIN, !AIR_ASSIST_ACTIVE); // Init Air Assist OFF #endif + #if ENABLED(I2C_AMMETER) + ammeter.init(); // Init I2C Ammeter + #endif } #if ENABLED(SPINDLE_LASER_PWM) diff --git a/Marlin/src/feature/tmc_util.cpp b/Marlin/src/feature/tmc_util.cpp index 9c4fbf08dfc81..48b26cc101def 100644 --- a/Marlin/src/feature/tmc_util.cpp +++ b/Marlin/src/feature/tmc_util.cpp @@ -417,6 +417,21 @@ } #endif + #if AXIS_IS_TMC(I) + if (monitor_tmc_driver(stepperI, need_update_error_counters, need_debug_reporting)) + step_current_down(stepperI); + #endif + + #if AXIS_IS_TMC(J) + if (monitor_tmc_driver(stepperJ, need_update_error_counters, need_debug_reporting)) + step_current_down(stepperJ); + #endif + + #if AXIS_IS_TMC(K) + if (monitor_tmc_driver(stepperK, need_update_error_counters, need_debug_reporting)) + step_current_down(stepperK); + #endif + #if AXIS_IS_TMC(E0) (void)monitor_tmc_driver(stepperE0, need_update_error_counters, need_debug_reporting); #endif @@ -757,128 +772,148 @@ } } - static void tmc_debug_loop(const TMC_debug_enum i, const bool print_x, const bool print_y, const bool print_z, const bool print_e) { - if (print_x) { + static void tmc_debug_loop(const TMC_debug_enum n, LOGICAL_AXIS_ARGS(const bool)) { + if (x) { #if AXIS_IS_TMC(X) - tmc_status(stepperX, i); + tmc_status(stepperX, n); #endif #if AXIS_IS_TMC(X2) - tmc_status(stepperX2, i); + tmc_status(stepperX2, n); #endif } - if (print_y) { + if (TERN0(HAS_Y_AXIS, y)) { #if AXIS_IS_TMC(Y) - tmc_status(stepperY, i); + tmc_status(stepperY, n); #endif #if AXIS_IS_TMC(Y2) - tmc_status(stepperY2, i); + tmc_status(stepperY2, n); #endif } - if (print_z) { + if (TERN0(HAS_Z_AXIS, z)) { #if AXIS_IS_TMC(Z) - tmc_status(stepperZ, i); + tmc_status(stepperZ, n); #endif #if AXIS_IS_TMC(Z2) - tmc_status(stepperZ2, i); + tmc_status(stepperZ2, n); #endif #if AXIS_IS_TMC(Z3) - tmc_status(stepperZ3, i); + tmc_status(stepperZ3, n); #endif #if AXIS_IS_TMC(Z4) - tmc_status(stepperZ4, i); + tmc_status(stepperZ4, n); #endif } - if (print_e) { + #if AXIS_IS_TMC(I) + if (i) tmc_status(stepperI, n); + #endif + #if AXIS_IS_TMC(J) + if (j) tmc_status(stepperJ, n); + #endif + #if AXIS_IS_TMC(K) + if (k) tmc_status(stepperK, n); + #endif + + if (TERN0(HAS_EXTRUDERS, e)) { #if AXIS_IS_TMC(E0) - tmc_status(stepperE0, i); + tmc_status(stepperE0, n); #endif #if AXIS_IS_TMC(E1) - tmc_status(stepperE1, i); + tmc_status(stepperE1, n); #endif #if AXIS_IS_TMC(E2) - tmc_status(stepperE2, i); + tmc_status(stepperE2, n); #endif #if AXIS_IS_TMC(E3) - tmc_status(stepperE3, i); + tmc_status(stepperE3, n); #endif #if AXIS_IS_TMC(E4) - tmc_status(stepperE4, i); + tmc_status(stepperE4, n); #endif #if AXIS_IS_TMC(E5) - tmc_status(stepperE5, i); + tmc_status(stepperE5, n); #endif #if AXIS_IS_TMC(E6) - tmc_status(stepperE6, i); + tmc_status(stepperE6, n); #endif #if AXIS_IS_TMC(E7) - tmc_status(stepperE7, i); + tmc_status(stepperE7, n); #endif } SERIAL_EOL(); } - static void drv_status_loop(const TMC_drv_status_enum i, const bool print_x, const bool print_y, const bool print_z, const bool print_e) { - if (print_x) { + static void drv_status_loop(const TMC_drv_status_enum n, LOGICAL_AXIS_ARGS(const bool)) { + if (x) { #if AXIS_IS_TMC(X) - tmc_parse_drv_status(stepperX, i); + tmc_parse_drv_status(stepperX, n); #endif #if AXIS_IS_TMC(X2) - tmc_parse_drv_status(stepperX2, i); + tmc_parse_drv_status(stepperX2, n); #endif } - if (print_y) { + if (TERN0(HAS_Y_AXIS, y)) { #if AXIS_IS_TMC(Y) - tmc_parse_drv_status(stepperY, i); + tmc_parse_drv_status(stepperY, n); #endif #if AXIS_IS_TMC(Y2) - tmc_parse_drv_status(stepperY2, i); + tmc_parse_drv_status(stepperY2, n); #endif } - if (print_z) { + if (TERN0(HAS_Z_AXIS, z)) { #if AXIS_IS_TMC(Z) - tmc_parse_drv_status(stepperZ, i); + tmc_parse_drv_status(stepperZ, n); #endif #if AXIS_IS_TMC(Z2) - tmc_parse_drv_status(stepperZ2, i); + tmc_parse_drv_status(stepperZ2, n); #endif #if AXIS_IS_TMC(Z3) - tmc_parse_drv_status(stepperZ3, i); + tmc_parse_drv_status(stepperZ3, n); #endif #if AXIS_IS_TMC(Z4) - tmc_parse_drv_status(stepperZ4, i); + tmc_parse_drv_status(stepperZ4, n); #endif } - if (print_e) { + #if AXIS_IS_TMC(I) + if (i) tmc_parse_drv_status(stepperI, n); + #endif + #if AXIS_IS_TMC(J) + if (j) tmc_parse_drv_status(stepperJ, n); + #endif + #if AXIS_IS_TMC(K) + if (k) tmc_parse_drv_status(stepperK, n); + #endif + + if (TERN0(HAS_EXTRUDERS, e)) { #if AXIS_IS_TMC(E0) - tmc_parse_drv_status(stepperE0, i); + tmc_parse_drv_status(stepperE0, n); #endif #if AXIS_IS_TMC(E1) - tmc_parse_drv_status(stepperE1, i); + tmc_parse_drv_status(stepperE1, n); #endif #if AXIS_IS_TMC(E2) - tmc_parse_drv_status(stepperE2, i); + tmc_parse_drv_status(stepperE2, n); #endif #if AXIS_IS_TMC(E3) - tmc_parse_drv_status(stepperE3, i); + tmc_parse_drv_status(stepperE3, n); #endif #if AXIS_IS_TMC(E4) - tmc_parse_drv_status(stepperE4, i); + tmc_parse_drv_status(stepperE4, n); #endif #if AXIS_IS_TMC(E5) - tmc_parse_drv_status(stepperE5, i); + tmc_parse_drv_status(stepperE5, n); #endif #if AXIS_IS_TMC(E6) - tmc_parse_drv_status(stepperE6, i); + tmc_parse_drv_status(stepperE6, n); #endif #if AXIS_IS_TMC(E7) - tmc_parse_drv_status(stepperE7, i); + tmc_parse_drv_status(stepperE7, n); #endif } @@ -889,9 +924,10 @@ * M122 report functions */ - void tmc_report_all(const bool print_x/*=true*/, const bool print_y/*=true*/, const bool print_z/*=true*/, const bool print_e/*=true*/) { - #define TMC_REPORT(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); tmc_debug_loop(ITEM, print_x, print_y, print_z, print_e); }while(0) - #define DRV_REPORT(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); drv_status_loop(ITEM, print_x, print_y, print_z, print_e); }while(0) + void tmc_report_all(LOGICAL_AXIS_ARGS(const bool)) { + #define TMC_REPORT(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); tmc_debug_loop(ITEM, LOGICAL_AXIS_ARGS()); }while(0) + #define DRV_REPORT(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); drv_status_loop(ITEM, LOGICAL_AXIS_ARGS()); }while(0) + TMC_REPORT("\t", TMC_CODES); #if HAS_DRIVER(TMC2209) TMC_REPORT("Address\t", TMC_UART_ADDR); @@ -1015,72 +1051,82 @@ } #endif - static void tmc_get_registers(TMC_get_registers_enum i, const bool print_x, const bool print_y, const bool print_z, const bool print_e) { - if (print_x) { + static void tmc_get_registers(TMC_get_registers_enum n, LOGICAL_AXIS_ARGS(const bool)) { + if (x) { #if AXIS_IS_TMC(X) - tmc_get_registers(stepperX, i); + tmc_get_registers(stepperX, n); #endif #if AXIS_IS_TMC(X2) - tmc_get_registers(stepperX2, i); + tmc_get_registers(stepperX2, n); #endif } - if (print_y) { + if (TERN0(HAS_Y_AXIS, y)) { #if AXIS_IS_TMC(Y) - tmc_get_registers(stepperY, i); + tmc_get_registers(stepperY, n); #endif #if AXIS_IS_TMC(Y2) - tmc_get_registers(stepperY2, i); + tmc_get_registers(stepperY2, n); #endif } - if (print_z) { + if (TERN0(HAS_Z_AXIS, z)) { #if AXIS_IS_TMC(Z) - tmc_get_registers(stepperZ, i); + tmc_get_registers(stepperZ, n); #endif #if AXIS_IS_TMC(Z2) - tmc_get_registers(stepperZ2, i); + tmc_get_registers(stepperZ2, n); #endif #if AXIS_IS_TMC(Z3) - tmc_get_registers(stepperZ3, i); + tmc_get_registers(stepperZ3, n); #endif #if AXIS_IS_TMC(Z4) - tmc_get_registers(stepperZ4, i); + tmc_get_registers(stepperZ4, n); #endif } - if (print_e) { + #if AXIS_IS_TMC(I) + if (i) tmc_get_registers(stepperI, n); + #endif + #if AXIS_IS_TMC(J) + if (j) tmc_get_registers(stepperJ, n); + #endif + #if AXIS_IS_TMC(K) + if (k) tmc_get_registers(stepperK, n); + #endif + + if (TERN0(HAS_EXTRUDERS, e)) { #if AXIS_IS_TMC(E0) - tmc_get_registers(stepperE0, i); + tmc_get_registers(stepperE0, n); #endif #if AXIS_IS_TMC(E1) - tmc_get_registers(stepperE1, i); + tmc_get_registers(stepperE1, n); #endif #if AXIS_IS_TMC(E2) - tmc_get_registers(stepperE2, i); + tmc_get_registers(stepperE2, n); #endif #if AXIS_IS_TMC(E3) - tmc_get_registers(stepperE3, i); + tmc_get_registers(stepperE3, n); #endif #if AXIS_IS_TMC(E4) - tmc_get_registers(stepperE4, i); + tmc_get_registers(stepperE4, n); #endif #if AXIS_IS_TMC(E5) - tmc_get_registers(stepperE5, i); + tmc_get_registers(stepperE5, n); #endif #if AXIS_IS_TMC(E6) - tmc_get_registers(stepperE6, i); + tmc_get_registers(stepperE6, n); #endif #if AXIS_IS_TMC(E7) - tmc_get_registers(stepperE7, i); + tmc_get_registers(stepperE7, n); #endif } SERIAL_EOL(); } - void tmc_get_registers(bool print_x, bool print_y, bool print_z, bool print_e) { - #define _TMC_GET_REG(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); tmc_get_registers(ITEM, print_x, print_y, print_z, print_e); }while(0) + void tmc_get_registers(LOGICAL_AXIS_ARGS(bool)) { + #define _TMC_GET_REG(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); tmc_get_registers(ITEM, LOGICAL_AXIS_ARGS()); }while(0) #define TMC_GET_REG(NAME, TABS) _TMC_GET_REG(STRINGIFY(NAME) TABS, TMC_GET_##NAME) _TMC_GET_REG("\t", TMC_AXIS_CODES); TMC_GET_REG(GCONF, "\t\t"); @@ -1165,6 +1211,15 @@ #if AXIS_HAS_SPI(Z4) SET_CS_PIN(Z4); #endif + #if AXIS_HAS_SPI(I) + SET_CS_PIN(I); + #endif + #if AXIS_HAS_SPI(J) + SET_CS_PIN(J); + #endif + #if AXIS_HAS_SPI(K) + SET_CS_PIN(K); + #endif #if AXIS_HAS_SPI(E0) SET_CS_PIN(E0); #endif @@ -1214,10 +1269,10 @@ static bool test_connection(TMC &st) { return test_result; } -void test_tmc_connection(const bool test_x/*=true*/, const bool test_y/*=true*/, const bool test_z/*=true*/, const bool test_e/*=true*/) { +void test_tmc_connection(LOGICAL_AXIS_ARGS(const bool)) { uint8_t axis_connection = 0; - if (test_x) { + if (x) { #if AXIS_IS_TMC(X) axis_connection += test_connection(stepperX); #endif @@ -1226,7 +1281,7 @@ void test_tmc_connection(const bool test_x/*=true*/, const bool test_y/*=true*/, #endif } - if (test_y) { + if (TERN0(HAS_Y_AXIS, y)) { #if AXIS_IS_TMC(Y) axis_connection += test_connection(stepperY); #endif @@ -1235,7 +1290,7 @@ void test_tmc_connection(const bool test_x/*=true*/, const bool test_y/*=true*/, #endif } - if (test_z) { + if (TERN0(HAS_Z_AXIS, z)) { #if AXIS_IS_TMC(Z) axis_connection += test_connection(stepperZ); #endif @@ -1250,7 +1305,17 @@ void test_tmc_connection(const bool test_x/*=true*/, const bool test_y/*=true*/, #endif } - if (test_e) { + #if AXIS_IS_TMC(I) + if (i) axis_connection += test_connection(stepperI); + #endif + #if AXIS_IS_TMC(J) + if (j) axis_connection += test_connection(stepperJ); + #endif + #if AXIS_IS_TMC(K) + if (k) axis_connection += test_connection(stepperK); + #endif + + if (TERN0(HAS_EXTRUDERS, e)) { #if AXIS_IS_TMC(E0) axis_connection += test_connection(stepperE0); #endif diff --git a/Marlin/src/feature/tmc_util.h b/Marlin/src/feature/tmc_util.h index a0e07ab8a8c65..741b840ec74ba 100644 --- a/Marlin/src/feature/tmc_util.h +++ b/Marlin/src/feature/tmc_util.h @@ -70,15 +70,9 @@ class TMCStorage { } struct { - #if ENABLED(HAS_STEALTHCHOP) - bool stealthChop_enabled = false; - #endif - #if ENABLED(HYBRID_THRESHOLD) - uint8_t hybrid_thrs = 0; - #endif - #if ENABLED(USE_SENSORLESS) - int16_t homing_thrs = 0; - #endif + OPTCODE(HAS_STEALTHCHOP, bool stealthChop_enabled = false) + OPTCODE(HYBRID_THRESHOLD, uint8_t hybrid_thrs = 0) + OPTCODE(USE_SENSORLESS, int16_t homing_thrs = 0) } stored; }; @@ -341,14 +335,14 @@ void tmc_print_current(TMC &st) { #endif void monitor_tmc_drivers(); -void test_tmc_connection(const bool test_x=true, const bool test_y=true, const bool test_z=true, const bool test_e=true); +void test_tmc_connection(LOGICAL_AXIS_DECL(const bool, true)); #if ENABLED(TMC_DEBUG) #if ENABLED(MONITOR_DRIVER_STATUS) void tmc_set_report_interval(const uint16_t update_interval); #endif - void tmc_report_all(const bool print_x=true, const bool print_y=true, const bool print_z=true, const bool print_e=true); - void tmc_get_registers(const bool print_x, const bool print_y, const bool print_z, const bool print_e); + void tmc_report_all(LOGICAL_AXIS_DECL(const bool, true)); + void tmc_get_registers(LOGICAL_AXIS_ARGS(const bool)); #endif /** @@ -361,16 +355,16 @@ void test_tmc_connection(const bool test_x=true, const bool test_y=true, const b #if USE_SENSORLESS // Track enabled status of stealthChop and only re-enable where applicable - struct sensorless_t { bool x, y, z, x2, y2, z2, z3, z4; }; + struct sensorless_t { bool LINEAR_AXIS_ARGS(), x2, y2, z2, z3, z4; }; #if ENABLED(IMPROVE_HOMING_RELIABILITY) extern millis_t sg_guard_period; constexpr uint16_t default_sg_guard_duration = 400; - struct slow_homing_t { + struct motion_state_t { xy_ulong_t acceleration; #if ENABLED(HAS_CLASSIC_JERK) - xy_float_t jerk_xy; + xy_float_t jerk_state; #endif }; #endif diff --git a/Marlin/src/gcode/bedlevel/G26.cpp b/Marlin/src/gcode/bedlevel/G26.cpp index 1e70652bdcef4..882197139ee1f 100644 --- a/Marlin/src/gcode/bedlevel/G26.cpp +++ b/Marlin/src/gcode/bedlevel/G26.cpp @@ -291,7 +291,7 @@ typedef struct { if (p2.x < 0 || p2.x >= (GRID_MAX_POINTS_X)) return; if (p2.y < 0 || p2.y >= (GRID_MAX_POINTS_Y)) return; - if(circle_flags.marked(p1.x, p1.y) && circle_flags.marked(p2.x, p2.y)) { + if (circle_flags.marked(p1.x, p1.y) && circle_flags.marked(p2.x, p2.y)) { xyz_pos_t s, e; s.x = _GET_MESH_X(p1.x) + (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)) * dx; e.x = _GET_MESH_X(p2.x) - (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)) * dx; @@ -330,12 +330,8 @@ typedef struct { thermalManager.setTargetBed(bed_temp); // Wait for the temperature to stabilize - if (!thermalManager.wait_for_bed(true - #if G26_CLICK_CAN_CANCEL - , true - #endif - ) - ) return G26_ERR; + if (!thermalManager.wait_for_bed(true OPTARG(G26_CLICK_CAN_CANCEL, true))) + return G26_ERR; } #else @@ -352,11 +348,8 @@ typedef struct { thermalManager.setTargetHotend(hotend_temp, active_extruder); // Wait for the temperature to stabilize - if (!thermalManager.wait_for_hotend(active_extruder, true - #if G26_CLICK_CAN_CANCEL - , true - #endif - )) return G26_ERR; + if (!thermalManager.wait_for_hotend(active_extruder, true OPTARG(G26_CLICK_CAN_CANCEL, true))) + return G26_ERR; #if HAS_WIRED_LCD ui.reset_status(); diff --git a/Marlin/src/gcode/bedlevel/G35.cpp b/Marlin/src/gcode/bedlevel/G35.cpp index ad2cc67db0412..44df6d9273bfc 100644 --- a/Marlin/src/gcode/bedlevel/G35.cpp +++ b/Marlin/src/gcode/bedlevel/G35.cpp @@ -91,8 +91,8 @@ void GcodeSuite::G35() { // Disable duplication mode on homing TERN_(HAS_DUPLICATION_MODE, set_duplication_enabled(false)); - // Home all before this procedure - home_all_axes(); + // Home only Z axis when X and Y is trusted, otherwise all axes, if needed before this procedure + if (!all_axes_trusted()) process_subcommands_now_P(PSTR("G28Z")); bool err_break = false; diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index a8c3f45cdca53..729bca93a6007 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -246,7 +246,7 @@ G29_TYPE GcodeSuite::G29() { // Send 'N' to force homing before G29 (internal only) if (parser.seen_test('N')) - process_subcommands_now_P(TERN(G28_L0_ENSURES_LEVELING_OFF, PSTR("G28L0"), G28_STR)); + process_subcommands_now_P(TERN(CAN_SET_LEVELING_AFTER_G28, PSTR("G28L0"), G28_STR)); // Don't allow auto-leveling without homing first if (homing_needed_error()) G29_RETURN(false); @@ -689,7 +689,7 @@ G29_TYPE GcodeSuite::G29() { TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/3"), GET_TEXT(MSG_PROBING_MESH), int(i + 1))); // Retain the last probe position - abl.probePos = points[i]; + abl.probePos = xy_pos_t(points[i]); abl.measured_z = faux ? 0.001 * random(-100, 101) : probe.probe_at_point(abl.probePos, raise_after, abl.verbose_level); if (isnan(abl.measured_z)) { set_bed_leveling_enabled(abl.reenable); @@ -795,7 +795,7 @@ G29_TYPE GcodeSuite::G29() { const int ind = abl.indexIntoAB[xx][yy]; xyz_float_t tmp = { abl.eqnAMatrix[ind + 0 * abl.abl_points], abl.eqnAMatrix[ind + 1 * abl.abl_points], 0 }; - planner.bed_level_matrix.apply_rotation_xyz(tmp); + planner.bed_level_matrix.apply_rotation_xyz(tmp.x, tmp.y, tmp.z); if (get_min) NOMORE(min_diff, abl.eqnBVector[ind] - tmp.z); const float subval = get_min ? abl.mean : tmp.z + min_diff, diff = abl.eqnBVector[ind] - subval; diff --git a/Marlin/src/gcode/bedlevel/mbl/G29.cpp b/Marlin/src/gcode/bedlevel/mbl/G29.cpp index 07721330ba516..21336f0b9a543 100644 --- a/Marlin/src/gcode/bedlevel/mbl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/mbl/G29.cpp @@ -70,7 +70,7 @@ void GcodeSuite::G29() { return; } - int8_t ix, iy; + int8_t ix, iy = 0; switch (state) { case MeshReport: @@ -87,7 +87,8 @@ void GcodeSuite::G29() { mbl.reset(); mbl_probe_index = 0; if (!ui.wait_for_move) { - queue.inject_P(parser.seen_test('N') ? PSTR("G28" TERN(G28_L0_ENSURES_LEVELING_OFF, "L0", "") "\nG29S2") : PSTR("G29S2")); + queue.inject_P(parser.seen_test('N') ? PSTR("G28" TERN(CAN_SET_LEVELING_AFTER_G28, "L0", "") "\nG29S2") : PSTR("G29S2")); + TERN_(EXTENSIBLE_UI, ExtUI::onMeshLevelingStart()); return; } state = MeshNext; @@ -109,6 +110,7 @@ void GcodeSuite::G29() { else { // Save Z for the previous mesh position mbl.set_zigzag_z(mbl_probe_index - 1, current_position.z); + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ix, iy, current_position.z)); SET_SOFT_ENDSTOP_LOOSE(false); } // If there's another point to sample, move there with optional lift. diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index aacfcfa42f5a3..7cd1f65fbf36c 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -164,24 +164,24 @@ #if ENABLED(IMPROVE_HOMING_RELIABILITY) - slow_homing_t begin_slow_homing() { - slow_homing_t slow_homing{0}; - slow_homing.acceleration.set(planner.settings.max_acceleration_mm_per_s2[X_AXIS], + motion_state_t begin_slow_homing() { + motion_state_t motion_state{0}; + motion_state.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_xy = planner.max_jerk; + motion_state.jerk_state = planner.max_jerk; planner.max_jerk.set(0, 0); #endif planner.reset_acceleration_rates(); - return slow_homing; + return motion_state; } - void end_slow_homing(const slow_homing_t &slow_homing) { - 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; - TERN_(HAS_CLASSIC_JERK, planner.max_jerk = slow_homing.jerk_xy); + void end_slow_homing(const motion_state_t &motion_state) { + planner.settings.max_acceleration_mm_per_s2[X_AXIS] = motion_state.acceleration.x; + planner.settings.max_acceleration_mm_per_s2[Y_AXIS] = motion_state.acceleration.y; + TERN_(HAS_CLASSIC_JERK, planner.max_jerk = motion_state.jerk_state); planner.reset_acceleration_rates(); } @@ -195,9 +195,9 @@ * None Home to all axes with no parameters. * With QUICK_HOME enabled XY will home together, then Z. * - * O Home only if position is unknown - * - * Rn Raise by n mm/inches before homing + * L Force leveling state ON (if possible) or OFF after homing (Requires RESTORE_LEVELING_AFTER_G28 or ENABLE_LEVELING_AFTER_G28) + * O Home only if the position is not known and trusted + * R Raise by n mm/inches before homing * * Cartesian/SCARA parameters * @@ -229,7 +229,7 @@ void GcodeSuite::G28() { #endif // Home (O)nly if position is unknown - if (!axes_should_home() && parser.boolval('O')) { + if (!axes_should_home() && parser.seen_test('O')) { if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("> homing not needed, skip"); return; } @@ -242,12 +242,16 @@ void GcodeSuite::G28() { SET_SOFT_ENDSTOP_LOOSE(false); // Reset a leftover 'loose' motion state // Disable the leveling matrix before homing - #if HAS_LEVELING - const bool leveling_restore_state = parser.boolval('L', TERN(RESTORE_LEVELING_AFTER_G28, planner.leveling_active, ENABLED(ENABLE_LEVELING_AFTER_G28))); - IF_ENABLED(PROBE_MANUALLY, g29_in_progress = false); // Cancel the active G29 session - set_bed_leveling_enabled(false); + #if CAN_SET_LEVELING_AFTER_G28 + const bool leveling_restore_state = parser.boolval('L', TERN1(RESTORE_LEVELING_AFTER_G28, planner.leveling_active)); #endif + // Cancel any prior G29 session + TERN_(PROBE_MANUALLY, g29_in_progress = false); + + // Disable leveling before homing + TERN_(HAS_LEVELING, set_bed_leveling_enabled(false)); + // Reset to the XY plane TERN_(CNC_WORKSPACE_PLANES, workspace_plane = PLANE_XY); @@ -285,7 +289,9 @@ void GcodeSuite::G28() { #endif #endif - TERN_(IMPROVE_HOMING_RELIABILITY, slow_homing_t slow_homing = begin_slow_homing()); + #if ENABLED(IMPROVE_HOMING_RELIABILITY) + motion_state_t saved_motion_state = begin_slow_homing(); + #endif // Always home with tool 0 active #if HAS_MULTI_HOTEND @@ -311,7 +317,7 @@ void GcodeSuite::G28() { home_delta(); - TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(slow_homing)); + TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(saved_motion_state)); #elif ENABLED(AXEL_TPARA) @@ -321,33 +327,47 @@ void GcodeSuite::G28() { #else - const bool homeZ = parser.seen_test('Z'), - needX = homeZ && TERN0(Z_SAFE_HOMING, axes_should_home(_BV(X_AXIS))), - needY = homeZ && TERN0(Z_SAFE_HOMING, axes_should_home(_BV(Y_AXIS))), - homeX = needX || parser.seen_test('X'), homeY = needY || parser.seen_test('Y'), - home_all = homeX == homeY && homeX == homeZ, // All or None - doX = home_all || homeX, doY = home_all || homeY, doZ = home_all || homeZ; - - #if ENABLED(HOME_Z_FIRST) - - if (doZ) homeaxis(Z_AXIS); - + #define _UNSAFE(A) (homeZ && TERN0(Z_SAFE_HOMING, axes_should_home(_BV(A##_AXIS)))) + + const bool homeZ = TERN0(HAS_Z_AXIS, parser.seen_test('Z')), + LINEAR_AXIS_LIST( // Other axes should be homed before Z safe-homing + needX = _UNSAFE(X), needY = _UNSAFE(Y), needZ = false, // UNUSED + needI = _UNSAFE(I), needJ = _UNSAFE(J), needK = _UNSAFE(K) + ), + LINEAR_AXIS_LIST( // Home each axis if needed or flagged + homeX = needX || parser.seen_test('X'), + homeY = needY || parser.seen_test('Y'), + homeZZ = homeZ, + homeI = needI || parser.seen_test(AXIS4_NAME), homeJ = needJ || parser.seen_test(AXIS5_NAME), homeK = needK || parser.seen_test(AXIS6_NAME), + ), + home_all = LINEAR_AXIS_GANG( // Home-all if all or none are flagged + homeX == homeX, && homeY == homeX, && homeZ == homeX, + && homeI == homeX, && homeJ == homeX, && homeK == homeX + ), + LINEAR_AXIS_LIST( + doX = home_all || homeX, doY = home_all || homeY, doZ = home_all || homeZ, + doI = home_all || homeI, doJ = home_all || homeJ, doK = home_all || homeK + ); + + #if HAS_Z_AXIS + UNUSED(needZ); UNUSED(homeZZ); + #else + constexpr bool doZ = false; #endif + TERN_(HOME_Z_FIRST, if (doZ) homeaxis(Z_AXIS)); + const float z_homing_height = parser.seenval('R') ? parser.value_linear_units() : Z_HOMING_HEIGHT; - if (z_homing_height && (doX || doY || TERN0(Z_SAFE_HOMING, doZ))) { + if (z_homing_height && (LINEAR_AXIS_GANG(doX, || doY, || TERN0(Z_SAFE_HOMING, doZ), || doI, || doJ, || doK))) { // Raise Z before homing any other axes and z is not already high enough (never lower z) if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Raise Z (before homing) by ", z_homing_height); do_z_clearance(z_homing_height); TERN_(BLTOUCH, bltouch.init()); } - #if ENABLED(QUICK_HOME) - - if (doX && doY) quick_home_xy(); - - #endif + // Diagonal move first if both are homing + TERN_(QUICK_HOME, if (doX && doY) quick_home_xy()); // Home Y (before X) if (ENABLED(HOME_Y_BEFORE_X) && (doY || TERN0(CODEPENDENT_XY_HOMING, doX))) @@ -383,10 +403,10 @@ void GcodeSuite::G28() { if (DISABLED(HOME_Y_BEFORE_X) && doY) homeaxis(Y_AXIS); - TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(slow_homing)); + TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(saved_motion_state)); // Home Z last if homing towards the bed - #if DISABLED(HOME_Z_FIRST) + #if HAS_Z_AXIS && DISABLED(HOME_Z_FIRST) if (doZ) { #if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN) stepper.set_all_z_lock(false); @@ -398,6 +418,16 @@ void GcodeSuite::G28() { } #endif + #if LINEAR_AXES >= 4 + if (doI) homeaxis(I_AXIS); + #endif + #if LINEAR_AXES >= 5 + if (doJ) homeaxis(J_AXIS); + #endif + #if LINEAR_AXES >= 6 + if (doK) homeaxis(K_AXIS); + #endif + sync_plan_position(); #endif @@ -412,7 +442,7 @@ void GcodeSuite::G28() { if (idex_is_duplicating()) { - TERN_(IMPROVE_HOMING_RELIABILITY, slow_homing = begin_slow_homing()); + TERN_(IMPROVE_HOMING_RELIABILITY, saved_motion_state = begin_slow_homing()); // Always home the 2nd (right) extruder first active_extruder = 1; @@ -431,7 +461,7 @@ void GcodeSuite::G28() { dual_x_carriage_mode = IDEX_saved_mode; set_duplication_enabled(IDEX_saved_duplication_state); - TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(slow_homing)); + TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(saved_motion_state)); } #endif // DUAL_X_CARRIAGE @@ -441,12 +471,10 @@ void GcodeSuite::G28() { // Clear endstop state for polled stallGuard endstops TERN_(SPI_ENDSTOPS, endstops.clear_endstop_state()); - #if BOTH(DELTA, DELTA_HOME_TO_SAFE_ZONE) - // move to a height where we can use the full xy-area - do_blocking_move_to_z(delta_clip_start_height); - #endif + // Move to a height where we can use the full xy-area + TERN_(DELTA_HOME_TO_SAFE_ZONE, do_blocking_move_to_z(delta_clip_start_height)); - TERN_(HAS_LEVELING, set_bed_leveling_enabled(leveling_restore_state)); + TERN_(CAN_SET_LEVELING_AFTER_G28, if (leveling_restore_state) set_bed_leveling_enabled()); restore_feedrate_and_scaling(); @@ -469,7 +497,16 @@ void GcodeSuite::G28() { #if HAS_CURRENT_HOME(Y2) stepperY2.rms_current(tmc_save_current_Y2); #endif - #endif + #if HAS_CURRENT_HOME(I) + stepperI.rms_current(tmc_save_current_I); + #endif + #if HAS_CURRENT_HOME(J) + stepperJ.rms_current(tmc_save_current_J); + #endif + #if HAS_CURRENT_HOME(K) + stepperK.rms_current(tmc_save_current_K); + #endif + #endif // HAS_HOMING_CURRENT ui.refresh(); @@ -487,11 +524,13 @@ void GcodeSuite::G28() { // Set L6470 absolute position registers to counts // constexpr *might* move this to PROGMEM. // If not, this will need a PROGMEM directive and an accessor. + #define _EN_ITEM(N) , E_AXIS static constexpr AxisEnum L64XX_axis_xref[MAX_L64XX] = { - X_AXIS, Y_AXIS, Z_AXIS, - X_AXIS, Y_AXIS, Z_AXIS, Z_AXIS, - E_AXIS, E_AXIS, E_AXIS, E_AXIS, E_AXIS, E_AXIS + LINEAR_AXIS_LIST(X_AXIS, Y_AXIS, Z_AXIS, I_AXIS, J_AXIS, K_AXIS), + X_AXIS, Y_AXIS, Z_AXIS, Z_AXIS, Z_AXIS + REPEAT(E_STEPPERS, _EN_ITEM) }; + #undef _EN_ITEM for (uint8_t j = 1; j <= L64XX::chain[0]; j++) { const uint8_t cv = L64XX::chain[j]; L64xxManager.set_param((L64XX_axis_t)cv, L6470_ABS_POS, stepper.position(L64XX_axis_xref[cv])); diff --git a/Marlin/src/gcode/calibrate/G34.cpp b/Marlin/src/gcode/calibrate/G34.cpp index bcca00dd42b3b..956960866dc81 100644 --- a/Marlin/src/gcode/calibrate/G34.cpp +++ b/Marlin/src/gcode/calibrate/G34.cpp @@ -39,7 +39,7 @@ void GcodeSuite::G34() { // Home before the alignment procedure - if (!all_axes_trusted()) home_all_axes(); + home_if_needed(); TERN_(HAS_LEVELING, TEMPORARY_BED_LEVELING_STATE(false)); diff --git a/Marlin/src/gcode/calibrate/G34_M422.cpp b/Marlin/src/gcode/calibrate/G34_M422.cpp index 1614dd6fbd1e2..6869962028405 100644 --- a/Marlin/src/gcode/calibrate/G34_M422.cpp +++ b/Marlin/src/gcode/calibrate/G34_M422.cpp @@ -48,6 +48,13 @@ #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) #include "../../core/debug_out.h" +#if NUM_Z_STEPPER_DRIVERS >= 3 + #define TRIPLE_Z 1 + #if NUM_Z_STEPPER_DRIVERS >= 4 + #define QUAD_Z 1 + #endif +#endif + /** * G34: Z-Stepper automatic alignment * @@ -82,9 +89,9 @@ void GcodeSuite::G34() { switch (parser.intval('Z')) { case 1: stepper.set_z1_lock(state); break; case 2: stepper.set_z2_lock(state); break; - #if NUM_Z_STEPPER_DRIVERS >= 3 + #if TRIPLE_Z case 3: stepper.set_z3_lock(state); break; - #if NUM_Z_STEPPER_DRIVERS >= 4 + #if QUAD_Z case 4: stepper.set_z4_lock(state); break; #endif #endif @@ -99,13 +106,6 @@ void GcodeSuite::G34() { #if ENABLED(Z_STEPPER_AUTO_ALIGN) do { // break out on error - #if NUM_Z_STEPPER_DRIVERS == 4 - SERIAL_ECHOLNPGM("Alignment for 4 steppers is Experimental!"); - #elif NUM_Z_STEPPER_DRIVERS > 4 - SERIAL_ECHOLNPGM("Alignment not supported for over 4 steppers"); - break; - #endif - const int8_t z_auto_align_iterations = parser.intval('I', Z_STEPPER_ALIGN_ITERATIONS); if (!WITHIN(z_auto_align_iterations, 1, 30)) { SERIAL_ECHOLNPGM("?(I)teration out of bounds (1-30)."); @@ -157,19 +157,17 @@ void GcodeSuite::G34() { const xy_pos_t diff = z_stepper_align.xy[i] - z_stepper_align.xy[j]; return HYPOT2(diff.x, diff.y); }; - float z_probe = Z_BASIC_CLEARANCE + (G34_MAX_GRADE) * 0.01f * SQRT( - #if NUM_Z_STEPPER_DRIVERS == 3 - _MAX(magnitude2(0, 1), magnitude2(1, 2), magnitude2(2, 0)) - #elif NUM_Z_STEPPER_DRIVERS == 4 - _MAX(magnitude2(0, 1), magnitude2(1, 2), magnitude2(2, 3), - magnitude2(3, 0), magnitude2(0, 2), magnitude2(1, 3)) - #else - magnitude2(0, 1) + float z_probe = Z_BASIC_CLEARANCE + (G34_MAX_GRADE) * 0.01f * SQRT(_MAX(0, magnitude2(0, 1) + #if TRIPLE_Z + , magnitude2(2, 1), magnitude2(2, 0) + #if QUAD_Z + , magnitude2(3, 2), magnitude2(3, 1), magnitude2(3, 0) + #endif #endif - ); + )); // Home before the alignment procedure - if (!all_axes_trusted()) home_all_axes(); + home_if_needed(); // Move the Z coordinate realm towards the positive - dirty trick current_position.z += z_probe * 0.5f; @@ -178,7 +176,7 @@ void GcodeSuite::G34() { // This hack is un-done at the end of G34 - either by re-homing, or by using the probed heights of the last iteration. #if DISABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) - float last_z_align_move[NUM_Z_STEPPER_DRIVERS] = ARRAY_N(NUM_Z_STEPPER_DRIVERS, 10000.0f, 10000.0f, 10000.0f, 10000.0f); + float last_z_align_move[NUM_Z_STEPPER_DRIVERS] = ARRAY_N_1(NUM_Z_STEPPER_DRIVERS, 10000.0f); #else float last_z_align_level_indicator = 10000.0f; #endif @@ -280,39 +278,52 @@ void GcodeSuite::G34() { z_measured_min = _MIN(z_measured_min, z_measured[i]); } - SERIAL_ECHOLNPAIR("CALCULATED STEPPER POSITIONS: Z1=", z_measured[0], " Z2=", z_measured[1], " Z3=", z_measured[2]); + SERIAL_ECHOLNPAIR( + LIST_N(DOUBLE(NUM_Z_STEPPER_DRIVERS), + "Calculated Z1=", z_measured[0], + " Z2=", z_measured[1], + " Z3=", z_measured[2], + " Z4=", z_measured[3] + ) + ); #endif SERIAL_ECHOLNPAIR("\n" - "DIFFERENCE Z1-Z2=", ABS(z_measured[0] - z_measured[1]) - #if NUM_Z_STEPPER_DRIVERS == 3 - , " Z2-Z3=", ABS(z_measured[1] - z_measured[2]) + "Z2-Z1=", ABS(z_measured[1] - z_measured[0]) + #if TRIPLE_Z + , " Z3-Z2=", ABS(z_measured[2] - z_measured[1]) , " Z3-Z1=", ABS(z_measured[2] - z_measured[0]) + #if QUAD_Z + , " Z4-Z3=", ABS(z_measured[3] - z_measured[2]) + , " Z4-Z2=", ABS(z_measured[3] - z_measured[1]) + , " Z4-Z1=", ABS(z_measured[3] - z_measured[0]) + #endif #endif ); + #if HAS_STATUS_MESSAGE char fstr1[10]; - #if NUM_Z_STEPPER_DRIVERS == 2 - char msg[6 + (6 + 5) * 1 + 1]; - #else - char msg[6 + (6 + 5) * 3 + 1], fstr2[10], fstr3[10]; - #endif - sprintf_P(msg, - PSTR("Diffs Z1-Z2=%s" - #if NUM_Z_STEPPER_DRIVERS == 3 - " Z2-Z3=%s" - " Z3-Z1=%s" + char msg[6 + (6 + 5) * NUM_Z_STEPPER_DRIVERS + 1] + #if TRIPLE_Z + , fstr2[10], fstr3[10] + #if QUAD_Z + , fstr4[10], fstr5[10], fstr6[10] #endif - ), dtostrf(ABS(z_measured[0] - z_measured[1]), 1, 3, fstr1) - #if NUM_Z_STEPPER_DRIVERS == 3 - , dtostrf(ABS(z_measured[1] - z_measured[2]), 1, 3, fstr2) - , dtostrf(ABS(z_measured[2] - z_measured[0]), 1, 3, fstr3) #endif + ; + sprintf_P(msg, + PSTR("1:2=%s" TERN_(TRIPLE_Z, " 3-2=%s 3-1=%s") TERN_(QUAD_Z, " 4-3=%s 4-2=%s 4-1=%s")), + dtostrf(ABS(z_measured[1] - z_measured[0]), 1, 3, fstr1) + OPTARG(TRIPLE_Z, dtostrf(ABS(z_measured[2] - z_measured[1]), 1, 3, fstr2)) + OPTARG(TRIPLE_Z, dtostrf(ABS(z_measured[2] - z_measured[0]), 1, 3, fstr3)) + OPTARG(QUAD_Z, dtostrf(ABS(z_measured[3] - z_measured[2]), 1, 3, fstr4)) + OPTARG(QUAD_Z, dtostrf(ABS(z_measured[3] - z_measured[1]), 1, 3, fstr5)) + OPTARG(QUAD_Z, dtostrf(ABS(z_measured[3] - z_measured[0]), 1, 3, fstr6)) ); ui.set_status(msg); #endif - auto decreasing_accuracy = [](const_float_t v1, const_float_t v2){ + auto decreasing_accuracy = [](const_float_t v1, const_float_t v2) { if (v1 < v2 * 0.7f) { SERIAL_ECHOLNPGM("Decreasing Accuracy Detected."); LCD_MESSAGEPGM(MSG_DECREASING_ACCURACY); @@ -437,7 +448,7 @@ void GcodeSuite::G34() { #endif }while(0); - #endif + #endif // Z_STEPPER_AUTO_ALIGN } #endif // Z_MULTI_ENDSTOPS || Z_STEPPER_AUTO_ALIGN diff --git a/Marlin/src/gcode/calibrate/G425.cpp b/Marlin/src/gcode/calibrate/G425.cpp index 2fb4502267975..c8efea858ca5d 100644 --- a/Marlin/src/gcode/calibrate/G425.cpp +++ b/Marlin/src/gcode/calibrate/G425.cpp @@ -73,11 +73,23 @@ #if BOTH(CALIBRATION_MEASURE_LEFT, CALIBRATION_MEASURE_RIGHT) #define HAS_X_CENTER 1 #endif -#if BOTH(CALIBRATION_MEASURE_FRONT, CALIBRATION_MEASURE_BACK) +#if HAS_Y_AXIS && BOTH(CALIBRATION_MEASURE_FRONT, CALIBRATION_MEASURE_BACK) #define HAS_Y_CENTER 1 #endif +#if LINEAR_AXES >= 4 && BOTH(CALIBRATION_MEASURE_IMIN, CALIBRATION_MEASURE_IMAX) + #define HAS_I_CENTER 1 +#endif +#if LINEAR_AXES >= 5 && BOTH(CALIBRATION_MEASURE_JMIN, CALIBRATION_MEASURE_JMAX) + #define HAS_J_CENTER 1 +#endif +#if LINEAR_AXES >= 6 && BOTH(CALIBRATION_MEASURE_KMIN, CALIBRATION_MEASURE_KMAX) + #define HAS_K_CENTER 1 +#endif -enum side_t : uint8_t { TOP, RIGHT, FRONT, LEFT, BACK, NUM_SIDES }; +enum side_t : uint8_t { + TOP, RIGHT, FRONT, LEFT, BACK, NUM_SIDES, + LIST_N(DOUBLE(SUB3(LINEAR_AXES)), IMINIMUM, IMAXIMUM, JMINIMUM, JMAXIMUM, KMINIMUM, KMAXIMUM) +}; static constexpr xyz_pos_t true_center CALIBRATION_OBJECT_CENTER; static constexpr xyz_float_t dimensions CALIBRATION_OBJECT_DIMENSIONS; @@ -105,7 +117,7 @@ struct measurements_t { #endif inline void calibration_move() { - do_blocking_move_to(current_position, MMM_TO_MMS(CALIBRATION_FEEDRATE_TRAVEL)); + do_blocking_move_to((xyz_pos_t)current_position, MMM_TO_MMS(CALIBRATION_FEEDRATE_TRAVEL)); } /** @@ -174,7 +186,7 @@ float measuring_movement(const AxisEnum axis, const int dir, const bool stop_sta destination = current_position; for (float travel = 0; travel < limit; travel += step) { destination[axis] += dir * step; - do_blocking_move_to(destination, mms); + do_blocking_move_to((xyz_pos_t)destination, mms); planner.synchronize(); if (read_calibration_pin() == stop_state) break; } @@ -209,7 +221,7 @@ inline float measure(const AxisEnum axis, const int dir, const bool stop_state, // Move back to the starting position destination = current_position; destination[axis] = start_pos; - do_blocking_move_to(destination, MMM_TO_MMS(CALIBRATION_FEEDRATE_TRAVEL)); + do_blocking_move_to((xyz_pos_t)destination, MMM_TO_MMS(CALIBRATION_FEEDRATE_TRAVEL)); return measured_pos; } @@ -230,7 +242,15 @@ inline void probe_side(measurements_t &m, const float uncertainty, const side_t park_above_object(m, uncertainty); switch (side) { - #if AXIS_CAN_CALIBRATE(Z) + #if AXIS_CAN_CALIBRATE(X) + case RIGHT: dir = -1; + case LEFT: axis = X_AXIS; break; + #endif + #if LINEAR_AXES >= 2 && AXIS_CAN_CALIBRATE(Y) + case BACK: dir = -1; + case FRONT: axis = Y_AXIS; break; + #endif + #if HAS_Z_AXIS && AXIS_CAN_CALIBRATE(Z) case TOP: { const float measurement = measure(Z_AXIS, -1, true, &m.backlash[TOP], uncertainty); m.obj_center.z = measurement - dimensions.z / 2; @@ -238,13 +258,17 @@ inline void probe_side(measurements_t &m, const float uncertainty, const side_t return; } #endif - #if AXIS_CAN_CALIBRATE(X) - case RIGHT: dir = -1; - case LEFT: axis = X_AXIS; break; + #if LINEAR_AXES >= 4 && AXIS_CAN_CALIBRATE(I) + case IMINIMUM: dir = -1; + case IMAXIMUM: axis = I_AXIS; break; #endif - #if AXIS_CAN_CALIBRATE(Y) - case BACK: dir = -1; - case FRONT: axis = Y_AXIS; break; + #if LINEAR_AXES >= 5 && AXIS_CAN_CALIBRATE(J) + case JMINIMUM: dir = -1; + case JMAXIMUM: axis = J_AXIS; break; + #endif + #if LINEAR_AXES >= 6 && AXIS_CAN_CALIBRATE(K) + case KMINIMUM: dir = -1; + case KMAXIMUM: axis = K_AXIS; break; #endif default: return; } @@ -289,14 +313,23 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { probe_side(m, uncertainty, TOP); #endif - TERN_(CALIBRATION_MEASURE_RIGHT, probe_side(m, uncertainty, RIGHT, probe_top_at_edge)); - TERN_(CALIBRATION_MEASURE_FRONT, probe_side(m, uncertainty, FRONT, probe_top_at_edge)); - TERN_(CALIBRATION_MEASURE_LEFT, probe_side(m, uncertainty, LEFT, probe_top_at_edge)); - TERN_(CALIBRATION_MEASURE_BACK, probe_side(m, uncertainty, BACK, probe_top_at_edge)); + TERN_(CALIBRATION_MEASURE_RIGHT, probe_side(m, uncertainty, RIGHT, probe_top_at_edge)); + TERN_(CALIBRATION_MEASURE_FRONT, probe_side(m, uncertainty, FRONT, probe_top_at_edge)); + TERN_(CALIBRATION_MEASURE_LEFT, probe_side(m, uncertainty, LEFT, probe_top_at_edge)); + TERN_(CALIBRATION_MEASURE_BACK, probe_side(m, uncertainty, BACK, probe_top_at_edge)); + TERN_(CALIBRATION_MEASURE_IMIN, probe_side(m, uncertainty, IMINIMUM, probe_top_at_edge)); + TERN_(CALIBRATION_MEASURE_IMAX, probe_side(m, uncertainty, IMAXIMUM, probe_top_at_edge)); + TERN_(CALIBRATION_MEASURE_JMIN, probe_side(m, uncertainty, JMINIMUM, probe_top_at_edge)); + TERN_(CALIBRATION_MEASURE_JMAX, probe_side(m, uncertainty, JMAXIMUM, probe_top_at_edge)); + TERN_(CALIBRATION_MEASURE_KMIN, probe_side(m, uncertainty, KMINIMUM, probe_top_at_edge)); + TERN_(CALIBRATION_MEASURE_KMAX, probe_side(m, uncertainty, KMAXIMUM, probe_top_at_edge)); // Compute the measured center of the calibration object. - TERN_(HAS_X_CENTER, m.obj_center.x = (m.obj_side[LEFT] + m.obj_side[RIGHT]) / 2); - TERN_(HAS_Y_CENTER, m.obj_center.y = (m.obj_side[FRONT] + m.obj_side[BACK]) / 2); + TERN_(HAS_X_CENTER, m.obj_center.x = (m.obj_side[LEFT] + m.obj_side[RIGHT]) / 2); + TERN_(HAS_Y_CENTER, m.obj_center.y = (m.obj_side[FRONT] + m.obj_side[BACK]) / 2); + TERN_(HAS_I_CENTER, m.obj_center.i = (m.obj_side[IMINIMUM] + m.obj_side[IMAXIMUM]) / 2); + TERN_(HAS_J_CENTER, m.obj_center.j = (m.obj_side[JMINIMUM] + m.obj_side[JMAXIMUM]) / 2); + TERN_(HAS_K_CENTER, m.obj_center.k = (m.obj_side[KMINIMUM] + m.obj_side[KMAXIMUM]) / 2); // Compute the outside diameter of the nozzle at the height // at which it makes contact with the calibration object @@ -307,15 +340,20 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { // The difference between the known and the measured location // of the calibration object is the positional error - m.pos_error.x = TERN0(HAS_X_CENTER, true_center.x - m.obj_center.x); - m.pos_error.y = TERN0(HAS_Y_CENTER, true_center.y - m.obj_center.y); - m.pos_error.z = true_center.z - m.obj_center.z; + LINEAR_AXIS_CODE( + m.pos_error.x = TERN0(HAS_X_CENTER, true_center.x - m.obj_center.x), + m.pos_error.y = TERN0(HAS_Y_CENTER, true_center.y - m.obj_center.y), + m.pos_error.z = true_center.z - m.obj_center.z, + m.pos_error.i = TERN0(HAS_I_CENTER, true_center.i - m.obj_center.i), + m.pos_error.j = TERN0(HAS_J_CENTER, true_center.j - m.obj_center.j), + m.pos_error.k = TERN0(HAS_K_CENTER, true_center.k - m.obj_center.k) + ); } #if ENABLED(CALIBRATION_REPORTING) inline void report_measured_faces(const measurements_t &m) { SERIAL_ECHOLNPGM("Sides:"); - #if AXIS_CAN_CALIBRATE(Z) + #if HAS_Z_AXIS && AXIS_CAN_CALIBRATE(Z) SERIAL_ECHOLNPAIR(" Top: ", m.obj_side[TOP]); #endif #if ENABLED(CALIBRATION_MEASURE_LEFT) @@ -324,11 +362,37 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { #if ENABLED(CALIBRATION_MEASURE_RIGHT) SERIAL_ECHOLNPAIR(" Right: ", m.obj_side[RIGHT]); #endif - #if ENABLED(CALIBRATION_MEASURE_FRONT) - SERIAL_ECHOLNPAIR(" Front: ", m.obj_side[FRONT]); + #if HAS_Y_AXIS + #if ENABLED(CALIBRATION_MEASURE_FRONT) + SERIAL_ECHOLNPAIR(" Front: ", m.obj_side[FRONT]); + #endif + #if ENABLED(CALIBRATION_MEASURE_BACK) + SERIAL_ECHOLNPAIR(" Back: ", m.obj_side[BACK]); + #endif + #endif + #if LINEAR_AXES >= 4 + #if ENABLED(CALIBRATION_MEASURE_IMIN) + SERIAL_ECHOLNPAIR(" " STR_I_MIN ": ", m.obj_side[IMINIMUM]); + #endif + #if ENABLED(CALIBRATION_MEASURE_IMAX) + SERIAL_ECHOLNPAIR(" " STR_I_MAX ": ", m.obj_side[IMAXIMUM]); + #endif + #endif + #if LINEAR_AXES >= 5 + #if ENABLED(CALIBRATION_MEASURE_JMIN) + SERIAL_ECHOLNPAIR(" " STR_J_MIN ": ", m.obj_side[JMINIMUM]); + #endif + #if ENABLED(CALIBRATION_MEASURE_JMAX) + SERIAL_ECHOLNPAIR(" " STR_J_MAX ": ", m.obj_side[JMAXIMUM]); + #endif #endif - #if ENABLED(CALIBRATION_MEASURE_BACK) - SERIAL_ECHOLNPAIR(" Back: ", m.obj_side[BACK]); + #if LINEAR_AXES >= 6 + #if ENABLED(CALIBRATION_MEASURE_KMIN) + SERIAL_ECHOLNPAIR(" " STR_K_MIN ": ", m.obj_side[KMINIMUM]); + #endif + #if ENABLED(CALIBRATION_MEASURE_KMAX) + SERIAL_ECHOLNPAIR(" " STR_K_MAX ": ", m.obj_side[KMAXIMUM]); + #endif #endif SERIAL_EOL(); } @@ -342,6 +406,15 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { SERIAL_ECHOLNPAIR_P(SP_Y_STR, m.obj_center.y); #endif SERIAL_ECHOLNPAIR_P(SP_Z_STR, m.obj_center.z); + #if HAS_I_CENTER + SERIAL_ECHOLNPAIR_P(SP_I_STR, m.obj_center.i); + #endif + #if HAS_J_CENTER + SERIAL_ECHOLNPAIR_P(SP_J_STR, m.obj_center.j); + #endif + #if HAS_K_CENTER + SERIAL_ECHOLNPAIR_P(SP_K_STR, m.obj_center.k); + #endif SERIAL_EOL(); } @@ -355,7 +428,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { SERIAL_ECHOLNPAIR(" Right: ", m.backlash[RIGHT]); #endif #endif - #if AXIS_CAN_CALIBRATE(Y) + #if HAS_Y_AXIS && AXIS_CAN_CALIBRATE(Y) #if ENABLED(CALIBRATION_MEASURE_FRONT) SERIAL_ECHOLNPAIR(" Front: ", m.backlash[FRONT]); #endif @@ -363,9 +436,33 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { SERIAL_ECHOLNPAIR(" Back: ", m.backlash[BACK]); #endif #endif - #if AXIS_CAN_CALIBRATE(Z) + #if HAS_Z_AXIS && AXIS_CAN_CALIBRATE(Z) SERIAL_ECHOLNPAIR(" Top: ", m.backlash[TOP]); #endif + #if LINEAR_AXES >= 4 && AXIS_CAN_CALIBRATE(I) + #if ENABLED(CALIBRATION_MEASURE_IMIN) + SERIAL_ECHOLNPAIR(" " STR_I_MIN ": ", m.backlash[IMINIMUM]); + #endif + #if ENABLED(CALIBRATION_MEASURE_IMAX) + SERIAL_ECHOLNPAIR(" " STR_I_MAX ": ", m.backlash[IMAXIMUM]); + #endif + #endif + #if LINEAR_AXES >= 5 && AXIS_CAN_CALIBRATE(J) + #if ENABLED(CALIBRATION_MEASURE_JMIN) + SERIAL_ECHOLNPAIR(" " STR_J_MIN ": ", m.backlash[JMINIMUM]); + #endif + #if ENABLED(CALIBRATION_MEASURE_JMAX) + SERIAL_ECHOLNPAIR(" " STR_J_MAX ": ", m.backlash[JMAXIMUM]); + #endif + #endif + #if LINEAR_AXES >= 6 && AXIS_CAN_CALIBRATE(K) + #if ENABLED(CALIBRATION_MEASURE_KMIN) + SERIAL_ECHOLNPAIR(" " STR_K_MIN ": ", m.backlash[KMINIMUM]); + #endif + #if ENABLED(CALIBRATION_MEASURE_KMAX) + SERIAL_ECHOLNPAIR(" " STR_K_MAX ": ", m.backlash[KMAXIMUM]); + #endif + #endif SERIAL_EOL(); } @@ -373,29 +470,37 @@ inline void probe_sides(measurements_t &m, const float uncertainty) { SERIAL_CHAR('T'); SERIAL_ECHO(active_extruder); SERIAL_ECHOLNPGM(" Positional Error:"); - #if HAS_X_CENTER + #if HAS_X_CENTER && AXIS_CAN_CALIBRATE(X) SERIAL_ECHOLNPAIR_P(SP_X_STR, m.pos_error.x); #endif - #if HAS_Y_CENTER + #if HAS_Y_CENTER && AXIS_CAN_CALIBRATE(Y) SERIAL_ECHOLNPAIR_P(SP_Y_STR, m.pos_error.y); #endif - if (AXIS_CAN_CALIBRATE(Z)) SERIAL_ECHOLNPAIR_P(SP_Z_STR, m.pos_error.z); + #if HAS_Z_AXIS && AXIS_CAN_CALIBRATE(Z) + SERIAL_ECHOLNPAIR_P(SP_Z_STR, m.pos_error.z); + #endif + #if HAS_I_CENTER && AXIS_CAN_CALIBRATE(I) + SERIAL_ECHOLNPAIR_P(SP_I_STR, m.pos_error.i); + #endif + #if HAS_J_CENTER && AXIS_CAN_CALIBRATE(J) + SERIAL_ECHOLNPAIR_P(SP_J_STR, m.pos_error.j); + #endif + #if HAS_K_CENTER && AXIS_CAN_CALIBRATE(K) + SERIAL_ECHOLNPAIR_P(SP_Z_STR, m.pos_error.z); + #endif SERIAL_EOL(); } inline void report_measured_nozzle_dimensions(const measurements_t &m) { SERIAL_ECHOLNPGM("Nozzle Tip Outer Dimensions:"); - #if HAS_X_CENTER || HAS_Y_CENTER - #if HAS_X_CENTER - SERIAL_ECHOLNPAIR_P(SP_X_STR, m.nozzle_outer_dimension.x); - #endif - #if HAS_Y_CENTER - SERIAL_ECHOLNPAIR_P(SP_Y_STR, m.nozzle_outer_dimension.y); - #endif - #else - UNUSED(m); + #if HAS_X_CENTER + SERIAL_ECHOLNPAIR_P(SP_X_STR, m.nozzle_outer_dimension.x); + #endif + #if HAS_Y_CENTER + SERIAL_ECHOLNPAIR_P(SP_Y_STR, m.nozzle_outer_dimension.y); #endif SERIAL_EOL(); + UNUSED(m); } #if HAS_HOTEND_OFFSET @@ -444,8 +549,33 @@ inline void calibrate_backlash(measurements_t &m, const float uncertainty) { backlash.distance_mm.y = m.backlash[BACK]; #endif - if (AXIS_CAN_CALIBRATE(Z)) backlash.distance_mm.z = m.backlash[TOP]; - #endif + TERN_(HAS_Z_AXIS, if (AXIS_CAN_CALIBRATE(Z)) backlash.distance_mm.z = m.backlash[TOP]); + + #if HAS_I_CENTER + backlash.distance_mm.i = (m.backlash[IMINIMUM] + m.backlash[IMAXIMUM]) / 2; + #elif ENABLED(CALIBRATION_MEASURE_IMIN) + backlash.distance_mm.i = m.backlash[IMINIMUM]; + #elif ENABLED(CALIBRATION_MEASURE_IMAX) + backlash.distance_mm.i = m.backlash[IMAXIMUM]; + #endif + + #if HAS_J_CENTER + backlash.distance_mm.j = (m.backlash[JMINIMUM] + m.backlash[JMAXIMUM]) / 2; + #elif ENABLED(CALIBRATION_MEASURE_JMIN) + backlash.distance_mm.j = m.backlash[JMINIMUM]; + #elif ENABLED(CALIBRATION_MEASURE_JMAX) + backlash.distance_mm.j = m.backlash[JMAXIMUM]; + #endif + + #if HAS_K_CENTER + backlash.distance_mm.k = (m.backlash[KMINIMUM] + m.backlash[KMAXIMUM]) / 2; + #elif ENABLED(CALIBRATION_MEASURE_KMIN) + backlash.distance_mm.k = m.backlash[KMINIMUM]; + #elif ENABLED(CALIBRATION_MEASURE_KMAX) + backlash.distance_mm.k = m.backlash[KMAXIMUM]; + #endif + + #endif // BACKLASH_GCODE } #if ENABLED(BACKLASH_GCODE) @@ -455,7 +585,10 @@ inline void calibrate_backlash(measurements_t &m, const float uncertainty) { // New scope for TEMPORARY_BACKLASH_CORRECTION TEMPORARY_BACKLASH_CORRECTION(all_on); TEMPORARY_BACKLASH_SMOOTHING(0.0f); - const xyz_float_t move = { AXIS_CAN_CALIBRATE(X) * 3, AXIS_CAN_CALIBRATE(Y) * 3, AXIS_CAN_CALIBRATE(Z) * 3 }; + const xyz_float_t move = LINEAR_AXIS_ARRAY( + AXIS_CAN_CALIBRATE(X) * 3, AXIS_CAN_CALIBRATE(Y) * 3, AXIS_CAN_CALIBRATE(Z) * 3, + AXIS_CAN_CALIBRATE(I) * 3, AXIS_CAN_CALIBRATE(J) * 3, AXIS_CAN_CALIBRATE(K) * 3 + ); current_position += move; calibration_move(); current_position -= move; calibration_move(); } @@ -483,11 +616,7 @@ inline void calibrate_toolhead(measurements_t &m, const float uncertainty, const TEMPORARY_BACKLASH_CORRECTION(all_on); TEMPORARY_BACKLASH_SMOOTHING(0.0f); - #if HAS_MULTI_HOTEND - set_nozzle(m, extruder); - #else - UNUSED(extruder); - #endif + TERN(HAS_MULTI_HOTEND, set_nozzle(m, extruder), UNUSED(extruder)); probe_sides(m, uncertainty); @@ -506,6 +635,10 @@ inline void calibrate_toolhead(measurements_t &m, const float uncertainty, const if (ENABLED(HAS_Y_CENTER) && AXIS_CAN_CALIBRATE(Y)) update_measurements(m, Y_AXIS); if (AXIS_CAN_CALIBRATE(Z)) update_measurements(m, Z_AXIS); + TERN_(HAS_I_CENTER, update_measurements(m, I_AXIS)); + TERN_(HAS_J_CENTER, update_measurements(m, J_AXIS)); + TERN_(HAS_K_CENTER, update_measurements(m, K_AXIS)); + sync_plan_position(); } diff --git a/Marlin/src/gcode/calibrate/M425.cpp b/Marlin/src/gcode/calibrate/M425.cpp index 432144f491c03..f30de00a0fdf8 100644 --- a/Marlin/src/gcode/calibrate/M425.cpp +++ b/Marlin/src/gcode/calibrate/M425.cpp @@ -48,10 +48,15 @@ void GcodeSuite::M425() { auto axis_can_calibrate = [](const uint8_t a) { switch (a) { - default: - case X_AXIS: return AXIS_CAN_CALIBRATE(X); - case Y_AXIS: return AXIS_CAN_CALIBRATE(Y); - case Z_AXIS: return AXIS_CAN_CALIBRATE(Z); + default: return false; + LINEAR_AXIS_CODE( + case X_AXIS: return AXIS_CAN_CALIBRATE(X), + case Y_AXIS: return AXIS_CAN_CALIBRATE(Y), + case Z_AXIS: return AXIS_CAN_CALIBRATE(Z), + case I_AXIS: return AXIS_CAN_CALIBRATE(I), + case J_AXIS: return AXIS_CAN_CALIBRATE(J), + case K_AXIS: return AXIS_CAN_CALIBRATE(K), + ); } }; diff --git a/Marlin/src/gcode/calibrate/M666.cpp b/Marlin/src/gcode/calibrate/M666.cpp index a3a48cd3fc1f2..8ff51f0e3f830 100644 --- a/Marlin/src/gcode/calibrate/M666.cpp +++ b/Marlin/src/gcode/calibrate/M666.cpp @@ -71,29 +71,27 @@ #endif #if ENABLED(Z_MULTI_ENDSTOPS) if (parser.seenval('Z')) { - #if NUM_Z_STEPPER_DRIVERS >= 3 - const float z_adj = parser.value_linear_units(); - const int ind = parser.intval('S'); - if (!ind || ind == 2) endstops.z2_endstop_adj = z_adj; - if (!ind || ind == 3) endstops.z3_endstop_adj = z_adj; - #if NUM_Z_STEPPER_DRIVERS >= 4 - if (!ind || ind == 4) endstops.z4_endstop_adj = z_adj; - #endif + const float z_adj = parser.value_linear_units(); + #if NUM_Z_STEPPER_DRIVERS == 2 + endstops.z2_endstop_adj = z_adj; #else - endstops.z2_endstop_adj = parser.value_linear_units(); + const int ind = parser.intval('S'); + #define _SET_ZADJ(N) if (!ind || ind == N) endstops.z##N##_endstop_adj = z_adj; + REPEAT_S(2, INCREMENT(NUM_Z_STEPPER_DRIVERS), _SET_ZADJ) #endif } #endif if (!parser.seen("XYZ")) { + auto echo_adj = [](PGM_P const label, const_float_t value) { SERIAL_ECHOPAIR_P(label, value); }; SERIAL_ECHOPGM("Dual Endstop Adjustment (mm): "); #if ENABLED(X_DUAL_ENDSTOPS) - SERIAL_ECHOPAIR(" X2:", endstops.x2_endstop_adj); + echo_adj(PSTR(" X2:"), endstops.x2_endstop_adj); #endif #if ENABLED(Y_DUAL_ENDSTOPS) - SERIAL_ECHOPAIR(" Y2:", endstops.y2_endstop_adj); + echo_adj(PSTR(" Y2:"), endstops.y2_endstop_adj); #endif #if ENABLED(Z_MULTI_ENDSTOPS) - #define _ECHO_ZADJ(N) SERIAL_ECHOPAIR(" Z" STRINGIFY(N) ":", endstops.z##N##_endstop_adj); + #define _ECHO_ZADJ(N) echo_adj(PSTR(" Z" STRINGIFY(N) ":"), endstops.z##N##_endstop_adj); REPEAT_S(2, INCREMENT(NUM_Z_STEPPER_DRIVERS), _ECHO_ZADJ) #endif SERIAL_EOL(); diff --git a/Marlin/src/gcode/config/M200-M205.cpp b/Marlin/src/gcode/config/M200-M205.cpp index 06751f41c4997..a2bcb8bb86a86 100644 --- a/Marlin/src/gcode/config/M200-M205.cpp +++ b/Marlin/src/gcode/config/M200-M205.cpp @@ -88,7 +88,7 @@ void GcodeSuite::M201() { LOOP_LOGICAL_AXES(i) { if (parser.seenval(axis_codes[i])) { - const uint8_t a = (i == E_AXIS ? uint8_t(E_AXIS_N(target_extruder)) : i); + const uint8_t a = TERN(HAS_EXTRUDERS, (i == E_AXIS ? uint8_t(E_AXIS_N(target_extruder)) : i), i); planner.set_max_acceleration(a, parser.value_axis_units((AxisEnum)a)); } } @@ -106,7 +106,7 @@ void GcodeSuite::M203() { LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) { - const uint8_t a = (i == E_AXIS ? uint8_t(E_AXIS_N(target_extruder)) : i); + const uint8_t a = TERN(HAS_EXTRUDERS, (i == E_AXIS ? uint8_t(E_AXIS_N(target_extruder)) : i), i); planner.set_max_feedrate(a, parser.value_axis_units((AxisEnum)a)); } } @@ -154,6 +154,9 @@ void GcodeSuite::M205() { if (parser.seenval('S')) planner.settings.min_feedrate_mm_s = parser.value_linear_units(); if (parser.seenval('T')) planner.settings.min_travel_feedrate_mm_s = parser.value_linear_units(); #if HAS_JUNCTION_DEVIATION + #if HAS_CLASSIC_JERK && (AXIS4_NAME == 'J' || AXIS5_NAME == 'J' || AXIS6_NAME == 'J') + #error "Can't set_max_jerk for 'J' axis because 'J' is used for Junction Deviation." + #endif if (parser.seenval('J')) { const float junc_dev = parser.value_linear_units(); if (WITHIN(junc_dev, 0.01f, 0.3f)) { @@ -165,17 +168,19 @@ void GcodeSuite::M205() { } #endif #if HAS_CLASSIC_JERK - if (parser.seenval('X')) planner.set_max_jerk(X_AXIS, parser.value_linear_units()); - if (parser.seenval('Y')) planner.set_max_jerk(Y_AXIS, parser.value_linear_units()); - if (parser.seenval('Z')) { - planner.set_max_jerk(Z_AXIS, parser.value_linear_units()); - #if HAS_MESH && DISABLED(LIMITED_JERK_EDITING) - if (planner.max_jerk.z <= 0.1f) - SERIAL_ECHOLNPGM("WARNING! Low Z Jerk may lead to unwanted pauses."); - #endif - } - #if HAS_CLASSIC_E_JERK - if (parser.seenval('E')) planner.set_max_jerk(E_AXIS, parser.value_linear_units()); + bool seenZ = false; + LOGICAL_AXIS_CODE( + if (parser.seenval('E')) planner.set_max_jerk(E_AXIS, parser.value_linear_units()), + if (parser.seenval('X')) planner.set_max_jerk(X_AXIS, parser.value_linear_units()), + if (parser.seenval('Y')) planner.set_max_jerk(Y_AXIS, parser.value_linear_units()), + if ((seenZ = parser.seenval('Z'))) planner.set_max_jerk(Z_AXIS, parser.value_linear_units()), + if (parser.seenval(AXIS4_NAME)) planner.set_max_jerk(I_AXIS, parser.value_linear_units()), + if (parser.seenval(AXIS5_NAME)) planner.set_max_jerk(J_AXIS, parser.value_linear_units()), + if (parser.seenval(AXIS6_NAME)) planner.set_max_jerk(K_AXIS, parser.value_linear_units()) + ); + #if HAS_MESH && DISABLED(LIMITED_JERK_EDITING) + if (seenZ && planner.max_jerk.z <= 0.1f) + SERIAL_ECHOLNPGM("WARNING! Low Z Jerk may lead to unwanted pauses."); #endif - #endif + #endif // HAS_CLASSIC_JERK } diff --git a/Marlin/src/gcode/config/M92.cpp b/Marlin/src/gcode/config/M92.cpp index 06c47b825334c..544c66a0768a1 100644 --- a/Marlin/src/gcode/config/M92.cpp +++ b/Marlin/src/gcode/config/M92.cpp @@ -25,10 +25,15 @@ void report_M92(const bool echo=true, const int8_t e=-1) { if (echo) SERIAL_ECHO_START(); else SERIAL_CHAR(' '); - SERIAL_ECHOPAIR_P(PSTR(" M92 X"), LINEAR_UNIT(planner.settings.axis_steps_per_mm[X_AXIS]), - SP_Y_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Y_AXIS]), - SP_Z_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Z_AXIS])); - #if DISABLED(DISTINCT_E_FACTORS) + SERIAL_ECHOPAIR_P(LIST_N(DOUBLE(LINEAR_AXES), + PSTR(" M92 X"), LINEAR_UNIT(planner.settings.axis_steps_per_mm[X_AXIS]), + SP_Y_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Y_AXIS]), + SP_Z_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Z_AXIS]), + SP_I_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[I_AXIS]), + SP_J_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[J_AXIS]), + SP_K_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[K_AXIS])) + ); + #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS) SERIAL_ECHOPAIR_P(SP_E_STR, VOLUMETRIC_UNIT(planner.settings.axis_steps_per_mm[E_AXIS])); #endif SERIAL_EOL(); @@ -64,25 +69,28 @@ void GcodeSuite::M92() { if (target_extruder < 0) return; // No arguments? Show M92 report. - if (!parser.seen("XYZE" TERN_(MAGIC_NUMBERS_GCODE, "HL"))) - return report_M92(true, target_extruder); + if (!parser.seen( + LOGICAL_AXIS_GANG("E", "X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR) + TERN_(MAGIC_NUMBERS_GCODE, "HL") + )) return report_M92(true, target_extruder); LOOP_LOGICAL_AXES(i) { if (parser.seenval(axis_codes[i])) { - if (i == E_AXIS) { - const float value = parser.value_per_axis_units((AxisEnum)(E_AXIS_N(target_extruder))); - 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 && HAS_CLASSIC_E_JERK - 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; - } - planner.settings.axis_steps_per_mm[E_AXIS_N(target_extruder)] = value; - } - else { + if (TERN1(HAS_EXTRUDERS, i != E_AXIS)) planner.settings.axis_steps_per_mm[i] = parser.value_per_axis_units((AxisEnum)i); + else { + #if HAS_EXTRUDERS + const float value = parser.value_per_axis_units((AxisEnum)(E_AXIS_N(target_extruder))); + 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 && HAS_CLASSIC_E_JERK + 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; + } + planner.settings.axis_steps_per_mm[E_AXIS_N(target_extruder)] = value; + #endif } } } diff --git a/Marlin/src/gcode/control/M17_M18_M84.cpp b/Marlin/src/gcode/control/M17_M18_M84.cpp index f02508a90171b..4ebb81cf7ea74 100644 --- a/Marlin/src/gcode/control/M17_M18_M84.cpp +++ b/Marlin/src/gcode/control/M17_M18_M84.cpp @@ -33,11 +33,16 @@ * M17: Enable stepper motors */ void GcodeSuite::M17() { - if (parser.seen("XYZE")) { - if (parser.seen_test('X')) ENABLE_AXIS_X(); - if (parser.seen_test('Y')) ENABLE_AXIS_Y(); - if (parser.seen_test('Z')) ENABLE_AXIS_Z(); - if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen_test('E'))) enable_e_steppers(); + if (parser.seen(LOGICAL_AXIS_GANG("E", "X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR))) { + LOGICAL_AXIS_CODE( + if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen_test('E'))) enable_e_steppers(), + if (parser.seen_test('X')) ENABLE_AXIS_X(), + if (parser.seen_test('Y')) ENABLE_AXIS_Y(), + if (parser.seen_test('Z')) ENABLE_AXIS_Z(), + if (parser.seen_test(AXIS4_NAME)) ENABLE_AXIS_I(), + if (parser.seen_test(AXIS5_NAME)) ENABLE_AXIS_J(), + if (parser.seen_test(AXIS6_NAME)) ENABLE_AXIS_K() + ); } else { LCD_MESSAGEPGM(MSG_NO_MOVE); @@ -54,12 +59,17 @@ void GcodeSuite::M18_M84() { stepper_inactive_time = parser.value_millis_from_seconds(); } else { - if (parser.seen("XYZE")) { + if (parser.seen(LOGICAL_AXIS_GANG("E", "X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR))) { planner.synchronize(); - if (parser.seen_test('X')) DISABLE_AXIS_X(); - if (parser.seen_test('Y')) DISABLE_AXIS_Y(); - if (parser.seen_test('Z')) DISABLE_AXIS_Z(); - if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen_test('E'))) disable_e_steppers(); + LOGICAL_AXIS_CODE( + if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen_test('E'))) disable_e_steppers(), + if (parser.seen_test('X')) DISABLE_AXIS_X(), + if (parser.seen_test('Y')) DISABLE_AXIS_Y(), + if (parser.seen_test('Z')) DISABLE_AXIS_Z(), + if (parser.seen_test(AXIS4_NAME)) DISABLE_AXIS_I(), + if (parser.seen_test(AXIS5_NAME)) DISABLE_AXIS_J(), + if (parser.seen_test(AXIS6_NAME)) DISABLE_AXIS_K() + ); } else planner.finish_and_disable(); diff --git a/Marlin/src/gcode/control/M605.cpp b/Marlin/src/gcode/control/M605.cpp index ac84ac6217962..23d43dd0a60bf 100644 --- a/Marlin/src/gcode/control/M605.cpp +++ b/Marlin/src/gcode/control/M605.cpp @@ -70,26 +70,12 @@ dual_x_carriage_mode = (DualXMode)parser.value_byte(); idex_set_mirrored_mode(false); - if (dual_x_carriage_mode == DXC_MIRRORED_MODE) { - if (previous_mode != DXC_DUPLICATION_MODE) { - SERIAL_ECHOLNPGM("Printer must be in DXC_DUPLICATION_MODE prior to "); - SERIAL_ECHOLNPGM("specifying DXC_MIRRORED_MODE."); - dual_x_carriage_mode = DEFAULT_DUAL_X_CARRIAGE_MODE; - return; - } - idex_set_mirrored_mode(true); - float x_jog = current_position.x - .1; - for (uint8_t i = 2; --i;) { - planner.buffer_line(x_jog, current_position.y, current_position.z, current_position.e, feedrate_mm_s, 0); - x_jog += .1; - } - return; - } - switch (dual_x_carriage_mode) { + case DXC_FULL_CONTROL_MODE: case DXC_AUTO_PARK_MODE: break; + case DXC_DUPLICATION_MODE: // Set the X offset, but no less than the safety gap if (parser.seen('X')) duplicate_extruder_x_offset = _MAX(parser.value_linear_units(), (X2_MIN_POS) - (X1_MIN_POS)); @@ -97,10 +83,29 @@ // Always switch back to tool 0 if (active_extruder != 0) tool_change(0); break; + + case DXC_MIRRORED_MODE: { + if (previous_mode != DXC_DUPLICATION_MODE) { + SERIAL_ECHOLNPGM("Printer must be in DXC_DUPLICATION_MODE prior to "); + SERIAL_ECHOLNPGM("specifying DXC_MIRRORED_MODE."); + dual_x_carriage_mode = DEFAULT_DUAL_X_CARRIAGE_MODE; + return; + } + idex_set_mirrored_mode(true); + + // Do a small 'jog' motion in the X axis + xyze_pos_t dest = current_position; dest.x -= 0.1f; + for (uint8_t i = 2; --i;) { + planner.buffer_line(dest, feedrate_mm_s, 0); + dest.x += 0.1f; + } + } return; + default: dual_x_carriage_mode = DEFAULT_DUAL_X_CARRIAGE_MODE; break; } + idex_set_parked(false); set_duplication_enabled(false); diff --git a/Marlin/src/gcode/control/M7-M9.cpp b/Marlin/src/gcode/control/M7-M9.cpp index ae112fc3723ad..ccde4f552cb99 100644 --- a/Marlin/src/gcode/control/M7-M9.cpp +++ b/Marlin/src/gcode/control/M7-M9.cpp @@ -20,9 +20,9 @@ * */ -#include "../../inc/MarlinConfig.h" +#include "../../inc/MarlinConfigPre.h" -#if ENABLED(COOLANT_CONTROL) +#if ANY(COOLANT_MIST, COOLANT_FLOOD, AIR_ASSIST) #include "../gcode.h" #include "../../module/planner.h" @@ -37,51 +37,41 @@ } #endif -#if ENABLED(COOLANT_FLOOD) +#if EITHER(COOLANT_FLOOD, AIR_ASSIST) + + #if ENABLED(AIR_ASSIST) + #include "../../feature/spindle_laser.h" + #endif + /** - * M8: Flood Coolant On + * M8: Flood Coolant / Air Assist ON */ void GcodeSuite::M8() { - planner.synchronize(); // Wait for move to arrive - WRITE(COOLANT_FLOOD_PIN, !(COOLANT_FLOOD_INVERT)); // Turn on Flood coolant + planner.synchronize(); // Wait for move to arrive + #if ENABLED(COOLANT_FLOOD) + WRITE(COOLANT_FLOOD_PIN, !(COOLANT_FLOOD_INVERT)); // Turn on Flood coolant + #endif + #if ENABLED(AIR_ASSIST) + cutter.air_assist_enable(); // Turn on Air Assist + #endif } + #endif /** - * M9: Coolant OFF + * M9: Coolant / Air Assist OFF */ void GcodeSuite::M9() { - planner.synchronize(); // Wait for move to arrive + planner.synchronize(); // Wait for move to arrive #if ENABLED(COOLANT_MIST) - WRITE(COOLANT_MIST_PIN, COOLANT_MIST_INVERT); // Turn off Mist coolant + WRITE(COOLANT_MIST_PIN, COOLANT_MIST_INVERT); // Turn off Mist coolant #endif #if ENABLED(COOLANT_FLOOD) - WRITE(COOLANT_FLOOD_PIN, COOLANT_FLOOD_INVERT); // Turn off Flood coolant + WRITE(COOLANT_FLOOD_PIN, COOLANT_FLOOD_INVERT); // Turn off Flood coolant + #endif + #if ENABLED(AIR_ASSIST) + cutter.air_assist_disable(); // Turn off Air Assist #endif } -#endif // COOLANT_CONTROL - -#if ENABLED(AIR_ASSIST) - -#include "../gcode.h" -#include "../../module/planner.h" -#include "../../feature/spindle_laser.h" - -/** - * M8: Air Assist On - */ -void GcodeSuite::M8() { - planner.synchronize(); - cutter.air_assist_enable(); // Turn on Air Assist pin -} - -/** - * M9: Air Assist Off - */ -void GcodeSuite::M9() { - planner.synchronize(); - cutter.air_assist_disable(); // Turn off Air Assist pin -} - -#endif // AIR_ASSIST +#endif // COOLANT_MIST | COOLANT_FLOOD | AIR_ASSIST diff --git a/Marlin/src/gcode/feature/L6470/M906.cpp b/Marlin/src/gcode/feature/L6470/M906.cpp index 87614e9c73de6..dddf7f8aeed14 100644 --- a/Marlin/src/gcode/feature/L6470/M906.cpp +++ b/Marlin/src/gcode/feature/L6470/M906.cpp @@ -32,31 +32,6 @@ #define DEBUG_OUT ENABLED(L6470_CHITCHAT) #include "../../../core/debug_out.h" -/** - * M906: report or set KVAL_HOLD which sets the maximum effective voltage provided by the - * PWMs to the steppers - * - * On L6474 this sets the TVAL register (same address). - * - * I - select which driver(s) to change on multi-driver axis - * 0 - (default) all drivers on the axis or E0 - * 1 - monitor only X, Y, Z or E1 - * 2 - monitor only X2, Y2, Z2 or E2 - * 3 - monitor only Z3 or E3 - * 4 - monitor only Z4 or E4 - * 5 - monitor only E5 - * Xxxx, Yxxx, Zxxx, Exxx - axis to change (optional) - * L6474 - current in mA (4A max) - * All others - 0-255 - */ - -/** - * Sets KVAL_HOLD wich affects the current being driven through the stepper. - * - * L6470 is used in the STEP-CLOCK mode. KVAL_HOLD is the only KVAL_xxx - * that affects the effective voltage seen by the stepper. - */ - /** * MACRO to fetch information on the items associated with current limiting * and maximum voltage output. @@ -220,6 +195,28 @@ void L64XX_report_current(L64XX &motor, const L64XX_axis_t axis) { } } +/** + * M906: report or set KVAL_HOLD which sets the maximum effective voltage provided by the + * PWMs to the steppers + * + * On L6474 this sets the TVAL register (same address). + * + * I - select which driver(s) to change on multi-driver axis + * 0 - (default) all drivers on the axis or E0 + * 1 - monitor only X, Y, Z or E1 + * 2 - monitor only X2, Y2, Z2 or E2 + * 3 - monitor only Z3 or E3 + * 4 - monitor only Z4 or E4 + * 5 - monitor only E5 + * Xxxx, Yxxx, Zxxx, Exxx - axis to change (optional) + * L6474 - current in mA (4A max) + * All others - 0-255 + * + * Sets KVAL_HOLD wich affects the current being driven through the stepper. + * + * L6470 is used in the STEP-CLOCK mode. KVAL_HOLD is the only KVAL_xxx + * that affects the effective voltage seen by the stepper. + */ void GcodeSuite::M906() { L64xxManager.pause_monitor(true); // Keep monitor_driver() from stealing status @@ -252,58 +249,67 @@ void GcodeSuite::M906() { if (index == 1) L6470_SET_KVAL_HOLD(X2); #endif break; - case Y_AXIS: - #if AXIS_IS_L64XX(Y) - if (index == 0) L6470_SET_KVAL_HOLD(Y); - #endif - #if AXIS_IS_L64XX(Y2) - if (index == 1) L6470_SET_KVAL_HOLD(Y2); - #endif - break; - case Z_AXIS: - #if AXIS_IS_L64XX(Z) - if (index == 0) L6470_SET_KVAL_HOLD(Z); - #endif - #if AXIS_IS_L64XX(Z2) - if (index == 1) L6470_SET_KVAL_HOLD(Z2); - #endif - #if AXIS_IS_L64XX(Z3) - if (index == 2) L6470_SET_KVAL_HOLD(Z3); - #endif - #if AXIS_DRIVER_TYPE_Z4(L6470) - if (index == 3) L6470_SET_KVAL_HOLD(Z4); - #endif - break; - case E_AXIS: { - const int8_t target_extruder = get_target_extruder_from_command(); - if (target_extruder < 0) return; - switch (target_extruder) { - #if AXIS_IS_L64XX(E0) - case 0: L6470_SET_KVAL_HOLD(E0); break; - #endif - #if AXIS_IS_L64XX(E1) - case 1: L6470_SET_KVAL_HOLD(E1); break; - #endif - #if AXIS_IS_L64XX(E2) - case 2: L6470_SET_KVAL_HOLD(E2); break; + + #if HAS_Y_AXIS + case Y_AXIS: + #if AXIS_IS_L64XX(Y) + if (index == 0) L6470_SET_KVAL_HOLD(Y); #endif - #if AXIS_IS_L64XX(E3) - case 3: L6470_SET_KVAL_HOLD(E3); break; + #if AXIS_IS_L64XX(Y2) + if (index == 1) L6470_SET_KVAL_HOLD(Y2); #endif - #if AXIS_IS_L64XX(E4) - case 4: L6470_SET_KVAL_HOLD(E4); break; + break; + #endif + + #if HAS_Z_AXIS + case Z_AXIS: + #if AXIS_IS_L64XX(Z) + if (index == 0) L6470_SET_KVAL_HOLD(Z); #endif - #if AXIS_IS_L64XX(E5) - case 5: L6470_SET_KVAL_HOLD(E5); break; + #if AXIS_IS_L64XX(Z2) + if (index == 1) L6470_SET_KVAL_HOLD(Z2); #endif - #if AXIS_IS_L64XX(E6) - case 6: L6470_SET_KVAL_HOLD(E6); break; + #if AXIS_IS_L64XX(Z3) + if (index == 2) L6470_SET_KVAL_HOLD(Z3); #endif - #if AXIS_IS_L64XX(E7) - case 7: L6470_SET_KVAL_HOLD(E7); break; + #if AXIS_DRIVER_TYPE_Z4(L6470) + if (index == 3) L6470_SET_KVAL_HOLD(Z4); #endif - } - } break; + break; + #endif + + #if E_STEPPERS + case E_AXIS: { + const int8_t target_e_stepper = get_target_e_stepper_from_command(); + if (target_e_stepper < 0) return; + switch (target_e_stepper) { + #if AXIS_IS_L64XX(E0) + case 0: L6470_SET_KVAL_HOLD(E0); break; + #endif + #if AXIS_IS_L64XX(E1) + case 1: L6470_SET_KVAL_HOLD(E1); break; + #endif + #if AXIS_IS_L64XX(E2) + case 2: L6470_SET_KVAL_HOLD(E2); break; + #endif + #if AXIS_IS_L64XX(E3) + case 3: L6470_SET_KVAL_HOLD(E3); break; + #endif + #if AXIS_IS_L64XX(E4) + case 4: L6470_SET_KVAL_HOLD(E4); break; + #endif + #if AXIS_IS_L64XX(E5) + case 5: L6470_SET_KVAL_HOLD(E5); break; + #endif + #if AXIS_IS_L64XX(E6) + case 6: L6470_SET_KVAL_HOLD(E6); break; + #endif + #if AXIS_IS_L64XX(E7) + case 7: L6470_SET_KVAL_HOLD(E7); break; + #endif + } + } break; + #endif } } diff --git a/Marlin/src/gcode/feature/clean/G12.cpp b/Marlin/src/gcode/feature/clean/G12.cpp index 216db5bae374c..b19932eb983dc 100644 --- a/Marlin/src/gcode/feature/clean/G12.cpp +++ b/Marlin/src/gcode/feature/clean/G12.cpp @@ -42,6 +42,7 @@ * P0 S : Stroke cleaning with S strokes * P1 Sn T : Zigzag cleaning with S repeats and T zigzags * P2 Sn R : Circle cleaning with S repeats and R radius + * X, Y, Z : Specify axes to move during cleaning. Default: ALL. */ void GcodeSuite::G12() { // Don't allow nozzle cleaning without homing first diff --git a/Marlin/src/gcode/feature/digipot/M907-M910.cpp b/Marlin/src/gcode/feature/digipot/M907-M910.cpp index ee9801eda910e..118ad21564ace 100644 --- a/Marlin/src/gcode/feature/digipot/M907-M910.cpp +++ b/Marlin/src/gcode/feature/digipot/M907-M910.cpp @@ -67,8 +67,10 @@ void GcodeSuite::M907() { LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) digipot_i2c.set_current(i, parser.value_float()); // Additional extruders use B,C,D for channels 4,5,6. // TODO: Change these parameters because 'E' is used. B? - for (uint8_t i = E_AXIS + 1; i < DIGIPOT_I2C_NUM_CHANNELS; i++) - if (parser.seenval('B' + i - (E_AXIS + 1))) digipot_i2c.set_current(i, parser.value_float()); + #if HAS_EXTRUDERS + for (uint8_t i = E_AXIS + 1; i < DIGIPOT_I2C_NUM_CHANNELS; i++) + if (parser.seenval('B' + i - (E_AXIS + 1))) digipot_i2c.set_current(i, parser.value_float()); + #endif #endif #if ENABLED(HAS_MOTOR_CURRENT_DAC) diff --git a/Marlin/src/gcode/feature/leds/M150.cpp b/Marlin/src/gcode/feature/leds/M150.cpp index cf09bf14ead79..4d271007e56ea 100644 --- a/Marlin/src/gcode/feature/leds/M150.cpp +++ b/Marlin/src/gcode/feature/leds/M150.cpp @@ -52,33 +52,40 @@ * M150 I1 R ; Set NEOPIXEL index 1 to red * M150 S1 I1 R ; Set SEPARATE index 1 to red */ - void GcodeSuite::M150() { #if ENABLED(NEOPIXEL_LED) - const uint8_t index = parser.intval('I', -1); + const int8_t index = parser.intval('I', -1); #if ENABLED(NEOPIXEL2_SEPARATE) - const uint8_t unit = parser.intval('S'), - brightness = unit ? neo2.brightness() : neo.brightness(); - *(unit ? &neo2.neoindex : &neo.neoindex) = index; + int8_t brightness, unit = parser.intval('S', -1); + switch (unit) { + case -1: neo2.neoindex = index; // fall-thru + case 0: neo.neoindex = index; brightness = neo.brightness(); break; + case 1: neo2.neoindex = index; brightness = neo2.brightness(); break; + } #else const uint8_t brightness = neo.brightness(); neo.neoindex = index; #endif #endif - const LEDColor color = MakeLEDColor( + const LEDColor color = LEDColor( parser.seen('R') ? (parser.has_value() ? parser.value_byte() : 255) : 0, parser.seen('U') ? (parser.has_value() ? parser.value_byte() : 255) : 0, - parser.seen('B') ? (parser.has_value() ? parser.value_byte() : 255) : 0, - parser.seen('W') ? (parser.has_value() ? parser.value_byte() : 255) : 0, - parser.seen('P') ? (parser.has_value() ? parser.value_byte() : 255) : brightness + parser.seen('B') ? (parser.has_value() ? parser.value_byte() : 255) : 0 + OPTARG(HAS_WHITE_LED, parser.seen('W') ? (parser.has_value() ? parser.value_byte() : 255) : 0) + OPTARG(NEOPIXEL_LED, parser.seen('P') ? (parser.has_value() ? parser.value_byte() : 255) : brightness) ); #if ENABLED(NEOPIXEL2_SEPARATE) - if (unit == 1) { leds2.set_color(color); return; } + switch (unit) { + case 0: leds.set_color(color); return; + case 1: leds2.set_color(color); return; + } #endif + // If 'S' is not specified use both leds.set_color(color); + TERN_(NEOPIXEL2_SEPARATE, leds2.set_color(color)); } #endif // HAS_COLOR_LEDS diff --git a/Marlin/src/gcode/feature/pause/G60.cpp b/Marlin/src/gcode/feature/pause/G60.cpp index 670ea2a58be69..79451235b1d9a 100644 --- a/Marlin/src/gcode/feature/pause/G60.cpp +++ b/Marlin/src/gcode/feature/pause/G60.cpp @@ -47,12 +47,13 @@ void GcodeSuite::G60() { SBI(saved_slots[slot >> 3], slot & 0x07); #if ENABLED(SAVED_POSITIONS_DEBUG) - const xyze_pos_t &pos = stored_position[slot]; DEBUG_ECHOPAIR(STR_SAVED_POS " S", slot); - DEBUG_ECHOPAIR_F(" : X", pos.x); - DEBUG_ECHOPAIR_F_P(SP_Y_STR, pos.y); - DEBUG_ECHOPAIR_F_P(SP_Z_STR, pos.z); - DEBUG_ECHOLNPAIR_F_P(SP_E_STR, pos.e); + const xyze_pos_t &pos = stored_position[slot]; + DEBUG_ECHOLNPAIR_F_P( + LIST_N(DOUBLE(LOGICAL_AXES), SP_E_STR, pos.e, + PSTR(" : X"), pos.x, SP_Y_STR, pos.y, SP_Z_STR, pos.z, + SP_I_STR, pos.i, SP_J_STR, pos.j, SP_K_STR, pos.k) + ); #endif } diff --git a/Marlin/src/gcode/feature/pause/G61.cpp b/Marlin/src/gcode/feature/pause/G61.cpp index a6d7cb3094c4d..a10c8217ef44a 100644 --- a/Marlin/src/gcode/feature/pause/G61.cpp +++ b/Marlin/src/gcode/feature/pause/G61.cpp @@ -37,8 +37,7 @@ * * F - Feedrate (optional) for the move back. * S - Slot # (0-based) to restore from (default 0). - * X Y Z - Axes to restore. At least one is required. - * E - Restore extruder position + * X Y Z E - Axes to restore. At least one is required. * * If XYZE are not given, default restore uses the smart blocking move. */ @@ -46,7 +45,7 @@ void GcodeSuite::G61(void) { const uint8_t slot = parser.byteval('S'); - #define SYNC_E(POINT) planner.set_e_position_mm((destination.e = current_position.e = (POINT))) + #define SYNC_E(POINT) TERN_(HAS_EXTRUDERS, planner.set_e_position_mm((destination.e = current_position.e = (POINT)))) #if SAVED_POSITIONS < 256 if (slot >= SAVED_POSITIONS) { @@ -69,7 +68,7 @@ void GcodeSuite::G61(void) { SYNC_E(stored_position[slot].e); } else { - if (parser.seen("XYZ")) { + if (parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR))) { DEBUG_ECHOPAIR(STR_RESTORING_POS " S", slot); LOOP_LINEAR_AXES(i) { destination[i] = parser.seen(AXIS_CHAR(i)) @@ -82,10 +81,12 @@ void GcodeSuite::G61(void) { // Move to the saved position prepare_line_to_destination(); } - if (parser.seen_test('E')) { - DEBUG_ECHOLNPAIR(STR_RESTORING_POS " S", slot, " E", current_position.e, "=>", stored_position[slot].e); - SYNC_E(stored_position[slot].e); - } + #if HAS_EXTRUDERS + if (parser.seen_test('E')) { + DEBUG_ECHOLNPAIR(STR_RESTORING_POS " S", slot, " E", current_position.e, "=>", stored_position[slot].e); + SYNC_E(stored_position[slot].e); + } + #endif } feedrate_mm_s = saved_feedrate; diff --git a/Marlin/src/gcode/feature/pause/M125.cpp b/Marlin/src/gcode/feature/pause/M125.cpp index 2eb4ceea41713..bc31e1225d86c 100644 --- a/Marlin/src/gcode/feature/pause/M125.cpp +++ b/Marlin/src/gcode/feature/pause/M125.cpp @@ -56,7 +56,7 @@ */ void GcodeSuite::M125() { // Initial retract before move to filament change position - const float retract = -ABS(parser.axisunitsval('L', E_AXIS, PAUSE_PARK_RETRACT_LENGTH)); + const float retract = TERN0(HAS_EXTRUDERS, -ABS(parser.axisunitsval('L', E_AXIS, PAUSE_PARK_RETRACT_LENGTH))); xyz_pos_t park_point = NOZZLE_PARK_POINT; diff --git a/Marlin/src/gcode/feature/pause/M600.cpp b/Marlin/src/gcode/feature/pause/M600.cpp index 2daa7d999a191..541fa08350e67 100644 --- a/Marlin/src/gcode/feature/pause/M600.cpp +++ b/Marlin/src/gcode/feature/pause/M600.cpp @@ -99,7 +99,7 @@ void GcodeSuite::M600() { #if ENABLED(HOME_BEFORE_FILAMENT_CHANGE) // If needed, home before parking for filament change - if (!all_axes_trusted()) home_all_axes(true); + home_if_needed(true); #endif #if HAS_MULTI_EXTRUDER diff --git a/Marlin/src/gcode/feature/runout/M412.cpp b/Marlin/src/gcode/feature/runout/M412.cpp index 540a160623002..9a063571326fb 100644 --- a/Marlin/src/gcode/feature/runout/M412.cpp +++ b/Marlin/src/gcode/feature/runout/M412.cpp @@ -54,10 +54,15 @@ void GcodeSuite::M412() { else { SERIAL_ECHO_START(); SERIAL_ECHOPGM("Filament runout "); - serialprintln_onoff(runout.enabled); + serialprint_onoff(runout.enabled); #if HAS_FILAMENT_RUNOUT_DISTANCE - SERIAL_ECHOLNPAIR("Filament runout distance (mm): ", runout.runout_distance()); + SERIAL_ECHOPAIR(" ; Distance ", runout.runout_distance(), "mm"); #endif + #if ENABLED(HOST_ACTION_COMMANDS) + SERIAL_ECHOPGM(" ; Host handling "); + serialprint_onoff(runout.host_handling); + #endif + SERIAL_EOL(); } } diff --git a/Marlin/src/gcode/feature/trinamic/M122.cpp b/Marlin/src/gcode/feature/trinamic/M122.cpp index 054d145c8c233..52a6920f0512a 100644 --- a/Marlin/src/gcode/feature/trinamic/M122.cpp +++ b/Marlin/src/gcode/feature/trinamic/M122.cpp @@ -35,7 +35,7 @@ void GcodeSuite::M122() { xyze_bool_t print_axis = ARRAY_N_1(LOGICAL_AXES, false); bool print_all = true; - LOOP_LOGICAL_AXES(i) if (parser.seen(axis_codes[i])) { print_axis[i] = true; print_all = false; } + LOOP_LOGICAL_AXES(i) if (parser.seen_test(axis_codes[i])) { print_axis[i] = true; print_all = false; } if (print_all) LOOP_LOGICAL_AXES(i) print_axis[i] = true; @@ -50,12 +50,12 @@ void GcodeSuite::M122() { #endif if (parser.seen_test('V')) - tmc_get_registers(print_axis.x, print_axis.y, print_axis.z, print_axis.e); + tmc_get_registers(LOGICAL_AXIS_ELEM(print_axis)); else - tmc_report_all(print_axis.x, print_axis.y, print_axis.z, print_axis.e); + tmc_report_all(LOGICAL_AXIS_ELEM(print_axis)); #endif - test_tmc_connection(print_axis.x, print_axis.y, print_axis.z, print_axis.e); + test_tmc_connection(LOGICAL_AXIS_ELEM(print_axis)); } #endif // HAS_TRINAMIC_CONFIG diff --git a/Marlin/src/gcode/feature/trinamic/M569.cpp b/Marlin/src/gcode/feature/trinamic/M569.cpp index 8f1c0ed819230..9a7f1fbce9021 100644 --- a/Marlin/src/gcode/feature/trinamic/M569.cpp +++ b/Marlin/src/gcode/feature/trinamic/M569.cpp @@ -40,132 +40,88 @@ void tmc_set_stealthChop(TMC &st, const bool enable) { st.refresh_stepping_mode(); } -static void set_stealth_status(const bool enable, const int8_t target_extruder) { +static void set_stealth_status(const bool enable, const int8_t target_e_stepper) { #define TMC_SET_STEALTH(Q) tmc_set_stealthChop(stepper##Q, enable) - #if AXIS_HAS_STEALTHCHOP(X) || AXIS_HAS_STEALTHCHOP(X2) \ - || AXIS_HAS_STEALTHCHOP(Y) || AXIS_HAS_STEALTHCHOP(Y2) \ - || AXIS_HAS_STEALTHCHOP(Z) || AXIS_HAS_STEALTHCHOP(Z2) \ - || AXIS_HAS_STEALTHCHOP(Z3) || AXIS_HAS_STEALTHCHOP(Z4) + #if X_HAS_STEALTHCHOP || Y_HAS_STEALTHCHOP || Z_HAS_STEALTHCHOP \ + || I_HAS_STEALTHCHOP || J_HAS_STEALTHCHOP || K_HAS_STEALTHCHOP \ + || X2_HAS_STEALTHCHOP || Y2_HAS_STEALTHCHOP || Z2_HAS_STEALTHCHOP || Z3_HAS_STEALTHCHOP || Z4_HAS_STEALTHCHOP const uint8_t index = parser.byteval('I'); #endif LOOP_LOGICAL_AXES(i) if (parser.seen(axis_codes[i])) { switch (i) { case X_AXIS: - #if AXIS_HAS_STEALTHCHOP(X) - if (index == 0) TMC_SET_STEALTH(X); - #endif - #if AXIS_HAS_STEALTHCHOP(X2) - if (index == 1) TMC_SET_STEALTH(X2); - #endif + TERN_(X_HAS_STEALTHCHOP, if (index == 0) TMC_SET_STEALTH(X)); + TERN_(X2_HAS_STEALTHCHOP, if (index == 1) TMC_SET_STEALTH(X2)); break; - case Y_AXIS: - #if AXIS_HAS_STEALTHCHOP(Y) - if (index == 0) TMC_SET_STEALTH(Y); - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - if (index == 1) TMC_SET_STEALTH(Y2); - #endif - break; - case Z_AXIS: - #if AXIS_HAS_STEALTHCHOP(Z) - if (index == 0) TMC_SET_STEALTH(Z); - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - if (index == 1) TMC_SET_STEALTH(Z2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z3) - if (index == 2) TMC_SET_STEALTH(Z3); - #endif - #if AXIS_HAS_STEALTHCHOP(Z4) - if (index == 3) TMC_SET_STEALTH(Z4); - #endif - break; - case E_AXIS: { - if (target_extruder < 0) return; - switch (target_extruder) { - #if AXIS_HAS_STEALTHCHOP(E0) - case 0: TMC_SET_STEALTH(E0); break; - #endif - #if AXIS_HAS_STEALTHCHOP(E1) - case 1: TMC_SET_STEALTH(E1); break; - #endif - #if AXIS_HAS_STEALTHCHOP(E2) - case 2: TMC_SET_STEALTH(E2); break; - #endif - #if AXIS_HAS_STEALTHCHOP(E3) - case 3: TMC_SET_STEALTH(E3); break; - #endif - #if AXIS_HAS_STEALTHCHOP(E4) - case 4: TMC_SET_STEALTH(E4); break; - #endif - #if AXIS_HAS_STEALTHCHOP(E5) - case 5: TMC_SET_STEALTH(E5); break; - #endif - #if AXIS_HAS_STEALTHCHOP(E6) - case 6: TMC_SET_STEALTH(E6); break; - #endif - #if AXIS_HAS_STEALTHCHOP(E7) - case 7: TMC_SET_STEALTH(E7); break; - #endif - } - } break; + + #if HAS_Y_AXIS + case Y_AXIS: + TERN_(Y_HAS_STEALTHCHOP, if (index == 0) TMC_SET_STEALTH(Y)); + TERN_(Y2_HAS_STEALTHCHOP, if (index == 1) TMC_SET_STEALTH(Y2)); + break; + #endif + + #if HAS_Z_AXIS + case Z_AXIS: + TERN_(Z_HAS_STEALTHCHOP, if (index == 0) TMC_SET_STEALTH(Z)); + TERN_(Z2_HAS_STEALTHCHOP, if (index == 1) TMC_SET_STEALTH(Z2)); + TERN_(Z3_HAS_STEALTHCHOP, if (index == 2) TMC_SET_STEALTH(Z3)); + TERN_(Z4_HAS_STEALTHCHOP, if (index == 3) TMC_SET_STEALTH(Z4)); + break; + #endif + + #if I_HAS_STEALTHCHOP + case I_AXIS: TMC_SET_STEALTH(I); break; + #endif + #if J_HAS_STEALTHCHOP + case J_AXIS: TMC_SET_STEALTH(J); break; + #endif + #if K_HAS_STEALTHCHOP + case K_AXIS: TMC_SET_STEALTH(K); break; + #endif + + #if E_STEPPERS + case E_AXIS: { + if (target_e_stepper < 0) return; + switch (target_e_stepper) { + TERN_(E0_HAS_STEALTHCHOP, case 0: TMC_SET_STEALTH(E0); break;) + TERN_(E1_HAS_STEALTHCHOP, case 1: TMC_SET_STEALTH(E1); break;) + TERN_(E2_HAS_STEALTHCHOP, case 2: TMC_SET_STEALTH(E2); break;) + TERN_(E3_HAS_STEALTHCHOP, case 3: TMC_SET_STEALTH(E3); break;) + TERN_(E4_HAS_STEALTHCHOP, case 4: TMC_SET_STEALTH(E4); break;) + TERN_(E5_HAS_STEALTHCHOP, case 5: TMC_SET_STEALTH(E5); break;) + TERN_(E6_HAS_STEALTHCHOP, case 6: TMC_SET_STEALTH(E6); break;) + TERN_(E7_HAS_STEALTHCHOP, case 7: TMC_SET_STEALTH(E7); break;) + } + } break; + #endif } } } static void say_stealth_status() { #define TMC_SAY_STEALTH_STATUS(Q) tmc_say_stealth_status(stepper##Q) - - #if AXIS_HAS_STEALTHCHOP(X) - TMC_SAY_STEALTH_STATUS(X); - #endif - #if AXIS_HAS_STEALTHCHOP(X2) - TMC_SAY_STEALTH_STATUS(X2); - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - TMC_SAY_STEALTH_STATUS(Y); - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - TMC_SAY_STEALTH_STATUS(Y2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - TMC_SAY_STEALTH_STATUS(Z); - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - TMC_SAY_STEALTH_STATUS(Z2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z3) - TMC_SAY_STEALTH_STATUS(Z3); - #endif - #if AXIS_HAS_STEALTHCHOP(Z4) - TMC_SAY_STEALTH_STATUS(Z4); - #endif - #if AXIS_HAS_STEALTHCHOP(E0) - TMC_SAY_STEALTH_STATUS(E0); - #endif - #if AXIS_HAS_STEALTHCHOP(E1) - TMC_SAY_STEALTH_STATUS(E1); - #endif - #if AXIS_HAS_STEALTHCHOP(E2) - TMC_SAY_STEALTH_STATUS(E2); - #endif - #if AXIS_HAS_STEALTHCHOP(E3) - TMC_SAY_STEALTH_STATUS(E3); - #endif - #if AXIS_HAS_STEALTHCHOP(E4) - TMC_SAY_STEALTH_STATUS(E4); - #endif - #if AXIS_HAS_STEALTHCHOP(E5) - TMC_SAY_STEALTH_STATUS(E5); - #endif - #if AXIS_HAS_STEALTHCHOP(E6) - TMC_SAY_STEALTH_STATUS(E6); - #endif - #if AXIS_HAS_STEALTHCHOP(E7) - TMC_SAY_STEALTH_STATUS(E7); - #endif + OPTCODE( X_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(X)) + OPTCODE(X2_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(X2)) + OPTCODE( Y_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(Y)) + OPTCODE(Y2_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(Y2)) + OPTCODE( Z_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(Z)) + OPTCODE(Z2_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(Z2)) + OPTCODE(Z3_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(Z3)) + OPTCODE(Z4_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(Z4)) + OPTCODE( I_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(I)) + OPTCODE( J_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(J)) + OPTCODE( K_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(K)) + OPTCODE(E0_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E0)) + OPTCODE(E1_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E1)) + OPTCODE(E2_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E2)) + OPTCODE(E3_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E3)) + OPTCODE(E4_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E4)) + OPTCODE(E5_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E5)) + OPTCODE(E6_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E6)) + OPTCODE(E7_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E7)) } /** @@ -177,7 +133,7 @@ static void say_stealth_status() { */ void GcodeSuite::M569() { if (parser.seen('S')) - set_stealth_status(parser.value_bool(), get_target_extruder_from_command()); + set_stealth_status(parser.value_bool(), get_target_e_stepper_from_command()); else say_stealth_status(); } diff --git a/Marlin/src/gcode/feature/trinamic/M906.cpp b/Marlin/src/gcode/feature/trinamic/M906.cpp index 86e0cd29871e8..9e56e513581d5 100644 --- a/Marlin/src/gcode/feature/trinamic/M906.cpp +++ b/Marlin/src/gcode/feature/trinamic/M906.cpp @@ -48,7 +48,7 @@ void GcodeSuite::M906() { bool report = true; - #if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4) + #if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4) || AXIS_IS_TMC(I) || AXIS_IS_TMC(J) || AXIS_IS_TMC(K) const uint8_t index = parser.byteval('I'); #endif @@ -63,58 +63,77 @@ void GcodeSuite::M906() { if (index == 1) TMC_SET_CURRENT(X2); #endif break; - case Y_AXIS: - #if AXIS_IS_TMC(Y) - if (index == 0) TMC_SET_CURRENT(Y); - #endif - #if AXIS_IS_TMC(Y2) - if (index == 1) TMC_SET_CURRENT(Y2); - #endif - break; - case Z_AXIS: - #if AXIS_IS_TMC(Z) - if (index == 0) TMC_SET_CURRENT(Z); - #endif - #if AXIS_IS_TMC(Z2) - if (index == 1) TMC_SET_CURRENT(Z2); - #endif - #if AXIS_IS_TMC(Z3) - if (index == 2) TMC_SET_CURRENT(Z3); - #endif - #if AXIS_IS_TMC(Z4) - if (index == 3) TMC_SET_CURRENT(Z4); - #endif - break; - case E_AXIS: { - const int8_t target_extruder = get_target_extruder_from_command(); - if (target_extruder < 0) return; - switch (target_extruder) { - #if AXIS_IS_TMC(E0) - case 0: TMC_SET_CURRENT(E0); break; - #endif - #if AXIS_IS_TMC(E1) - case 1: TMC_SET_CURRENT(E1); break; - #endif - #if AXIS_IS_TMC(E2) - case 2: TMC_SET_CURRENT(E2); break; + + #if HAS_Y_AXIS + case Y_AXIS: + #if AXIS_IS_TMC(Y) + if (index == 0) TMC_SET_CURRENT(Y); #endif - #if AXIS_IS_TMC(E3) - case 3: TMC_SET_CURRENT(E3); break; + #if AXIS_IS_TMC(Y2) + if (index == 1) TMC_SET_CURRENT(Y2); #endif - #if AXIS_IS_TMC(E4) - case 4: TMC_SET_CURRENT(E4); break; + break; + #endif + + #if HAS_Z_AXIS + case Z_AXIS: + #if AXIS_IS_TMC(Z) + if (index == 0) TMC_SET_CURRENT(Z); #endif - #if AXIS_IS_TMC(E5) - case 5: TMC_SET_CURRENT(E5); break; + #if AXIS_IS_TMC(Z2) + if (index == 1) TMC_SET_CURRENT(Z2); #endif - #if AXIS_IS_TMC(E6) - case 6: TMC_SET_CURRENT(E6); break; + #if AXIS_IS_TMC(Z3) + if (index == 2) TMC_SET_CURRENT(Z3); #endif - #if AXIS_IS_TMC(E7) - case 7: TMC_SET_CURRENT(E7); break; + #if AXIS_IS_TMC(Z4) + if (index == 3) TMC_SET_CURRENT(Z4); #endif - } - } break; + break; + #endif + + #if AXIS_IS_TMC(I) + case I_AXIS: TMC_SET_CURRENT(I); break; + #endif + #if AXIS_IS_TMC(J) + case J_AXIS: TMC_SET_CURRENT(J); break; + #endif + #if AXIS_IS_TMC(K) + case K_AXIS: TMC_SET_CURRENT(K); break; + #endif + + #if E_STEPPERS + case E_AXIS: { + const int8_t target_e_stepper = get_target_e_stepper_from_command(); + if (target_e_stepper < 0) return; + switch (target_e_stepper) { + #if AXIS_IS_TMC(E0) + case 0: TMC_SET_CURRENT(E0); break; + #endif + #if AXIS_IS_TMC(E1) + case 1: TMC_SET_CURRENT(E1); break; + #endif + #if AXIS_IS_TMC(E2) + case 2: TMC_SET_CURRENT(E2); break; + #endif + #if AXIS_IS_TMC(E3) + case 3: TMC_SET_CURRENT(E3); break; + #endif + #if AXIS_IS_TMC(E4) + case 4: TMC_SET_CURRENT(E4); break; + #endif + #if AXIS_IS_TMC(E5) + case 5: TMC_SET_CURRENT(E5); break; + #endif + #if AXIS_IS_TMC(E6) + case 6: TMC_SET_CURRENT(E6); break; + #endif + #if AXIS_IS_TMC(E7) + case 7: TMC_SET_CURRENT(E7); break; + #endif + } + } break; + #endif } } @@ -143,6 +162,15 @@ void GcodeSuite::M906() { #if AXIS_IS_TMC(Z4) TMC_SAY_CURRENT(Z4); #endif + #if AXIS_IS_TMC(I) + TMC_SAY_CURRENT(I); + #endif + #if AXIS_IS_TMC(J) + TMC_SAY_CURRENT(J); + #endif + #if AXIS_IS_TMC(K) + TMC_SAY_CURRENT(K); + #endif #if AXIS_IS_TMC(E0) TMC_SAY_CURRENT(E0); #endif diff --git a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp index c4b4a8772e955..f90a30aab2f60 100644 --- a/Marlin/src/gcode/feature/trinamic/M911-M914.cpp +++ b/Marlin/src/gcode/feature/trinamic/M911-M914.cpp @@ -38,18 +38,27 @@ #if M91x_USE(X) || M91x_USE(X2) #define M91x_SOME_X 1 #endif - #if M91x_USE(Y) || M91x_USE(Y2) + #if LINEAR_AXES >= 2 && (M91x_USE(Y) || M91x_USE(Y2)) #define M91x_SOME_Y 1 #endif - #if M91x_USE(Z) || M91x_USE(Z2) || M91x_USE(Z3) || M91x_USE(Z4) + #if HAS_Z_AXIS && (M91x_USE(Z) || M91x_USE(Z2) || M91x_USE(Z3) || M91x_USE(Z4)) #define M91x_SOME_Z 1 #endif + #if LINEAR_AXES >= 4 && M91x_USE(I) + #define M91x_USE_I 1 + #endif + #if LINEAR_AXES >= 5 && M91x_USE(J) + #define M91x_USE_J 1 + #endif + #if LINEAR_AXES >= 6 && M91x_USE(K) + #define M91x_USE_K 1 + #endif #if M91x_USE_E(0) || M91x_USE_E(1) || M91x_USE_E(2) || M91x_USE_E(3) || M91x_USE_E(4) || M91x_USE_E(5) || M91x_USE_E(6) || M91x_USE_E(7) #define M91x_SOME_E 1 #endif - #if !M91x_SOME_X && !M91x_SOME_Y && !M91x_SOME_Z && !M91x_SOME_E + #if !M91x_SOME_X && !M91x_SOME_Y && !M91x_SOME_Z && !M91x_USE_I && !M91x_USE_J && !M91x_USE_K && !M91x_SOME_E #error "MONITOR_DRIVER_STATUS requires at least one TMC2130, 2160, 2208, 2209, 2660, 5130, or 5160." #endif @@ -82,6 +91,9 @@ #if M91x_USE(Z4) tmc_report_otpw(stepperZ4); #endif + TERN_(M91x_USE_I, tmc_report_otpw(stepperI)); + TERN_(M91x_USE_J, tmc_report_otpw(stepperJ)); + TERN_(M91x_USE_K, tmc_report_otpw(stepperK)); #if M91x_USE_E(0) tmc_report_otpw(stepperE0); #endif @@ -124,9 +136,12 @@ const bool hasX = TERN0(M91x_SOME_X, parser.seen(axis_codes.x)), hasY = TERN0(M91x_SOME_Y, parser.seen(axis_codes.y)), hasZ = TERN0(M91x_SOME_Z, parser.seen(axis_codes.z)), + hasI = TERN0(M91x_USE_I, parser.seen(axis_codes.i)), + hasJ = TERN0(M91x_USE_J, parser.seen(axis_codes.j)), + hasK = TERN0(M91x_USE_K, parser.seen(axis_codes.k)), hasE = TERN0(M91x_SOME_E, parser.seen(axis_codes.e)); - const bool hasNone = !hasE && !hasX && !hasY && !hasZ; + const bool hasNone = !hasE && !hasX && !hasY && !hasZ && !hasI && !hasJ && !hasK; #if M91x_SOME_X const int8_t xval = int8_t(parser.byteval(axis_codes.x, 0xFF)); @@ -164,6 +179,19 @@ #endif #endif + #if M91x_USE_I + const int8_t ival = int8_t(parser.byteval(axis_codes.i, 0xFF)); + if (hasNone || ival == 1 || (hasI && ival < 0)) tmc_clear_otpw(stepperI); + #endif + #if M91x_USE_J + const int8_t jval = int8_t(parser.byteval(axis_codes.j, 0xFF)); + if (hasNone || jval == 1 || (hasJ && jval < 0)) tmc_clear_otpw(stepperJ); + #endif + #if M91x_USE_K + const int8_t kval = int8_t(parser.byteval(axis_codes.k, 0xFF)); + if (hasNone || kval == 1 || (hasK && kval < 0)) tmc_clear_otpw(stepperK); + #endif + #if M91x_SOME_E const int8_t eval = int8_t(parser.byteval(axis_codes.e, 0xFF)); #if M91x_USE_E(0) @@ -206,126 +234,78 @@ #define TMC_SET_PWMTHRS_E(E) stepperE##E.set_pwm_thrs(value) bool report = true; - #if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4) + #if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4) || AXIS_IS_TMC(I) || AXIS_IS_TMC(J) || AXIS_IS_TMC(K) const uint8_t index = parser.byteval('I'); #endif LOOP_LOGICAL_AXES(i) if (int32_t value = parser.longval(axis_codes[i])) { report = false; switch (i) { case X_AXIS: - #if AXIS_HAS_STEALTHCHOP(X) - if (index < 2) TMC_SET_PWMTHRS(X,X); - #endif - #if AXIS_HAS_STEALTHCHOP(X2) - if (!(index & 1)) TMC_SET_PWMTHRS(X,X2); - #endif + TERN_(X_HAS_STEALTHCHOP, if (index < 2) TMC_SET_PWMTHRS(X,X)); + TERN_(X2_HAS_STEALTHCHOP, if (!(index & 1)) TMC_SET_PWMTHRS(X,X2)); break; case Y_AXIS: - #if AXIS_HAS_STEALTHCHOP(Y) - if (index < 2) TMC_SET_PWMTHRS(Y,Y); - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - if (!(index & 1)) TMC_SET_PWMTHRS(Y,Y2); - #endif + TERN_(Y_HAS_STEALTHCHOP, if (index < 2) TMC_SET_PWMTHRS(Y,Y)); + TERN_(Y2_HAS_STEALTHCHOP, if (!(index & 1)) TMC_SET_PWMTHRS(Y,Y2)); break; + + #if I_HAS_STEALTHCHOP + case I_AXIS: TMC_SET_PWMTHRS(I,I); break; + #endif + #if J_HAS_STEALTHCHOP + case J_AXIS: TMC_SET_PWMTHRS(J,J); break; + #endif + #if K_HAS_STEALTHCHOP + case K_AXIS: TMC_SET_PWMTHRS(K,K); break; + #endif + case Z_AXIS: - #if AXIS_HAS_STEALTHCHOP(Z) - if (index < 2) TMC_SET_PWMTHRS(Z,Z); - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - if (index == 0 || index == 2) TMC_SET_PWMTHRS(Z,Z2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z3) - if (index == 0 || index == 3) TMC_SET_PWMTHRS(Z,Z3); - #endif - #if AXIS_HAS_STEALTHCHOP(Z4) - if (index == 0 || index == 4) TMC_SET_PWMTHRS(Z,Z4); - #endif + TERN_(Z_HAS_STEALTCHOP, if (index < 2) TMC_SET_PWMTHRS(Z,Z)); + TERN_(Z2_HAS_STEALTCHOP, if (index == 0 || index == 2) TMC_SET_PWMTHRS(Z,Z2)); + TERN_(Z3_HAS_STEALTCHOP, if (index == 0 || index == 3) TMC_SET_PWMTHRS(Z,Z3)); + TERN_(Z4_HAS_STEALTCHOP, if (index == 0 || index == 4) TMC_SET_PWMTHRS(Z,Z4)); break; - case E_AXIS: { - #if E_STEPPERS - const int8_t target_extruder = get_target_extruder_from_command(); - if (target_extruder < 0) return; - switch (target_extruder) { - #if AXIS_HAS_STEALTHCHOP(E0) - case 0: TMC_SET_PWMTHRS_E(0); break; - #endif - #if E_STEPPERS > 1 && AXIS_HAS_STEALTHCHOP(E1) - case 1: TMC_SET_PWMTHRS_E(1); break; - #endif - #if E_STEPPERS > 2 && AXIS_HAS_STEALTHCHOP(E2) - case 2: TMC_SET_PWMTHRS_E(2); break; - #endif - #if E_STEPPERS > 3 && AXIS_HAS_STEALTHCHOP(E3) - case 3: TMC_SET_PWMTHRS_E(3); break; - #endif - #if E_STEPPERS > 4 && AXIS_HAS_STEALTHCHOP(E4) - case 4: TMC_SET_PWMTHRS_E(4); break; - #endif - #if E_STEPPERS > 5 && AXIS_HAS_STEALTHCHOP(E5) - case 5: TMC_SET_PWMTHRS_E(5); break; - #endif - #if E_STEPPERS > 6 && AXIS_HAS_STEALTHCHOP(E6) - case 6: TMC_SET_PWMTHRS_E(6); break; - #endif - #if E_STEPPERS > 7 && AXIS_HAS_STEALTHCHOP(E7) - case 7: TMC_SET_PWMTHRS_E(7); break; - #endif + #if E_STEPPERS + case E_AXIS: { + const int8_t target_e_stepper = get_target_e_stepper_from_command(); + if (target_e_stepper < 0) return; + switch (target_e_stepper) { + TERN_(E0_HAS_STEALTHCHOP, case 0: TMC_SET_PWMTHRS_E(0); break;) + TERN_(E1_HAS_STEALTHCHOP, case 1: TMC_SET_PWMTHRS_E(1); break;) + TERN_(E2_HAS_STEALTHCHOP, case 2: TMC_SET_PWMTHRS_E(2); break;) + TERN_(E3_HAS_STEALTHCHOP, case 3: TMC_SET_PWMTHRS_E(3); break;) + TERN_(E4_HAS_STEALTHCHOP, case 4: TMC_SET_PWMTHRS_E(4); break;) + TERN_(E5_HAS_STEALTHCHOP, case 5: TMC_SET_PWMTHRS_E(5); break;) + TERN_(E6_HAS_STEALTHCHOP, case 6: TMC_SET_PWMTHRS_E(6); break;) + TERN_(E7_HAS_STEALTHCHOP, case 7: TMC_SET_PWMTHRS_E(7); break;) } - #endif // E_STEPPERS - } break; + } break; + #endif // E_STEPPERS } } if (report) { - #if AXIS_HAS_STEALTHCHOP(X) - TMC_SAY_PWMTHRS(X,X); - #endif - #if AXIS_HAS_STEALTHCHOP(X2) - TMC_SAY_PWMTHRS(X,X2); - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - TMC_SAY_PWMTHRS(Y,Y); - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - TMC_SAY_PWMTHRS(Y,Y2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - TMC_SAY_PWMTHRS(Z,Z); - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - TMC_SAY_PWMTHRS(Z,Z2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z3) - TMC_SAY_PWMTHRS(Z,Z3); - #endif - #if AXIS_HAS_STEALTHCHOP(Z4) - TMC_SAY_PWMTHRS(Z,Z4); - #endif - #if E_STEPPERS && AXIS_HAS_STEALTHCHOP(E0) - TMC_SAY_PWMTHRS_E(0); - #endif - #if E_STEPPERS > 1 && AXIS_HAS_STEALTHCHOP(E1) - TMC_SAY_PWMTHRS_E(1); - #endif - #if E_STEPPERS > 2 && AXIS_HAS_STEALTHCHOP(E2) - TMC_SAY_PWMTHRS_E(2); - #endif - #if E_STEPPERS > 3 && AXIS_HAS_STEALTHCHOP(E3) - TMC_SAY_PWMTHRS_E(3); - #endif - #if E_STEPPERS > 4 && AXIS_HAS_STEALTHCHOP(E4) - TMC_SAY_PWMTHRS_E(4); - #endif - #if E_STEPPERS > 5 && AXIS_HAS_STEALTHCHOP(E5) - TMC_SAY_PWMTHRS_E(5); - #endif - #if E_STEPPERS > 6 && AXIS_HAS_STEALTHCHOP(E6) - TMC_SAY_PWMTHRS_E(6); - #endif - #if E_STEPPERS > 7 && AXIS_HAS_STEALTHCHOP(E7) - TMC_SAY_PWMTHRS_E(7); - #endif + TERN_( X_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(X,X)); + TERN_(X2_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(X,X2)); + TERN_( Y_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(Y,Y)); + TERN_(Y2_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(Y,Y2)); + TERN_( Z_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(Z,Z)); + TERN_(Z2_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(Z,Z2)); + TERN_(Z3_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(Z,Z3)); + TERN_(Z4_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(Z,Z4)); + + TERN_( I_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(I,I)); + TERN_( J_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(J,J)); + TERN_( K_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(K,K)); + + TERN_(E0_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(0)); + TERN_(E1_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(1)); + TERN_(E2_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(2)); + TERN_(E3_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(3)); + TERN_(E4_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(4)); + TERN_(E5_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(5)); + TERN_(E6_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(6)); + TERN_(E7_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(7)); } } #endif // HYBRID_THRESHOLD @@ -378,6 +358,15 @@ #endif break; #endif + #if I_SENSORLESS && AXIS_HAS_STALLGUARD(I) + case I_AXIS: stepperI.homing_threshold(value); break; + #endif + #if J_SENSORLESS && AXIS_HAS_STALLGUARD(J) + case J_AXIS: stepperJ.homing_threshold(value); break; + #endif + #if K_SENSORLESS && AXIS_HAS_STALLGUARD(K) + case K_AXIS: stepperK.homing_threshold(value); break; + #endif } } @@ -412,6 +401,15 @@ tmc_print_sgt(stepperZ4); #endif #endif + #if I_SENSORLESS && AXIS_HAS_STALLGUARD(I) + tmc_print_sgt(stepperI); + #endif + #if J_SENSORLESS && AXIS_HAS_STALLGUARD(J) + tmc_print_sgt(stepperJ); + #endif + #if K_SENSORLESS && AXIS_HAS_STALLGUARD(K) + tmc_print_sgt(stepperK); + #endif } } #endif // USE_SENSORLESS diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index fa4682c0823f9..ac3b5010b9800 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -74,11 +74,14 @@ millis_t GcodeSuite::previous_move_ms = 0, // 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 ? _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) +uint8_t GcodeSuite::axis_relative = 0 LOGICAL_AXIS_GANG( + | (ar_init.e << REL_E), + | (ar_init.x << REL_X), + | (ar_init.y << REL_Y), + | (ar_init.z << REL_Z), + | (ar_init.i << REL_I), + | (ar_init.j << REL_J), + | (ar_init.k << REL_K) ); #if EITHER(HAS_AUTO_REPORTING, HOST_KEEPALIVE_FEATURE) @@ -161,13 +164,15 @@ void GcodeSuite::get_destination_from_command() { destination[i] = current_position[i]; } - // Get new E position, whether absolute or relative - if ( (seen.e = parser.seenval('E')) ) { - const float v = parser.value_axis_units(E_AXIS); - destination.e = axis_is_relative(E_AXIS) ? current_position.e + v : v; - } - else - destination.e = current_position.e; + #if HAS_EXTRUDERS + // Get new E position, whether absolute or relative + if ( (seen.e = parser.seenval('E')) ) { + const float v = parser.value_axis_units(E_AXIS); + destination.e = axis_is_relative(E_AXIS) ? current_position.e + v : v; + } + else + destination.e = current_position.e; + #endif #if ENABLED(POWER_LOSS_RECOVERY) && !PIN_EXISTS(POWER_LOSS) // Only update power loss recovery on moves with E @@ -436,20 +441,23 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 3: M3_M4(false); break; // M3: Turn ON Laser | Spindle (clockwise), set Power | Speed case 4: M3_M4(true ); break; // M4: Turn ON Laser | Spindle (counter-clockwise), set Power | Speed case 5: M5(); break; // M5: Turn OFF Laser | Spindle - #if ENABLED(AIR_EVACUATION) - case 10: M10(); break; // M10: Vacuum or Blower motor ON - case 11: M11(); break; // M11: Vacuum or Blower motor OFF - #endif #endif - #if ENABLED(COOLANT_CONTROL) - #if ENABLED(COOLANT_MIST) - case 7: M7(); break; // M7: Mist coolant ON - #endif - #if ENABLED(COOLANT_FLOOD) - case 8: M8(); break; // M8: Flood coolant ON - #endif - case 9: M9(); break; // M9: Coolant OFF + #if ENABLED(COOLANT_MIST) + case 7: M7(); break; // M7: Coolant Mist ON + #endif + + #if EITHER(AIR_ASSIST, COOLANT_FLOOD) + case 8: M8(); break; // M8: Air Assist / Coolant Flood ON + #endif + + #if EITHER(AIR_ASSIST, COOLANT_CONTROL) + case 9: M9(); break; // M9: Air Assist / Coolant OFF + #endif + + #if ENABLED(AIR_EVACUATION) + case 10: M10(); break; // M10: Vacuum or Blower motor ON + case 11: M11(); break; // M11: Vacuum or Blower motor OFF #endif #if ENABLED(EXTERNAL_CLOSED_LOOP_CONTROLLER) @@ -605,7 +613,9 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 92: M92(); break; // M92: Set the steps-per-unit for one or more axes case 114: M114(); break; // M114: Report current position case 115: M115(); break; // M115: Report capabilities - case 117: M117(); break; // M117: Set LCD message text, if possible + + case 117: TERN_(HAS_STATUS_MESSAGE, M117()); break; // M117: Set LCD message text, if possible + case 118: M118(); break; // M118: Display a message in the host console case 119: M119(); break; // M119: Report endstop states case 120: M120(); break; // M120: Enable endstops diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 6f8568730b495..752a3da9dc63b 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -314,7 +314,12 @@ #define HAS_FAST_MOVES 1 #endif -enum AxisRelative : uint8_t { REL_X, REL_Y, REL_Z, REL_E, E_MODE_ABS, E_MODE_REL }; +enum AxisRelative : uint8_t { + LOGICAL_AXIS_LIST(REL_E, REL_X, REL_Y, REL_Z, REL_I, REL_J, REL_K) + #if HAS_EXTRUDERS + , E_MODE_ABS, E_MODE_REL + #endif +}; extern const char G28_STR[]; @@ -324,23 +329,31 @@ class GcodeSuite { static uint8_t axis_relative; static inline bool axis_is_relative(const AxisEnum a) { - if (a == E_AXIS) { - if (TEST(axis_relative, E_MODE_REL)) return true; - if (TEST(axis_relative, E_MODE_ABS)) return false; - } + #if HAS_EXTRUDERS + if (a == E_AXIS) { + if (TEST(axis_relative, E_MODE_REL)) return true; + if (TEST(axis_relative, E_MODE_ABS)) return false; + } + #endif return TEST(axis_relative, a); } static inline void set_relative_mode(const bool rel) { - axis_relative = rel ? _BV(REL_X) | _BV(REL_Y) | _BV(REL_Z) | _BV(REL_E) : 0; - } - static inline void set_e_relative() { - CBI(axis_relative, E_MODE_ABS); - SBI(axis_relative, E_MODE_REL); - } - static inline void set_e_absolute() { - CBI(axis_relative, E_MODE_REL); - SBI(axis_relative, E_MODE_ABS); + axis_relative = rel ? (0 LOGICAL_AXIS_GANG( + | _BV(REL_E), + | _BV(REL_X), | _BV(REL_Y), | _BV(REL_Z), + | _BV(REL_I), | _BV(REL_J), | _BV(REL_K) + )) : 0; } + #if HAS_EXTRUDERS + static inline void set_e_relative() { + CBI(axis_relative, E_MODE_ABS); + SBI(axis_relative, E_MODE_REL); + } + static inline void set_e_absolute() { + CBI(axis_relative, E_MODE_REL); + SBI(axis_relative, E_MODE_ABS); + } + #endif #if ENABLED(CNC_WORKSPACE_PLANES) /** @@ -379,7 +392,7 @@ class GcodeSuite { static void process_subcommands_now(char * gcode); static inline void home_all_axes(const bool keep_leveling=false) { - process_subcommands_now_P(keep_leveling ? G28_STR : TERN(G28_L0_ENSURES_LEVELING_OFF, PSTR("G28L0"), G28_STR)); + process_subcommands_now_P(keep_leveling ? G28_STR : TERN(CAN_SET_LEVELING_AFTER_G28, PSTR("G28L0"), G28_STR)); } #if EITHER(HAS_AUTO_REPORTING, HOST_KEEPALIVE_FEATURE) @@ -551,22 +564,25 @@ class GcodeSuite { #if HAS_CUTTER static void M3_M4(const bool is_M4); static void M5(); - #if ENABLED(AIR_EVACUATION) - static void M10(); - static void M11(); - #endif #endif - #if ENABLED(COOLANT_CONTROL) - #if ENABLED(COOLANT_MIST) - static void M7(); - #endif - #if ENABLED(COOLANT_FLOOD) - static void M8(); - #endif + #if ENABLED(COOLANT_MIST) + static void M7(); + #endif + + #if EITHER(AIR_ASSIST, COOLANT_FLOOD) + static void M8(); + #endif + + #if EITHER(AIR_ASSIST, COOLANT_CONTROL) static void M9(); #endif + #if ENABLED(AIR_EVACUATION) + static void M10(); + static void M11(); + #endif + #if ENABLED(EXTERNAL_CLOSED_LOOP_CONTROLLER) static void M12(); #endif @@ -678,7 +694,11 @@ class GcodeSuite { static void M114(); static void M115(); - static void M117(); + + #if HAS_STATUS_MESSAGE + static void M117(); + #endif + static void M118(); static void M119(); static void M120(); diff --git a/Marlin/src/gcode/geometry/G92.cpp b/Marlin/src/gcode/geometry/G92.cpp index a9970b1e9c09a..990236c0e878a 100644 --- a/Marlin/src/gcode/geometry/G92.cpp +++ b/Marlin/src/gcode/geometry/G92.cpp @@ -48,7 +48,10 @@ */ void GcodeSuite::G92() { - bool sync_E = false, sync_XYZE = false; + #if HAS_EXTRUDERS + bool sync_E = false; + #endif + bool sync_XYZE = false; #if USE_GCODE_SUBCODES const uint8_t subcode_G92 = parser.subcode; @@ -72,7 +75,11 @@ void GcodeSuite::G92() { case 9: // G92.9 - Set Current Position directly (like Marlin 1.0) LOOP_LOGICAL_AXES(i) { if (parser.seenval(axis_codes[i])) { - if (i == E_AXIS) sync_E = true; else sync_XYZE = true; + if (TERN1(HAS_EXTRUDERS, i != E_AXIS)) + sync_XYZE = true; + else { + TERN_(HAS_EXTRUDERS, sync_E = true); + } current_position[i] = parser.value_axis_units((AxisEnum)i); } } @@ -83,20 +90,26 @@ void GcodeSuite::G92() { LOOP_LOGICAL_AXES(i) { if (parser.seenval(axis_codes[i])) { const float l = parser.value_axis_units((AxisEnum)i), // Given axis coordinate value, converted to millimeters - v = i == E_AXIS ? l : LOGICAL_TO_NATIVE(l, i), // Axis position in NATIVE space (applying the existing offset) + v = TERN0(HAS_EXTRUDERS, i == E_AXIS) ? l : LOGICAL_TO_NATIVE(l, i), // Axis position in NATIVE space (applying the existing offset) d = v - current_position[i]; // How much is the current axis position altered by? if (!NEAR_ZERO(d)) { #if HAS_POSITION_SHIFT && !IS_SCARA // When using workspaces... - if (i == E_AXIS) { - sync_E = true; - current_position.e = v; // ...E is still set directly + if (TERN1(HAS_EXTRUDERS, i != E_AXIS)) { + position_shift[i] += d; // ...most axes offset the workspace... + update_workspace_offset((AxisEnum)i); } else { - position_shift[i] += d; // ...but other axes offset the workspace. - update_workspace_offset((AxisEnum)i); + #if HAS_EXTRUDERS + sync_E = true; + current_position.e = v; // ...but E is set directly + #endif } #else // Without workspaces... - if (i == E_AXIS) sync_E = true; else sync_XYZE = true; + if (TERN1(HAS_EXTRUDERS, i != E_AXIS)) + sync_XYZE = true; + else { + TERN_(HAS_EXTRUDERS, sync_E = true); + } current_position[i] = v; // ...set Current Position directly (like Marlin 1.0) #endif } @@ -111,8 +124,10 @@ void GcodeSuite::G92() { coordinate_system[active_coordinate_system] = position_shift; #endif - if (sync_XYZE) sync_plan_position(); - else if (sync_E) sync_plan_position_e(); + if (sync_XYZE) sync_plan_position(); + #if HAS_EXTRUDERS + else if (sync_E) sync_plan_position_e(); + #endif IF_DISABLED(DIRECT_STEPPING, report_current_position()); } diff --git a/Marlin/src/gcode/geometry/M206_M428.cpp b/Marlin/src/gcode/geometry/M206_M428.cpp index e65540eb8c31a..51f3e7c14c049 100644 --- a/Marlin/src/gcode/geometry/M206_M428.cpp +++ b/Marlin/src/gcode/geometry/M206_M428.cpp @@ -31,7 +31,16 @@ #include "../../MarlinCore.h" void M206_report() { - SERIAL_ECHOLNPAIR_P(PSTR("M206 X"), home_offset.x, SP_Y_STR, home_offset.y, SP_Z_STR, home_offset.z); + SERIAL_ECHOLNPAIR_P( + LIST_N(DOUBLE(LINEAR_AXES), + PSTR("M206 X"), home_offset.x, + SP_Y_STR, home_offset.y, + SP_Z_STR, home_offset.z, + SP_I_STR, home_offset.i, + SP_J_STR, home_offset.j, + SP_K_STR, home_offset.k, + ) + ); } /** @@ -51,7 +60,7 @@ void GcodeSuite::M206() { if (parser.seen('P')) set_home_offset(B_AXIS, parser.value_float()); // Psi #endif - if (!parser.seen("XYZ")) + if (!parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z", "I", "J", "K"))) M206_report(); else report_current_position(); diff --git a/Marlin/src/gcode/host/M114.cpp b/Marlin/src/gcode/host/M114.cpp index 2d43d33aa122b..7d69033319b73 100644 --- a/Marlin/src/gcode/host/M114.cpp +++ b/Marlin/src/gcode/host/M114.cpp @@ -125,6 +125,15 @@ #if AXIS_IS_L64XX(Z4) REPORT_ABSOLUTE_POS(Z4); #endif + #if AXIS_IS_L64XX(I) + REPORT_ABSOLUTE_POS(I); + #endif + #if AXIS_IS_L64XX(J) + REPORT_ABSOLUTE_POS(J); + #endif + #if AXIS_IS_L64XX(K) + REPORT_ABSOLUTE_POS(K); + #endif #if AXIS_IS_L64XX(E0) REPORT_ABSOLUTE_POS(E0); #endif @@ -170,7 +179,13 @@ SERIAL_ECHOPGM("FromStp:"); 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) }; + xyze_pos_t from_steppers = LOGICAL_AXIS_ARRAY( + planner.get_axis_position_mm(E_AXIS), + cartes.x, cartes.y, cartes.z, + planner.get_axis_position_mm(I_AXIS), + planner.get_axis_position_mm(J_AXIS), + planner.get_axis_position_mm(K_AXIS) + ); report_all_axis_pos(from_steppers); const xyze_float_t diff = from_steppers - leveled; @@ -201,10 +216,12 @@ void GcodeSuite::M114() { report_current_position_detail(); return; } - if (parser.seen_test('E')) { - SERIAL_ECHOLNPAIR("Count E:", stepper.position(E_AXIS)); - return; - } + #if HAS_EXTRUDERS + if (parser.seen_test('E')) { + SERIAL_ECHOLNPAIR("Count E:", stepper.position(E_AXIS)); + return; + } + #endif #endif #if ENABLED(M114_REALTIME) diff --git a/Marlin/src/gcode/host/M115.cpp b/Marlin/src/gcode/host/M115.cpp index ef4c8983cdd76..49bb806377a95 100644 --- a/Marlin/src/gcode/host/M115.cpp +++ b/Marlin/src/gcode/host/M115.cpp @@ -119,6 +119,9 @@ void GcodeSuite::M115() { // EMERGENCY_PARSER (M108, M112, M410, M876) cap_line(PSTR("EMERGENCY_PARSER"), ENABLED(EMERGENCY_PARSER)); + // HOST ACTION COMMANDS (paused, resume, resumed, cancel, etc.) + cap_line(PSTR("HOST_ACTION_COMMANDS"), ENABLED(HOST_ACTION_COMMANDS)); + // PROMPT SUPPORT (M876) cap_line(PSTR("PROMPT_SUPPORT"), ENABLED(HOST_PROMPT_SUPPORT)); diff --git a/Marlin/src/gcode/lcd/M117.cpp b/Marlin/src/gcode/lcd/M117.cpp index 59305d94c5b53..f26694bd64631 100644 --- a/Marlin/src/gcode/lcd/M117.cpp +++ b/Marlin/src/gcode/lcd/M117.cpp @@ -20,6 +20,10 @@ * */ +#include "../../inc/MarlinConfig.h" + +#if HAS_STATUS_MESSAGE + #include "../gcode.h" #include "../../lcd/marlinui.h" @@ -34,3 +38,5 @@ void GcodeSuite::M117() { ui.reset_status(); } + +#endif // HAS_STATUS_MESSAGE diff --git a/Marlin/src/gcode/motion/G0_G1.cpp b/Marlin/src/gcode/motion/G0_G1.cpp index 73c5b11714225..eb79180c69887 100644 --- a/Marlin/src/gcode/motion/G0_G1.cpp +++ b/Marlin/src/gcode/motion/G0_G1.cpp @@ -49,9 +49,14 @@ void GcodeSuite::G0_G1(TERN_(HAS_FAST_MOVES, const bool fast_move/*=false*/)) { if (IsRunning() #if ENABLED(NO_MOTION_BEFORE_HOMING) && !homing_needed_error( - (parser.seen_test('X') ? _BV(X_AXIS) : 0) - | (parser.seen_test('Y') ? _BV(Y_AXIS) : 0) - | (parser.seen_test('Z') ? _BV(Z_AXIS) : 0) ) + LINEAR_AXIS_GANG( + (parser.seen_test('X') ? _BV(X_AXIS) : 0), + | (parser.seen_test('Y') ? _BV(Y_AXIS) : 0), + | (parser.seen_test('Z') ? _BV(Z_AXIS) : 0), + | (parser.seen_test(AXIS4_NAME) ? _BV(I_AXIS) : 0), + | (parser.seen_test(AXIS5_NAME) ? _BV(J_AXIS) : 0), + | (parser.seen_test(AXIS6_NAME) ? _BV(K_AXIS) : 0)) + ) #endif ) { TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_RUNNING)); @@ -83,7 +88,9 @@ void GcodeSuite::G0_G1(TERN_(HAS_FAST_MOVES, const bool fast_move/*=false*/)) { 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("XYZ")) { + if (fwretract.autoretract_enabled && parser.seen_test('E') + && !parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR)) + ) { 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)) { diff --git a/Marlin/src/gcode/motion/G2_G3.cpp b/Marlin/src/gcode/motion/G2_G3.cpp index 41ff7e9765958..170789d82727e 100644 --- a/Marlin/src/gcode/motion/G2_G3.cpp +++ b/Marlin/src/gcode/motion/G2_G3.cpp @@ -63,7 +63,7 @@ void plan_arc( case GcodeSuite::PLANE_ZX: p_axis = Z_AXIS; q_axis = X_AXIS; l_axis = Y_AXIS; break; } #else - constexpr AxisEnum p_axis = X_AXIS, q_axis = Y_AXIS, l_axis = Z_AXIS; + constexpr AxisEnum p_axis = X_AXIS, q_axis = Y_AXIS OPTARG(HAS_Z_AXIS, l_axis = Z_AXIS); #endif // Radius vector from center to current location @@ -73,8 +73,8 @@ void plan_arc( 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, - start_L = current_position[l_axis]; + rt_Y = cart[q_axis] - center_Q + OPTARG(HAS_Z_AXIS, start_L = current_position[l_axis]); #ifdef MIN_ARC_SEGMENTS uint16_t min_segments = MIN_ARC_SEGMENTS; @@ -109,27 +109,37 @@ void plan_arc( #endif } - float linear_travel = cart[l_axis] - start_L, - extruder_travel = cart.e - current_position.e; + #if HAS_Z_AXIS + float linear_travel = cart[l_axis] - start_L; + #endif + #if HAS_EXTRUDERS + float extruder_travel = cart.e - current_position.e; + #endif // If circling around... if (ENABLED(ARC_P_CIRCLES) && circles) { const float total_angular = angular_travel + circles * RADIANS(360), // Total rotation with all circles and remainder - part_per_circle = RADIANS(360) / total_angular, // Each circle's part of the total - l_per_circle = linear_travel * part_per_circle, // L movement per circle - e_per_circle = extruder_travel * part_per_circle; // E movement per circle + part_per_circle = RADIANS(360) / total_angular; // Each circle's part of the total + + #if HAS_Z_AXIS + const float l_per_circle = linear_travel * part_per_circle; // L movement per circle + #endif + #if HAS_EXTRUDERS + const float e_per_circle = extruder_travel * part_per_circle; // E movement per circle + #endif + xyze_pos_t temp_position = current_position; // for plan_arc to compare to current_position for (uint16_t n = circles; n--;) { - temp_position.e += e_per_circle; // Destination E axis - temp_position[l_axis] += l_per_circle; // Destination L axis + TERN_(HAS_EXTRUDERS, temp_position.e += e_per_circle); // Destination E axis + TERN_(HAS_Z_AXIS, temp_position[l_axis] += l_per_circle); // Destination L axis plan_arc(temp_position, offset, clockwise, 0); // Plan a single whole circle } - linear_travel = cart[l_axis] - current_position[l_axis]; - extruder_travel = cart.e - current_position.e; + TERN_(HAS_Z_AXIS, linear_travel = cart[l_axis] - current_position[l_axis]); + TERN_(HAS_EXTRUDERS, extruder_travel = cart.e - current_position.e); } const float flat_mm = radius * angular_travel, - mm_of_travel = linear_travel ? HYPOT(flat_mm, linear_travel) : ABS(flat_mm); + mm_of_travel = TERN_(HAS_Z_AXIS, linear_travel ? HYPOT(flat_mm, linear_travel) :) ABS(flat_mm); if (mm_of_travel < 0.001f) return; const feedRate_t scaled_fr_mm_s = MMS_SCALED(feedrate_mm_s); @@ -178,17 +188,22 @@ void plan_arc( // Vector rotation matrix values xyze_pos_t raw; const float theta_per_segment = angular_travel / segments, - linear_per_segment = linear_travel / segments, - extruder_per_segment = extruder_travel / segments, sq_theta_per_segment = sq(theta_per_segment), sin_T = theta_per_segment - sq_theta_per_segment * theta_per_segment / 6, cos_T = 1 - 0.5f * sq_theta_per_segment; // Small angle approximation + #if HAS_Z_AXIS && DISABLED(AUTO_BED_LEVELING_UBL) + const float linear_per_segment = linear_travel / segments; + #endif + #if HAS_EXTRUDERS + const float extruder_per_segment = extruder_travel / segments; + #endif + // Initialize the linear axis - raw[l_axis] = current_position[l_axis]; + TERN_(HAS_Z_AXIS, raw[l_axis] = current_position[l_axis]); // Initialize the extruder axis - raw.e = current_position.e; + TERN_(HAS_EXTRUDERS, raw.e = current_position.e); #if ENABLED(SCARA_FEEDRATE_SCALING) const float inv_duration = scaled_fr_mm_s / seg_length; @@ -234,13 +249,11 @@ void plan_arc( // Update raw location 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; + #if HAS_Z_AXIS + raw[l_axis] = TERN(AUTO_BED_LEVELING_UBL, start_L, raw[l_axis] + linear_per_segment); #endif - raw.e += extruder_per_segment; + + TERN_(HAS_EXTRUDERS, raw.e += extruder_per_segment); apply_motion_limits(raw); @@ -249,15 +262,13 @@ void plan_arc( #endif if (!planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, 0 - #if ENABLED(SCARA_FEEDRATE_SCALING) - , inv_duration - #endif + OPTARG(SCARA_FEEDRATE_SCALING, inv_duration) )) break; } // Ensure last segment arrives at target location. raw = cart; - TERN_(AUTO_BED_LEVELING_UBL, raw[l_axis] = start_L); + TERN_(AUTO_BED_LEVELING_UBL, TERN_(HAS_Z_AXIS, raw[l_axis] = start_L)); apply_motion_limits(raw); @@ -266,12 +277,10 @@ void plan_arc( #endif planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, 0 - #if ENABLED(SCARA_FEEDRATE_SCALING) - , inv_duration - #endif + OPTARG(SCARA_FEEDRATE_SCALING, inv_duration) ); - TERN_(AUTO_BED_LEVELING_UBL, raw[l_axis] = start_L); + TERN_(AUTO_BED_LEVELING_UBL, TERN_(HAS_Z_AXIS, raw[l_axis] = start_L)); current_position = raw; } // plan_arc diff --git a/Marlin/src/gcode/motion/M290.cpp b/Marlin/src/gcode/motion/M290.cpp index 0a858090f955d..2b57a6b99a9b6 100644 --- a/Marlin/src/gcode/motion/M290.cpp +++ b/Marlin/src/gcode/motion/M290.cpp @@ -87,7 +87,7 @@ void GcodeSuite::M290() { } #endif - if (!parser.seen("XYZ") || parser.seen('R')) { + if (!parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR)) || parser.seen('R')) { SERIAL_ECHO_START(); #if ENABLED(BABYSTEP_ZPROBE_OFFSET) diff --git a/Marlin/src/gcode/parser.cpp b/Marlin/src/gcode/parser.cpp index 514d6b7a5daff..e4e2973449407 100644 --- a/Marlin/src/gcode/parser.cpp +++ b/Marlin/src/gcode/parser.cpp @@ -248,7 +248,8 @@ void GCodeParser::parse(char *p) { case 'R': if (!WITHIN(motion_mode_codenum, 2, 3)) return; #endif - case 'X' ... 'Z': case 'E' ... 'F': + LOGICAL_AXIS_GANG(case 'E':, case 'X':, case 'Y':, case 'Z':, case AXIS4_NAME:, case AXIS5_NAME:, case AXIS6_NAME:) + case 'F': if (motion_mode_codenum < 0) return; command_letter = 'G'; codenum = motion_mode_codenum; diff --git a/Marlin/src/gcode/parser.h b/Marlin/src/gcode/parser.h index 4270e04c9f093..08cf10004a166 100644 --- a/Marlin/src/gcode/parser.h +++ b/Marlin/src/gcode/parser.h @@ -226,7 +226,7 @@ class GCodeParser { // Seen any axis parameter static inline bool seen_axis() { - return seen("XYZE"); + return seen(LOGICAL_AXIS_GANG("E", "X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR)); } #if ENABLED(GCODE_QUOTED_STRINGS) @@ -311,7 +311,13 @@ class GCodeParser { } static inline float axis_unit_factor(const AxisEnum axis) { - return (axis >= E_AXIS && volumetric_enabled ? volumetric_unit_factor : linear_unit_factor); + return ( + #if HAS_EXTRUDERS + axis >= E_AXIS && volumetric_enabled ? volumetric_unit_factor : linear_unit_factor + #else + linear_unit_factor + #endif + ); } static inline float linear_value_to_mm(const_float_t v) { return v * linear_unit_factor; } diff --git a/Marlin/src/gcode/queue.cpp b/Marlin/src/gcode/queue.cpp index c0075373986f8..09755fbf21a81 100644 --- a/Marlin/src/gcode/queue.cpp +++ b/Marlin/src/gcode/queue.cpp @@ -84,9 +84,7 @@ char GCodeQueue::injected_commands[64]; // = { 0 } void GCodeQueue::RingBuffer::commit_command(bool skip_ok - #if HAS_MULTI_SERIAL - , serial_index_t serial_ind/*=-1*/ - #endif + OPTARG(HAS_MULTI_SERIAL, serial_index_t serial_ind/*=-1*/) ) { commands[index_w].skip_ok = skip_ok; TERN_(HAS_MULTI_SERIAL, commands[index_w].port = serial_ind); @@ -100,9 +98,7 @@ void GCodeQueue::RingBuffer::commit_command(bool skip_ok * Return false for a full buffer, or if the 'command' is a comment. */ bool GCodeQueue::RingBuffer::enqueue(const char *cmd, bool skip_ok/*=true*/ - #if HAS_MULTI_SERIAL - , serial_index_t serial_ind/*=-1*/ - #endif + OPTARG(HAS_MULTI_SERIAL, serial_index_t serial_ind/*=-1*/) ) { if (*cmd == ';' || length >= BUFSIZE) return false; strcpy(commands[index_w].buffer, cmd); diff --git a/Marlin/src/gcode/queue.h b/Marlin/src/gcode/queue.h index 5df4a0104c491..ea99ce7a2d548 100644 --- a/Marlin/src/gcode/queue.h +++ b/Marlin/src/gcode/queue.h @@ -80,15 +80,11 @@ class GCodeQueue { void advance_pos(uint8_t &p, const int inc) { if (++p >= BUFSIZE) p = 0; length += inc; } void commit_command(bool skip_ok - #if HAS_MULTI_SERIAL - , serial_index_t serial_ind = serial_index_t() - #endif + OPTARG(HAS_MULTI_SERIAL, serial_index_t serial_ind = serial_index_t()) ); bool enqueue(const char *cmd, bool skip_ok = true - #if HAS_MULTI_SERIAL - , serial_index_t serial_ind = serial_index_t() - #endif + OPTARG(HAS_MULTI_SERIAL, serial_index_t serial_ind = serial_index_t()) ); void ok_to_send(); diff --git a/Marlin/src/gcode/temp/M104_M109.cpp b/Marlin/src/gcode/temp/M104_M109.cpp index b6a3fa8507164..efda04def50ac 100644 --- a/Marlin/src/gcode/temp/M104_M109.cpp +++ b/Marlin/src/gcode/temp/M104_M109.cpp @@ -125,10 +125,8 @@ void GcodeSuite::M104_M109(const bool isM109) { thermalManager.auto_job_check_timer(isM109, true); #endif - #if HAS_STATUS_MESSAGE - if (thermalManager.isHeatingHotend(target_extruder) || !no_wait_for_cooling) - thermalManager.set_heating_message(target_extruder); - #endif + if (thermalManager.isHeatingHotend(target_extruder) || !no_wait_for_cooling) + thermalManager.set_heating_message(target_extruder); } TERN_(AUTOTEMP, planner.autotemp_M104_M109()); diff --git a/Marlin/src/gcode/temp/M105.cpp b/Marlin/src/gcode/temp/M105.cpp index eefc3ae9f17f7..4de5ba8eefe15 100644 --- a/Marlin/src/gcode/temp/M105.cpp +++ b/Marlin/src/gcode/temp/M105.cpp @@ -35,11 +35,7 @@ void GcodeSuite::M105() { #if HAS_TEMP_SENSOR - thermalManager.print_heater_states(target_extruder - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - , parser.boolval('R') - #endif - ); + thermalManager.print_heater_states(target_extruder OPTARG(HAS_TEMP_REDUNDANT, parser.boolval('R'))); SERIAL_EOL(); diff --git a/Marlin/src/gcode/temp/M106_M107.cpp b/Marlin/src/gcode/temp/M106_M107.cpp index 73dc82b8dfa6a..3f85c53d78ae6 100644 --- a/Marlin/src/gcode/temp/M106_M107.cpp +++ b/Marlin/src/gcode/temp/M106_M107.cpp @@ -60,37 +60,40 @@ */ void GcodeSuite::M106() { const uint8_t pfan = parser.byteval('P', _ALT_P); + if (pfan >= _CNT_P) return; + #if REDUNDANT_PART_COOLING_FAN + if (pfan == REDUNDANT_PART_COOLING_FAN) return; + #endif - if (pfan < _CNT_P) { + #if ENABLED(EXTRA_FAN_SPEED) + const uint16_t t = parser.intval('T'); + if (t > 0) return thermalManager.set_temp_fan_speed(pfan, t); + #endif - #if ENABLED(EXTRA_FAN_SPEED) - const uint16_t t = parser.intval('T'); - if (t > 0) return thermalManager.set_temp_fan_speed(pfan, t); - #endif + const uint16_t dspeed = parser.seen_test('A') ? thermalManager.fan_speed[active_extruder] : 255; - const uint16_t dspeed = parser.seen_test('A') ? thermalManager.fan_speed[active_extruder] : 255; + uint16_t speed = dspeed; - uint16_t speed = dspeed; + // Accept 'I' if temperature presets are defined + #if PREHEAT_COUNT + const bool got_preset = parser.seenval('I'); + if (got_preset) speed = ui.material_preset[_MIN(parser.value_byte(), PREHEAT_COUNT - 1)].fan_speed; + #else + constexpr bool got_preset = false; + #endif - // Accept 'I' if temperature presets are defined - #if PREHEAT_COUNT - const bool got_preset = parser.seenval('I'); - if (got_preset) speed = ui.material_preset[_MIN(parser.value_byte(), PREHEAT_COUNT - 1)].fan_speed; - #else - constexpr bool got_preset = false; - #endif + if (!got_preset && parser.seenval('S')) + speed = parser.value_ushort(); - if (!got_preset && parser.seenval('S')) - speed = parser.value_ushort(); + TERN_(FOAMCUTTER_XYUV, speed *= 2.55); // Get command in % of max heat - // Set speed, with constraint - thermalManager.set_fan_speed(pfan, speed); + // Set speed, with constraint + thermalManager.set_fan_speed(pfan, speed); - TERN_(LASER_SYNCHRONOUS_M106_M107, planner.buffer_sync_block(BLOCK_FLAG_SYNC_FANS)); + TERN_(LASER_SYNCHRONOUS_M106_M107, planner.buffer_sync_block(BLOCK_FLAG_SYNC_FANS)); - if (TERN0(DUAL_X_CARRIAGE, idex_is_duplicating())) // pfan == 0 when duplicating - thermalManager.set_fan_speed(1 - pfan, speed); - } + if (TERN0(DUAL_X_CARRIAGE, idex_is_duplicating())) // pfan == 0 when duplicating + thermalManager.set_fan_speed(1 - pfan, speed); } /** @@ -99,6 +102,9 @@ void GcodeSuite::M106() { void GcodeSuite::M107() { const uint8_t pfan = parser.byteval('P', _ALT_P); if (pfan >= _CNT_P) return; + #if REDUNDANT_PART_COOLING_FAN + if (pfan == REDUNDANT_PART_COOLING_FAN) return; + #endif thermalManager.set_fan_speed(pfan, 0); diff --git a/Marlin/src/gcode/temp/M140_M190.cpp b/Marlin/src/gcode/temp/M140_M190.cpp index ddab003973a0c..857e11dde53f4 100644 --- a/Marlin/src/gcode/temp/M140_M190.cpp +++ b/Marlin/src/gcode/temp/M140_M190.cpp @@ -83,10 +83,11 @@ void GcodeSuite::M140_M190(const bool isM190) { thermalManager.setTargetBed(temp); - TERN_(PRINTJOB_TIMER_AUTOSTART, thermalManager.auto_job_check_timer(true, false)); - ui.set_status_P(thermalManager.isHeatingBed() ? GET_TEXT(MSG_BED_HEATING) : GET_TEXT(MSG_BED_COOLING)); + // with PRINTJOB_TIMER_AUTOSTART, M190 can start the timer, and M140 can stop it + TERN_(PRINTJOB_TIMER_AUTOSTART, thermalManager.auto_job_check_timer(isM190, !isM190)); + if (isM190) thermalManager.wait_for_bed(no_wait_for_cooling); } diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 8001674dc4d5f..833fe0d2277ed 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -405,6 +405,10 @@ #endif +#if EITHER(LCD_I2C_TYPE_MCP23017, LCD_I2C_TYPE_MCP23008) && DISABLED(NO_LCD_DETECT) + #define DETECT_I2C_LCD_DEVICE 1 +#endif + #ifndef STD_ENCODER_PULSES_PER_STEP #if ENABLED(TOUCH_SCREEN) #define STD_ENCODER_PULSES_PER_STEP 2 @@ -517,7 +521,7 @@ #define HAS_PRUSA_MMU2 1 #define HAS_PRUSA_MMU2S 1 #endif - #if MMU_MODEL == EXTENDABLE_EMU_MMU2 || MMU_MODEL == EXTENDABLE_EMU_MMU2S + #if MMU_MODEL >= EXTENDABLE_EMU_MMU2 #define HAS_EXTENDABLE_MMU 1 #endif #endif @@ -537,12 +541,12 @@ * E_STEPPERS - Number of actual E stepper motors * E_MANUAL - Number of E steppers for LCD move options */ - #if EXTRUDERS #define HAS_EXTRUDERS 1 #if EXTRUDERS > 1 #define HAS_MULTI_EXTRUDER 1 #endif + #define E_AXIS_N(E) AxisEnum(E_AXIS + E_INDEX_N(E)) #else #undef EXTRUDERS #define EXTRUDERS 0 @@ -551,9 +555,15 @@ #undef SWITCHING_NOZZLE #undef MIXING_EXTRUDER #undef HOTEND_IDLE_TIMEOUT + #undef DISABLE_E #endif -#if ENABLED(SWITCHING_EXTRUDER) // One stepper for every two EXTRUDERS +#if ENABLED(E_DUAL_STEPPER_DRIVERS) // E0/E1 steppers act in tandem as E0 + + #define E_STEPPERS 2 + +#elif ENABLED(SWITCHING_EXTRUDER) // One stepper for every two EXTRUDERS + #if EXTRUDERS > 4 #define E_STEPPERS 3 #elif EXTRUDERS > 2 @@ -564,17 +574,24 @@ #if DISABLED(SWITCHING_NOZZLE) #define HOTENDS E_STEPPERS #endif -#elif ENABLED(MIXING_EXTRUDER) + +#elif ENABLED(MIXING_EXTRUDER) // Multiple feeds are mixed proportionally + #define E_STEPPERS MIXING_STEPPERS #define E_MANUAL 1 #if MIXING_STEPPERS == 2 #define HAS_DUAL_MIXING 1 #endif -#elif ENABLED(SWITCHING_TOOLHEAD) + +#elif ENABLED(SWITCHING_TOOLHEAD) // Toolchanger + #define E_STEPPERS EXTRUDERS #define E_MANUAL EXTRUDERS -#elif HAS_PRUSA_MMU2 + +#elif HAS_PRUSA_MMU2 // Průša Multi-Material Unit v2 + #define E_STEPPERS 1 + #endif // No inactive extruders with SWITCHING_NOZZLE or Průša MMU1 @@ -604,6 +621,56 @@ #define E_MANUAL EXTRUDERS #endif +/** + * Number of Linear Axes (e.g., XYZ) + * All the logical axes except for the tool (E) axis + */ +#ifndef LINEAR_AXES + #define LINEAR_AXES XYZ +#endif +#if LINEAR_AXES >= XY + #define HAS_Y_AXIS 1 + #if LINEAR_AXES >= XYZ + #define HAS_Z_AXIS 1 + #endif +#endif + +/** + * Number of Logical Axes (e.g., XYZE) + * All the logical axes that can be commanded directly by G-code. + * Delta maps stepper-specific values to ABC steppers. + */ +#if HAS_EXTRUDERS + #define LOGICAL_AXES INCREMENT(LINEAR_AXES) +#else + #define LOGICAL_AXES LINEAR_AXES +#endif + +/** + * DISTINCT_E_FACTORS is set to give extruders (some) individual settings. + * + * DISTINCT_AXES is the number of distinct addressable axes (not steppers). + * Includes all linear axes plus all distinguished extruders. + * The default behavior is to treat all extruders as a single E axis + * with shared motion and temperature settings. + * + * DISTINCT_E is the number of distinguished extruders. By default this + * well be 1 which indicates all extruders share the same settings. + * + * E_INDEX_N(E) should be used to get the E index of any item that might be + * distinguished. + */ +#if ENABLED(DISTINCT_E_FACTORS) && E_STEPPERS > 1 + #define DISTINCT_AXES (LINEAR_AXES + E_STEPPERS) + #define DISTINCT_E E_STEPPERS + #define E_INDEX_N(E) (E) +#else + #undef DISTINCT_E_FACTORS + #define DISTINCT_AXES LOGICAL_AXES + #define DISTINCT_E 1 + #define E_INDEX_N(E) 0 +#endif + #if HOTENDS #define HAS_HOTEND 1 #ifndef HOTEND_OVERSHOOT @@ -624,10 +691,6 @@ #define ARRAY_BY_HOTENDS(V...) ARRAY_N(HOTENDS, V) #define ARRAY_BY_HOTENDS1(v1) ARRAY_N_1(HOTENDS, v1) -#if ENABLED(SWITCHING_EXTRUDER) && (DISABLED(SWITCHING_NOZZLE) || SWITCHING_EXTRUDER_SERVO_NR != SWITCHING_NOZZLE_SERVO_NR) - #define DO_SWITCH_EXTRUDER 1 -#endif - /** * Default hotend offsets, if not defined */ @@ -653,39 +716,10 @@ #undef SINGLENOZZLE_STANDBY_FAN #endif -/** - * Number of Linear Axes (e.g., XYZ) - * All the logical axes except for the tool (E) axis - */ -#ifndef LINEAR_AXES - #define LINEAR_AXES XYZ -#endif - -/** - * Number of Logical Axes (e.g., XYZE) - * All the logical axes that can be commanded directly by G-code. - * Delta maps stepper-specific values to ABC steppers. - */ -#if HAS_EXTRUDERS - #define LOGICAL_AXES INCREMENT(LINEAR_AXES) -#else - #define LOGICAL_AXES LINEAR_AXES -#endif - -/** - * DISTINCT_E_FACTORS affects whether Extruders use different settings - */ -#if ENABLED(DISTINCT_E_FACTORS) && E_STEPPERS > 1 - #define DISTINCT_E E_STEPPERS - #define DISTINCT_AXES (LINEAR_AXES + E_STEPPERS) - #define E_INDEX_N(E) (E) -#else - #undef DISTINCT_E_FACTORS - #define DISTINCT_E 1 - #define DISTINCT_AXES LOGICAL_AXES - #define E_INDEX_N(E) 0 +// Switching extruder has its own servo? +#if ENABLED(SWITCHING_EXTRUDER) && (DISABLED(SWITCHING_NOZZLE) || SWITCHING_EXTRUDER_SERVO_NR != SWITCHING_NOZZLE_SERVO_NR) + #define DO_SWITCH_EXTRUDER 1 #endif -#define E_AXIS_N(E) AxisEnum(E_AXIS + E_INDEX_N(E)) /** * The BLTouch Probe emulates a servo probe @@ -695,14 +729,19 @@ #ifndef Z_PROBE_SERVO_NR #define Z_PROBE_SERVO_NR 0 #endif - #undef DEACTIVATE_SERVOS_AFTER_MOVE + #ifdef DEACTIVATE_SERVOS_AFTER_MOVE + #error "BLTOUCH requires DEACTIVATE_SERVOS_AFTER_MOVE to be to disabled. Please update your Configuration.h file." + #endif // Always disable probe pin inverting for BLTouch - #undef Z_MIN_PROBE_ENDSTOP_INVERTING - #define Z_MIN_PROBE_ENDSTOP_INVERTING false + #if Z_MIN_PROBE_ENDSTOP_INVERTING + #error "BLTOUCH requires Z_MIN_PROBE_ENDSTOP_INVERTING set to false. Please update your Configuration.h file." + #endif + #if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) - #undef Z_MIN_ENDSTOP_INVERTING - #define Z_MIN_ENDSTOP_INVERTING false + #if Z_MIN_ENDSTOP_INVERTING + #error "BLTOUCH requires Z_MIN_ENDSTOP_INVERTING set to false. Please update your Configuration.h file." + #endif #endif #endif @@ -726,6 +765,9 @@ #define HAS_BED_PROBE 1 #endif +/** + * Fill in undefined Filament Sensor options + */ #if ENABLED(FILAMENT_RUNOUT_SENSOR) #if NUM_RUNOUT_SENSORS >= 1 #ifndef FIL_RUNOUT1_STATE @@ -833,7 +875,25 @@ #elif Z_HOME_DIR < 0 #define Z_HOME_TO_MIN 1 #endif +#if I_HOME_DIR > 0 + #define I_HOME_TO_MAX 1 +#elif I_HOME_DIR < 0 + #define I_HOME_TO_MIN 1 +#endif +#if J_HOME_DIR > 0 + #define J_HOME_TO_MAX 1 +#elif J_HOME_DIR < 0 + #define J_HOME_TO_MIN 1 +#endif +#if K_HOME_DIR > 0 + #define K_HOME_TO_MAX 1 +#elif K_HOME_DIR < 0 + #define K_HOME_TO_MIN 1 +#endif +/** + * Conditionals based on the type of Bed Probe + */ #if HAS_BED_PROBE #if DISABLED(NOZZLE_AS_PROBE) #define HAS_PROBE_XY_OFFSET 1 @@ -868,7 +928,7 @@ #endif /** - * Set granular options based on the specific type of leveling + * Conditionals based on the type of Bed Leveling */ #if ENABLED(AUTO_BED_LEVELING_UBL) #undef LCD_BED_LEVELING @@ -974,6 +1034,10 @@ #endif #endif +#if DISABLED(DELTA) + #undef DELTA_HOME_TO_SAFE_ZONE +#endif + // This flag indicates some kind of jerk storage is needed #if EITHER(CLASSIC_JERK, IS_KINEMATIC) #define HAS_CLASSIC_JERK 1 @@ -1088,13 +1152,22 @@ #ifndef INVERT_X_DIR #define INVERT_X_DIR false #endif -#ifndef INVERT_Y_DIR +#if HAS_Y_AXIS && !defined(INVERT_Y_DIR) #define INVERT_Y_DIR false #endif -#ifndef INVERT_Z_DIR +#if HAS_Z_AXIS && !defined(INVERT_Z_DIR) #define INVERT_Z_DIR false #endif -#ifndef INVERT_E_DIR +#if LINEAR_AXES >= 4 && !defined(INVERT_I_DIR) + #define INVERT_I_DIR false +#endif +#if LINEAR_AXES >= 5 && !defined(INVERT_J_DIR) + #define INVERT_J_DIR false +#endif +#if LINEAR_AXES >= 6 && !defined(INVERT_K_DIR) + #define INVERT_K_DIR false +#endif +#if HAS_EXTRUDERS && !defined(INVERT_E_DIR) #define INVERT_E_DIR false #endif @@ -1118,29 +1191,38 @@ * - TFT_COLOR * - GRAPHICAL_TFT_UPSCALE */ -#if ENABLED(MKS_TS35_V2_0) // Most common: ST7796 +#if ENABLED(MKS_TS35_V2_0) // ST7796 + #define TFT_DEFAULT_DRIVER ST7796 #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY) #define TFT_RES_480x320 #define TFT_INTERFACE_SPI -#elif ENABLED(MKS_ROBIN_TFT24) // Most common: ST7789 +#elif ENABLED(ANET_ET5_TFT35) // ST7796 + #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY) + #define TFT_RES_480x320 + #define TFT_INTERFACE_FSMC +#elif ENABLED(ANET_ET4_TFT28) // ST7789 #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_Y) #define TFT_RES_320x240 #define TFT_INTERFACE_FSMC -#elif ENABLED(MKS_ROBIN_TFT28) // Most common: ST7789 +#elif ENABLED(MKS_ROBIN_TFT24) // ST7789 #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_Y) #define TFT_RES_320x240 #define TFT_INTERFACE_FSMC -#elif ENABLED(MKS_ROBIN_TFT32) // Most common: ST7789 +#elif ENABLED(MKS_ROBIN_TFT28) // ST7789 #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_Y) #define TFT_RES_320x240 #define TFT_INTERFACE_FSMC -#elif ENABLED(MKS_ROBIN_TFT35) // Most common: ILI9488 +#elif ENABLED(MKS_ROBIN_TFT32) // ST7789 + #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_Y) + #define TFT_RES_320x240 + #define TFT_INTERFACE_FSMC +#elif ENABLED(MKS_ROBIN_TFT35) // ILI9488 #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_X | TFT_INVERT_Y) #define TFT_RES_480x320 #define TFT_INTERFACE_FSMC #elif ENABLED(MKS_ROBIN_TFT43) - #define TFT_DEFAULT_ORIENTATION 0 #define TFT_DRIVER SSD1963 + #define TFT_DEFAULT_ORIENTATION 0 #define TFT_RES_480x272 #define TFT_INTERFACE_FSMC #elif ENABLED(MKS_ROBIN_TFT_V1_1R) // ILI9328 or R61505 @@ -1148,22 +1230,14 @@ #define TFT_RES_320x240 #define TFT_INTERFACE_FSMC #elif EITHER(TFT_TRONXY_X5SA, ANYCUBIC_TFT35) // ILI9488 - #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_X | TFT_INVERT_Y) #define TFT_DRIVER ILI9488 + #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_X | TFT_INVERT_Y) #define TFT_RES_480x320 #define TFT_INTERFACE_FSMC #elif ENABLED(LONGER_LK_TFT28) #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_X | TFT_INVERT_Y) #define TFT_RES_320x240 #define TFT_INTERFACE_FSMC -#elif ENABLED(ANET_ET4_TFT28) // ST7789 - #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_Y) - #define TFT_RES_320x240 - #define TFT_INTERFACE_FSMC -#elif ENABLED(ANET_ET5_TFT35) // ST7796 - #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY) - #define TFT_RES_480x320 - #define TFT_INTERFACE_FSMC #elif ENABLED(BIQU_BX_TFT70) // RGB #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY) #define TFT_RES_1024x600 @@ -1303,3 +1377,10 @@ #else #define COORDINATE_OKAY(N,L,H) true #endif + +/** + * LED Backlight INDEX END + */ +#if defined(NEOPIXEL_BKGD_INDEX_FIRST) && !defined(NEOPIXEL_BKGD_INDEX_LAST) + #define NEOPIXEL_BKGD_INDEX_LAST NEOPIXEL_BKGD_INDEX_FIRST +#endif diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 1d3253b1ccb28..f88d28e1a1086 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -26,6 +26,10 @@ * Defines that depend on advanced configuration. */ +#ifndef AXIS_RELATIVE_MODES + #define AXIS_RELATIVE_MODES {} +#endif + #ifdef SWITCHING_NOZZLE_E1_SERVO_NR #define SWITCHING_NOZZLE_TWO_SERVOS 1 #endif @@ -103,6 +107,9 @@ #undef THERMAL_PROTECTION_PERIOD #undef WATCH_TEMP_PERIOD #undef SHOW_TEMP_ADC_VALUES + #undef LCD_SHOW_E_TOTAL + #undef MANUAL_E_MOVES_RELATIVE + #undef STEALTHCHOP_E #endif #if TEMP_SENSOR_BED == 0 @@ -482,6 +489,37 @@ #endif #endif +// Remove unused STEALTHCHOP flags +#if LINEAR_AXES < 6 + #undef STEALTHCHOP_K + #undef CALIBRATION_MEASURE_KMIN + #undef CALIBRATION_MEASURE_KMAX + #if LINEAR_AXES < 5 + #undef STEALTHCHOP_J + #undef CALIBRATION_MEASURE_JMIN + #undef CALIBRATION_MEASURE_JMAX + #if LINEAR_AXES < 4 + #undef STEALTHCHOP_I + #undef CALIBRATION_MEASURE_IMIN + #undef CALIBRATION_MEASURE_IMAX + #if LINEAR_AXES < 3 + #undef Z_IDLE_HEIGHT + #undef STEALTHCHOP_Z + #undef Z_PROBE_SLED + #undef Z_SAFE_HOMING + #undef HOME_Z_FIRST + #undef HOMING_Z_WITH_PROBE + #undef ENABLE_LEVELING_FADE_HEIGHT + #undef NUM_Z_STEPPER_DRIVERS + #undef CNC_WORKSPACE_PLANES + #if LINEAR_AXES < 2 + #undef STEALTHCHOP_Y + #endif + #endif + #endif + #endif +#endif + // // SD Card connection methods // Defined here so pins and sanity checks can use them diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index d86b02bdc2332..45271bca72ac0 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -78,17 +78,49 @@ /** * Axis lengths and center */ +#ifndef AXIS4_NAME + #define AXIS4_NAME 'A' +#endif +#ifndef AXIS5_NAME + #define AXIS5_NAME 'B' +#endif +#ifndef AXIS6_NAME + #define AXIS6_NAME 'C' +#endif + #define X_MAX_LENGTH (X_MAX_POS - (X_MIN_POS)) -#define Y_MAX_LENGTH (Y_MAX_POS - (Y_MIN_POS)) -#define Z_MAX_LENGTH (Z_MAX_POS - (Z_MIN_POS)) +#if HAS_Y_AXIS + #define Y_MAX_LENGTH (Y_MAX_POS - (Y_MIN_POS)) +#endif +#if HAS_Z_AXIS + #define Z_MAX_LENGTH (Z_MAX_POS - (Z_MIN_POS)) +#endif +#if LINEAR_AXES >= 4 + #define I_MAX_LENGTH (I_MAX_POS - (I_MIN_POS)) +#endif +#if LINEAR_AXES >= 5 + #define J_MAX_LENGTH (J_MAX_POS - (J_MIN_POS)) +#endif +#if LINEAR_AXES >= 6 + #define K_MAX_LENGTH (K_MAX_POS - (K_MIN_POS)) +#endif // Defined only if the sanity-check is bypassed #ifndef X_BED_SIZE #define X_BED_SIZE X_MAX_LENGTH #endif -#ifndef Y_BED_SIZE +#if HAS_Y_AXIS && !defined(Y_BED_SIZE) #define Y_BED_SIZE Y_MAX_LENGTH #endif +#if LINEAR_AXES >= 4 && !defined(I_BED_SIZE) + #define I_BED_SIZE I_MAX_LENGTH +#endif +#if LINEAR_AXES >= 5 && !defined(J_BED_SIZE) + #define J_BED_SIZE J_MAX_LENGTH +#endif +#if LINEAR_AXES >= 6 && !defined(K_BED_SIZE) + #define K_BED_SIZE K_MAX_LENGTH +#endif // Require 0,0 bed center for Delta and SCARA #if IS_KINEMATIC @@ -97,16 +129,53 @@ // Define center values for future use #define _X_HALF_BED ((X_BED_SIZE) / 2) -#define _Y_HALF_BED ((Y_BED_SIZE) / 2) +#if HAS_Y_AXIS + #define _Y_HALF_BED ((Y_BED_SIZE) / 2) +#endif +#if LINEAR_AXES >= 4 + #define _I_HALF_IMAX ((I_BED_SIZE) / 2) +#endif +#if LINEAR_AXES >= 5 + #define _J_HALF_JMAX ((J_BED_SIZE) / 2) +#endif +#if LINEAR_AXES >= 6 + #define _K_HALF_KMAX ((K_BED_SIZE) / 2) +#endif + #define X_CENTER TERN(BED_CENTER_AT_0_0, 0, _X_HALF_BED) -#define Y_CENTER TERN(BED_CENTER_AT_0_0, 0, _Y_HALF_BED) -#define XY_CENTER { X_CENTER, Y_CENTER } +#if HAS_Y_AXIS + #define Y_CENTER TERN(BED_CENTER_AT_0_0, 0, _Y_HALF_BED) + #define XY_CENTER { X_CENTER, Y_CENTER } +#endif +#if LINEAR_AXES >= 4 + #define I_CENTER TERN(BED_CENTER_AT_0_0, 0, _I_HALF_BED) +#endif +#if LINEAR_AXES >= 5 + #define J_CENTER TERN(BED_CENTER_AT_0_0, 0, _J_HALF_BED) +#endif +#if LINEAR_AXES >= 6 + #define K_CENTER TERN(BED_CENTER_AT_0_0, 0, _K_HALF_BED) +#endif // Get the linear boundaries of the bed #define X_MIN_BED (X_CENTER - _X_HALF_BED) #define X_MAX_BED (X_MIN_BED + X_BED_SIZE) -#define Y_MIN_BED (Y_CENTER - _Y_HALF_BED) -#define Y_MAX_BED (Y_MIN_BED + Y_BED_SIZE) +#if HAS_Y_AXIS + #define Y_MIN_BED (Y_CENTER - _Y_HALF_BED) + #define Y_MAX_BED (Y_MIN_BED + Y_BED_SIZE) +#endif +#if LINEAR_AXES >= 4 + #define I_MINIM (I_CENTER - _I_HALF_BED_SIZE) + #define I_MAXIM (I_MINIM + I_BED_SIZE) +#endif +#if LINEAR_AXES >= 5 + #define J_MINIM (J_CENTER - _J_HALF_BED_SIZE) + #define J_MAXIM (J_MINIM + J_BED_SIZE) +#endif +#if LINEAR_AXES >= 6 + #define K_MINIM (K_CENTER - _K_HALF_BED_SIZE) + #define K_MAXIM (K_MINIM + K_BED_SIZE) +#endif /** * Dual X Carriage @@ -163,14 +232,16 @@ #endif #endif -#ifdef MANUAL_Y_HOME_POS - #define Y_HOME_POS MANUAL_Y_HOME_POS -#else - #define Y_END_POS TERN(Y_HOME_TO_MIN, Y_MIN_POS, Y_MAX_POS) - #if ENABLED(BED_CENTER_AT_0_0) - #define Y_HOME_POS TERN(DELTA, 0, Y_END_POS) +#if HAS_Y_AXIS + #ifdef MANUAL_Y_HOME_POS + #define Y_HOME_POS MANUAL_Y_HOME_POS #else - #define Y_HOME_POS TERN(DELTA, Y_MIN_POS + (Y_BED_SIZE) * 0.5, Y_END_POS) + #define Y_END_POS TERN(Y_HOME_TO_MIN, Y_MIN_POS, Y_MAX_POS) + #if ENABLED(BED_CENTER_AT_0_0) + #define Y_HOME_POS TERN(DELTA, 0, Y_END_POS) + #else + #define Y_HOME_POS TERN(DELTA, Y_MIN_POS + (Y_BED_SIZE) * 0.5, Y_END_POS) + #endif #endif #endif @@ -180,6 +251,28 @@ #define Z_HOME_POS TERN(Z_HOME_TO_MIN, Z_MIN_POS, Z_MAX_POS) #endif +#if LINEAR_AXES >= 4 + #ifdef MANUAL_I_HOME_POS + #define I_HOME_POS MANUAL_I_HOME_POS + #else + #define I_HOME_POS TERN(I_HOME_TO_MIN, I_MIN_POS, I_MAX_POS) + #endif +#endif +#if LINEAR_AXES >= 5 + #ifdef MANUAL_J_HOME_POS + #define J_HOME_POS MANUAL_J_HOME_POS + #else + #define J_HOME_POS TERN(J_HOME_TO_MIN, J_MIN_POS, J_MAX_POS) + #endif +#endif +#if LINEAR_AXES >= 6 + #ifdef MANUAL_K_HOME_POS + #define K_HOME_POS MANUAL_K_HOME_POS + #else + #define K_HOME_POS TERN(K_HOME_TO_MIN, K_MIN_POS, K_MAX_POS) + #endif +#endif + /** * If DELTA_HEIGHT isn't defined use the old setting */ @@ -374,15 +467,24 @@ #ifndef DISABLE_INACTIVE_X #define DISABLE_INACTIVE_X DISABLE_X #endif -#ifndef DISABLE_INACTIVE_Y +#if HAS_Y_AXIS && !defined(DISABLE_INACTIVE_Y) #define DISABLE_INACTIVE_Y DISABLE_Y #endif -#ifndef DISABLE_INACTIVE_Z +#if HAS_Z_AXIS && !defined(DISABLE_INACTIVE_Z) #define DISABLE_INACTIVE_Z DISABLE_Z #endif #ifndef DISABLE_INACTIVE_E #define DISABLE_INACTIVE_E DISABLE_E #endif +#if LINEAR_AXES >= 4 && !defined(DISABLE_INACTIVE_I) + #define DISABLE_INACTIVE_I DISABLE_I +#endif +#if LINEAR_AXES >= 5 && !defined(DISABLE_INACTIVE_J) + #define DISABLE_INACTIVE_J DISABLE_J +#endif +#if LINEAR_AXES >= 6 && !defined(DISABLE_INACTIVE_K) + #define DISABLE_INACTIVE_K DISABLE_K +#endif /** * Power Supply @@ -410,11 +512,106 @@ * Temp Sensor defines */ -#define ANY_TEMP_SENSOR_IS(n) (TEMP_SENSOR_0 == (n) || TEMP_SENSOR_1 == (n) || TEMP_SENSOR_2 == (n) || TEMP_SENSOR_3 == (n) || TEMP_SENSOR_4 == (n) || TEMP_SENSOR_5 == (n) || TEMP_SENSOR_6 == (n) || TEMP_SENSOR_7 == (n) || TEMP_SENSOR_BED == (n) || TEMP_SENSOR_PROBE == (n) || TEMP_SENSOR_CHAMBER == (n) || TEMP_SENSOR_COOLER == (n)) - +#define ANY_TEMP_SENSOR_IS(n) ( \ + n == TEMP_SENSOR_0 || n == TEMP_SENSOR_1 || n == TEMP_SENSOR_2 || n == TEMP_SENSOR_3 \ + || n == TEMP_SENSOR_4 || n == TEMP_SENSOR_5 || n == TEMP_SENSOR_6 || n == TEMP_SENSOR_7 \ + || n == TEMP_SENSOR_BED \ + || n == TEMP_SENSOR_PROBE \ + || n == TEMP_SENSOR_CHAMBER \ + || n == TEMP_SENSOR_COOLER \ + || n == TEMP_SENSOR_REDUNDANT ) #if ANY_TEMP_SENSOR_IS(1000) #define HAS_USER_THERMISTORS 1 #endif +#undef ANY_TEMP_SENSOR_IS + +// Usurp a sensor to do redundant readings +#if TEMP_SENSOR_REDUNDANT + #ifndef TEMP_SENSOR_REDUNDANT_SOURCE + #define TEMP_SENSOR_REDUNDANT_SOURCE 1 + #endif + #ifndef TEMP_SENSOR_REDUNDANT_TARGET + #define TEMP_SENSOR_REDUNDANT_TARGET 0 + #endif + #if !PIN_EXISTS(TEMP_REDUNDANT) + #ifndef TEMP_SENSOR_REDUNDANT_MAX_DIFF + #define TEMP_SENSOR_REDUNDANT_MAX_DIFF 10 + #endif + #if TEMP_SENSOR_REDUNDANT_SOURCE == -5 + #if !PIN_EXISTS(TEMP_COOLER) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to COOLER requires TEMP_COOLER_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_COOLER_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == -4 + #if !PIN_EXISTS(TEMP_PROBE) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to PROBE requires TEMP_PROBE_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_PROBE_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == -2 + #if !PIN_EXISTS(TEMP_CHAMBER) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to CHAMBER requires TEMP_CHAMBER_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_CHAMBER_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == -1 + #if !PIN_EXISTS(TEMP_BED) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to BED requires TEMP_BED_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_BED_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 0 + #if !PIN_EXISTS(TEMP_0) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 0 requires TEMP_0_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_0_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 1 + #if !PIN_EXISTS(TEMP_1) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 1 requires TEMP_1_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_1_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 2 + #if !PIN_EXISTS(TEMP_2) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 2 requires TEMP_2_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_2_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 3 + #if !PIN_EXISTS(TEMP_3) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 3 requires TEMP_3_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_3_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 4 + #if !PIN_EXISTS(TEMP_4) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 4 requires TEMP_4_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_4_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 5 + #if !PIN_EXISTS(TEMP_5) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 5 requires TEMP_5_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_5_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 6 + #if !PIN_EXISTS(TEMP_6) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 6 requires TEMP_6_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_6_PIN + #endif + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 7 + #if !PIN_EXISTS(TEMP_7) + #error "TEMP_SENSOR_REDUNDANT_SOURCE set to 7 requires TEMP_7_PIN." + #else + #define TEMP_REDUNDANT_PIN TEMP_7_PIN + #endif + #endif + #endif +#endif #if TEMP_SENSOR_0 == -5 || TEMP_SENSOR_0 == -3 || TEMP_SENSOR_0 == -2 #define TEMP_SENSOR_0_IS_MAX_TC 1 @@ -438,7 +635,6 @@ #elif TEMP_SENSOR_0 == -1 #define TEMP_SENSOR_0_IS_AD595 1 #elif TEMP_SENSOR_0 > 0 - #define TEMP_SENSOR_0_THERMISTOR_ID TEMP_SENSOR_0 #define TEMP_SENSOR_0_IS_THERMISTOR 1 #if TEMP_SENSOR_0 == 1000 #define TEMP_SENSOR_0_IS_CUSTOM 1 @@ -481,7 +677,6 @@ #elif TEMP_SENSOR_1 == -1 #define TEMP_SENSOR_1_IS_AD595 1 #elif TEMP_SENSOR_1 > 0 - #define TEMP_SENSOR_1_THERMISTOR_ID TEMP_SENSOR_1 #define TEMP_SENSOR_1_IS_THERMISTOR 1 #if TEMP_SENSOR_1 == 1000 #define TEMP_SENSOR_1_IS_CUSTOM 1 @@ -493,35 +688,92 @@ #undef HEATER_1_MAXTEMP #endif -#if TEMP_SENSOR_0_IS_MAX31855 || TEMP_SENSOR_1_IS_MAX31855 +#if TEMP_SENSOR_REDUNDANT == -5 || TEMP_SENSOR_REDUNDANT == -3 || TEMP_SENSOR_REDUNDANT == -2 + #define TEMP_SENSOR_REDUNDANT_IS_MAX_TC 1 + #define HAS_MAX_TC 1 + #if TEMP_SENSOR_REDUNDANT == -3 + #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN -270 + #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX 1800 + #else + #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN 0 + #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX 1024 + #endif + #if TEMP_SENSOR_REDUNDANT_SOURCE == 0 + #define TEMP_SENSOR_0_MAX_TC_TMIN TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN + #define TEMP_SENSOR_0_MAX_TC_TMAX TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX + #elif TEMP_SENSOR_REDUNDANT_SOURCE == 1 + #define TEMP_SENSOR_1_MAX_TC_TMIN TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN + #define TEMP_SENSOR_1_MAX_TC_TMAX TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX + #endif + #if TEMP_SENSOR_REDUNDANT == -5 + #if TEMP_SENSOR_REDUNDANT_SOURCE != 0 && TEMP_SENSOR_REDUNDANT_SOURCE != 1 + #error "MAX31865 Thermocouples (-5) not supported for TEMP_SENSOR_REDUNDANT_SOURCE other than TEMP_SENSOR_0/TEMP_SENSOR_1 (0/1)." + #endif + #define TEMP_SENSOR_REDUNDANT_IS_MAX31865 1 + #elif TEMP_SENSOR_REDUNDANT == -3 + #if TEMP_SENSOR_REDUNDANT_SOURCE != 0 && TEMP_SENSOR_REDUNDANT_SOURCE != 1 + #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_REDUNDANT_SOURCE other than TEMP_SENSOR_0/TEMP_SENSOR_1 (0/1)." + #endif + #define TEMP_SENSOR_REDUNDANT_IS_MAX31855 1 + #elif TEMP_SENSOR_REDUNDANT == -2 + #if TEMP_SENSOR_REDUNDANT_SOURCE != 0 && TEMP_SENSOR_REDUNDANT_SOURCE != 1 + #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_REDUNDANT_SOURCE other than TEMP_SENSOR_0/TEMP_SENSOR_1 (0/1)." + #endif + #define TEMP_SENSOR_REDUNDANT_IS_MAX6675 1 + #endif + #if (TEMP_SENSOR_0_IS_MAX_TC && TEMP_SENSOR_REDUNDANT != TEMP_SENSOR_0) || (TEMP_SENSOR_1_IS_MAX_TC && TEMP_SENSOR_REDUNDANT != TEMP_SENSOR_1) + #if TEMP_SENSOR_REDUNDANT == -5 + #error "If MAX31865 Thermocouple (-5) is used for TEMP_SENSOR_0/TEMP_SENSOR_1 then TEMP_SENSOR_REDUNDANT must match." + #elif TEMP_SENSOR_REDUNDANT == -3 + #error "If MAX31855 Thermocouple (-3) is used for TEMP_SENSOR_0/TEMP_SENSOR_1 then TEMP_SENSOR_REDUNDANT must match." + #elif TEMP_SENSOR_REDUNDANT == -2 + #error "If MAX6675 Thermocouple (-2) is used for TEMP_SENSOR_0/TEMP_SENSOR_1 then TEMP_SENSOR_REDUNDANT must match." + #endif + #endif +#elif TEMP_SENSOR_REDUNDANT == -4 + #define TEMP_SENSOR_REDUNDANT_IS_AD8495 1 +#elif TEMP_SENSOR_REDUNDANT == -1 + #define TEMP_SENSOR_REDUNDANT_IS_AD595 1 +#elif TEMP_SENSOR_REDUNDANT > 0 + #define TEMP_SENSOR_REDUNDANT_IS_THERMISTOR 1 + #if TEMP_SENSOR_REDUNDANT == 1000 + #define TEMP_SENSOR_REDUNDANT_IS_CUSTOM 1 + #elif TEMP_SENSOR_REDUNDANT == 998 || TEMP_SENSOR_REDUNDANT == 999 + #error "Dummy sensors are not supported for TEMP_SENSOR_REDUNDANT." + #endif +#endif + +#if TEMP_SENSOR_0_IS_MAX31855 || TEMP_SENSOR_1_IS_MAX31855 || TEMP_SENSOR_REDUNDANT_IS_MAX31855 #define HAS_MAX31855 1 #endif -#if TEMP_SENSOR_0_IS_MAX31865 || TEMP_SENSOR_1_IS_MAX31865 +#if TEMP_SENSOR_0_IS_MAX31865 || TEMP_SENSOR_1_IS_MAX31865 || TEMP_SENSOR_REDUNDANT_IS_MAX31865 #define HAS_MAX31865 1 #endif -#if TEMP_SENSOR_0_IS_MAX6675 || TEMP_SENSOR_1_IS_MAX6675 +#if TEMP_SENSOR_0_IS_MAX6675 || TEMP_SENSOR_1_IS_MAX6675 || TEMP_SENSOR_REDUNDANT_IS_MAX6675 #define HAS_MAX6675 1 #endif // // Compatibility layer for MAX (SPI) temp boards // +#define TEMP_SENSOR_IS_MAX(n, M) (ENABLED(TEMP_SENSOR_##n##_IS_##M) || (ENABLED(TEMP_SENSOR_REDUNDANT_IS_##M) && TEMP_SENSOR_REDUNDANT_SOURCE == (n))) + #if PIN_EXISTS(MAX6675_SS) - #if TEMP_SENSOR_0_IS_MAX31855 + #if TEMP_SENSOR_IS_MAX(0, MAX31855) #define MAX31855_CS_PIN MAX6675_SS_PIN - #elif TEMP_SENSOR_0_IS_MAX31865 + #elif TEMP_SENSOR_IS_MAX(0, MAX31865) #define MAX31865_CS_PIN MAX6675_SS_PIN - #elif TEMP_SENSOR_0_IS_MAX6675 + #elif TEMP_SENSOR_IS_MAX(0, MAX6675) #define MAX6675_CS_PIN MAX6675_SS_PIN #endif #endif #if PIN_EXISTS(MAX6675_SS2) - #if TEMP_SENSOR_1_IS_MAX31855 + #if TEMP_SENSOR_IS_MAX(1, MAX31855) #define MAX31855_CS2_PIN MAX6675_SS2_PIN - #elif TEMP_SENSOR_1_IS_MAX31865 + #elif TEMP_SENSOR_IS_MAX(1, MAX31865) #define MAX31865_CS2_PIN MAX6675_SS2_PIN - #elif TEMP_SENSOR_1_IS_MAX6675 + #elif TEMP_SENSOR_IS_MAX(1, MAX6675) #define MAX6675_CS2_PIN MAX6675_SS2_PIN #endif #endif @@ -596,7 +848,6 @@ #elif TEMP_SENSOR_2 == -1 #define TEMP_SENSOR_2_IS_AD595 1 #elif TEMP_SENSOR_2 > 0 - #define TEMP_SENSOR_2_THERMISTOR_ID TEMP_SENSOR_2 #define TEMP_SENSOR_2_IS_THERMISTOR 1 #if TEMP_SENSOR_2 == 1000 #define TEMP_SENSOR_2_IS_CUSTOM 1 @@ -617,7 +868,6 @@ #elif TEMP_SENSOR_3 == -1 #define TEMP_SENSOR_3_IS_AD595 1 #elif TEMP_SENSOR_3 > 0 - #define TEMP_SENSOR_3_THERMISTOR_ID TEMP_SENSOR_3 #define TEMP_SENSOR_3_IS_THERMISTOR 1 #if TEMP_SENSOR_3 == 1000 #define TEMP_SENSOR_3_IS_CUSTOM 1 @@ -638,7 +888,6 @@ #elif TEMP_SENSOR_4 == -1 #define TEMP_SENSOR_4_IS_AD595 1 #elif TEMP_SENSOR_4 > 0 - #define TEMP_SENSOR_4_THERMISTOR_ID TEMP_SENSOR_4 #define TEMP_SENSOR_4_IS_THERMISTOR 1 #if TEMP_SENSOR_4 == 1000 #define TEMP_SENSOR_4_IS_CUSTOM 1 @@ -659,7 +908,6 @@ #elif TEMP_SENSOR_5 == -1 #define TEMP_SENSOR_5_IS_AD595 1 #elif TEMP_SENSOR_5 > 0 - #define TEMP_SENSOR_5_THERMISTOR_ID TEMP_SENSOR_5 #define TEMP_SENSOR_5_IS_THERMISTOR 1 #if TEMP_SENSOR_5 == 1000 #define TEMP_SENSOR_5_IS_CUSTOM 1 @@ -680,7 +928,6 @@ #elif TEMP_SENSOR_6 == -1 #define TEMP_SENSOR_6_IS_AD595 1 #elif TEMP_SENSOR_6 > 0 - #define TEMP_SENSOR_6_THERMISTOR_ID TEMP_SENSOR_6 #define TEMP_SENSOR_6_IS_THERMISTOR 1 #if TEMP_SENSOR_6 == 1000 #define TEMP_SENSOR_6_IS_CUSTOM 1 @@ -701,7 +948,6 @@ #elif TEMP_SENSOR_7 == -1 #define TEMP_SENSOR_7_IS_AD595 1 #elif TEMP_SENSOR_7 > 0 - #define TEMP_SENSOR_7_THERMISTOR_ID TEMP_SENSOR_7 #define TEMP_SENSOR_7_IS_THERMISTOR 1 #if TEMP_SENSOR_7 == 1000 #define TEMP_SENSOR_7_IS_CUSTOM 1 @@ -722,7 +968,6 @@ #elif TEMP_SENSOR_BED == -1 #define TEMP_SENSOR_BED_IS_AD595 1 #elif TEMP_SENSOR_BED > 0 - #define TEMP_SENSOR_BED_THERMISTOR_ID TEMP_SENSOR_BED #define TEMP_SENSOR_BED_IS_THERMISTOR 1 #if TEMP_SENSOR_BED == 1000 #define TEMP_SENSOR_BED_IS_CUSTOM 1 @@ -743,7 +988,6 @@ #elif TEMP_SENSOR_CHAMBER == -1 #define TEMP_SENSOR_CHAMBER_IS_AD595 1 #elif TEMP_SENSOR_CHAMBER > 0 - #define TEMP_SENSOR_CHAMBER_THERMISTOR_ID TEMP_SENSOR_CHAMBER #define TEMP_SENSOR_CHAMBER_IS_THERMISTOR 1 #if TEMP_SENSOR_CHAMBER == 1000 #define TEMP_SENSOR_CHAMBER_IS_CUSTOM 1 @@ -756,20 +1000,19 @@ #endif #if TEMP_SENSOR_COOLER == -4 - #define COOLER_USES_AD8495 1 + #define TEMP_SENSOR_COOLER_IS_AD8495 1 #elif TEMP_SENSOR_COOLER == -3 #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_COOLER." #elif TEMP_SENSOR_COOLER == -2 #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_COOLER." #elif TEMP_SENSOR_COOLER == -1 - #define COOLER_USES_AD595 1 + #define TEMP_SENSOR_COOLER_IS_AD595 1 #elif TEMP_SENSOR_COOLER > 0 - #define TEMP_SENSOR_COOLER_THERMISTOR_ID TEMP_SENSOR_COOLER #define TEMP_SENSOR_COOLER_IS_THERMISTOR 1 #if TEMP_SENSOR_COOLER == 1000 - #define COOLER_USER_THERMISTOR 1 + #define TEMP_SENSOR_COOLER_IS_CUSTOM 1 #elif TEMP_SENSOR_COOLER == 998 || TEMP_SENSOR_COOLER == 999 - #define COOLER_DUMMY_THERMISTOR 1 + #define TEMP_SENSOR_COOLER_IS_DUMMY 1 #endif #else #undef COOLER_MINTEMP @@ -785,7 +1028,6 @@ #elif TEMP_SENSOR_PROBE == -1 #define TEMP_SENSOR_PROBE_IS_AD595 1 #elif TEMP_SENSOR_PROBE > 0 - #define TEMP_SENSOR_PROBE_THERMISTOR_ID TEMP_SENSOR_PROBE #define TEMP_SENSOR_PROBE_IS_THERMISTOR 1 #if TEMP_SENSOR_PROBE == 1000 #define TEMP_SENSOR_PROBE_IS_CUSTOM 1 @@ -1418,6 +1660,15 @@ #if ENABLED(USE_ZMAX_PLUG) #define ENDSTOPPULLUP_ZMAX #endif + #if ENABLED(USE_IMAX_PLUG) + #define ENDSTOPPULLUP_IMAX + #endif + #if ENABLED(USE_JMAX_PLUG) + #define ENDSTOPPULLUP_JMAX + #endif + #if ENABLED(USE_KMAX_PLUG) + #define ENDSTOPPULLUP_KMAX + #endif #if ENABLED(USE_XMIN_PLUG) #define ENDSTOPPULLUP_XMIN #endif @@ -1427,6 +1678,15 @@ #if ENABLED(USE_ZMIN_PLUG) #define ENDSTOPPULLUP_ZMIN #endif + #if ENABLED(USE_IMIN_PLUG) + #define ENDSTOPPULLUP_IMIN + #endif + #if ENABLED(USE_JMIN_PLUG) + #define ENDSTOPPULLUP_JMIN + #endif + #if ENABLED(USE_KMIN_PLUG) + #define ENDSTOPPULLUP_KMIN + #endif #endif /** @@ -1484,219 +1744,278 @@ #define HAS_X2_MS_PINS 1 #endif -#if PIN_EXISTS(Y_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y)) - #define HAS_Y_ENABLE 1 -#endif -#if PIN_EXISTS(Y_DIR) - #define HAS_Y_DIR 1 -#endif -#if PIN_EXISTS(Y_STEP) - #define HAS_Y_STEP 1 -#endif -#if PIN_EXISTS(Y_MS1) - #define HAS_Y_MS_PINS 1 -#endif +#if HAS_Y_AXIS + #if PIN_EXISTS(Y_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y)) + #define HAS_Y_ENABLE 1 + #endif + #if PIN_EXISTS(Y_DIR) + #define HAS_Y_DIR 1 + #endif + #if PIN_EXISTS(Y_STEP) + #define HAS_Y_STEP 1 + #endif + #if PIN_EXISTS(Y_MS1) + #define HAS_Y_MS_PINS 1 + #endif -#if PIN_EXISTS(Y2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y2)) - #define HAS_Y2_ENABLE 1 -#endif -#if PIN_EXISTS(Y2_DIR) - #define HAS_Y2_DIR 1 -#endif -#if PIN_EXISTS(Y2_STEP) - #define HAS_Y2_STEP 1 -#endif -#if PIN_EXISTS(Y2_MS1) - #define HAS_Y2_MS_PINS 1 + #if PIN_EXISTS(Y2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y2)) + #define HAS_Y2_ENABLE 1 + #endif + #if PIN_EXISTS(Y2_DIR) + #define HAS_Y2_DIR 1 + #endif + #if PIN_EXISTS(Y2_STEP) + #define HAS_Y2_STEP 1 + #endif + #if PIN_EXISTS(Y2_MS1) + #define HAS_Y2_MS_PINS 1 + #endif #endif -#if PIN_EXISTS(Z_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z)) - #define HAS_Z_ENABLE 1 -#endif -#if PIN_EXISTS(Z_DIR) - #define HAS_Z_DIR 1 -#endif -#if PIN_EXISTS(Z_STEP) - #define HAS_Z_STEP 1 -#endif -#if PIN_EXISTS(Z_MS1) - #define HAS_Z_MS_PINS 1 +#if HAS_Z_AXIS + #if PIN_EXISTS(Z_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z)) + #define HAS_Z_ENABLE 1 + #endif + #if PIN_EXISTS(Z_DIR) + #define HAS_Z_DIR 1 + #endif + #if PIN_EXISTS(Z_STEP) + #define HAS_Z_STEP 1 + #endif + #if PIN_EXISTS(Z_MS1) + #define HAS_Z_MS_PINS 1 + #endif #endif -#if PIN_EXISTS(Z2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z2)) - #define HAS_Z2_ENABLE 1 -#endif -#if PIN_EXISTS(Z2_DIR) - #define HAS_Z2_DIR 1 -#endif -#if PIN_EXISTS(Z2_STEP) - #define HAS_Z2_STEP 1 -#endif -#if PIN_EXISTS(Z2_MS1) - #define HAS_Z2_MS_PINS 1 +#if NUM_Z_STEPPER_DRIVERS >= 2 + #if PIN_EXISTS(Z2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z2)) + #define HAS_Z2_ENABLE 1 + #endif + #if PIN_EXISTS(Z2_DIR) + #define HAS_Z2_DIR 1 + #endif + #if PIN_EXISTS(Z2_STEP) + #define HAS_Z2_STEP 1 + #endif + #if PIN_EXISTS(Z2_MS1) + #define HAS_Z2_MS_PINS 1 + #endif #endif -#if PIN_EXISTS(Z3_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z3)) - #define HAS_Z3_ENABLE 1 -#endif -#if PIN_EXISTS(Z3_DIR) - #define HAS_Z3_DIR 1 -#endif -#if PIN_EXISTS(Z3_STEP) - #define HAS_Z3_STEP 1 -#endif -#if PIN_EXISTS(Z3_MS1) - #define HAS_Z3_MS_PINS 1 +#if NUM_Z_STEPPER_DRIVERS >= 3 + #if PIN_EXISTS(Z3_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z3)) + #define HAS_Z3_ENABLE 1 + #endif + #if PIN_EXISTS(Z3_DIR) + #define HAS_Z3_DIR 1 + #endif + #if PIN_EXISTS(Z3_STEP) + #define HAS_Z3_STEP 1 + #endif + #if PIN_EXISTS(Z3_MS1) + #define HAS_Z3_MS_PINS 1 + #endif #endif -#if PIN_EXISTS(Z4_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z4)) - #define HAS_Z4_ENABLE 1 +#if NUM_Z_STEPPER_DRIVERS >= 4 + #if PIN_EXISTS(Z4_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z4)) + #define HAS_Z4_ENABLE 1 + #endif + #if PIN_EXISTS(Z4_DIR) + #define HAS_Z4_DIR 1 + #endif + #if PIN_EXISTS(Z4_STEP) + #define HAS_Z4_STEP 1 + #endif + #if PIN_EXISTS(Z4_MS1) + #define HAS_Z4_MS_PINS 1 + #endif #endif -#if PIN_EXISTS(Z4_DIR) - #define HAS_Z4_DIR 1 + +#if LINEAR_AXES >= 4 + #if PIN_EXISTS(I_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(I)) + #define HAS_I_ENABLE 1 + #endif + #if PIN_EXISTS(I_DIR) + #define HAS_I_DIR 1 + #endif + #if PIN_EXISTS(I_STEP) + #define HAS_I_STEP 1 + #endif + #if PIN_EXISTS(I_MS1) + #define HAS_I_MS_PINS 1 + #endif #endif -#if PIN_EXISTS(Z4_STEP) - #define HAS_Z4_STEP 1 + +#if LINEAR_AXES >= 5 + #if PIN_EXISTS(J_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(J)) + #define HAS_J_ENABLE 1 + #endif + #if PIN_EXISTS(J_DIR) + #define HAS_J_DIR 1 + #endif + #if PIN_EXISTS(J_STEP) + #define HAS_J_STEP 1 + #endif + #if PIN_EXISTS(J_MS1) + #define HAS_J_MS_PINS 1 + #endif #endif -#if PIN_EXISTS(Z4_MS1) - #define HAS_Z4_MS_PINS 1 + +#if LINEAR_AXES >= 6 + #if PIN_EXISTS(K_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(K)) + #define HAS_K_ENABLE 1 + #endif + #if PIN_EXISTS(K_DIR) + #define HAS_K_DIR 1 + #endif + #if PIN_EXISTS(K_STEP) + #define HAS_K_STEP 1 + #endif + #if PIN_EXISTS(K_MS1) + #define HAS_K_MS_PINS 1 + #endif #endif // Extruder steppers and solenoids -#if PIN_EXISTS(E0_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E0)) - #define HAS_E0_ENABLE 1 -#endif -#if PIN_EXISTS(E0_DIR) - #define HAS_E0_DIR 1 -#endif -#if PIN_EXISTS(E0_STEP) - #define HAS_E0_STEP 1 -#endif -#if PIN_EXISTS(E0_MS1) - #define HAS_E0_MS_PINS 1 -#endif -#if PIN_EXISTS(SOL0) - #define HAS_SOLENOID_0 1 -#endif +#if HAS_EXTRUDERS -#if PIN_EXISTS(E1_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E1)) - #define HAS_E1_ENABLE 1 -#endif -#if PIN_EXISTS(E1_DIR) - #define HAS_E1_DIR 1 -#endif -#if PIN_EXISTS(E1_STEP) - #define HAS_E1_STEP 1 -#endif -#if PIN_EXISTS(E1_MS1) - #define HAS_E1_MS_PINS 1 -#endif -#if PIN_EXISTS(SOL1) - #define HAS_SOLENOID_1 1 -#endif + #if PIN_EXISTS(E0_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E0)) + #define HAS_E0_ENABLE 1 + #endif + #if PIN_EXISTS(E0_DIR) + #define HAS_E0_DIR 1 + #endif + #if PIN_EXISTS(E0_STEP) + #define HAS_E0_STEP 1 + #endif + #if PIN_EXISTS(E0_MS1) + #define HAS_E0_MS_PINS 1 + #endif + #if PIN_EXISTS(SOL0) + #define HAS_SOLENOID_0 1 + #endif -#if PIN_EXISTS(E2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E2)) - #define HAS_E2_ENABLE 1 -#endif -#if PIN_EXISTS(E2_DIR) - #define HAS_E2_DIR 1 -#endif -#if PIN_EXISTS(E2_STEP) - #define HAS_E2_STEP 1 -#endif -#if PIN_EXISTS(E2_MS1) - #define HAS_E2_MS_PINS 1 -#endif -#if PIN_EXISTS(SOL2) - #define HAS_SOLENOID_2 1 -#endif + #if PIN_EXISTS(E1_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E1)) + #define HAS_E1_ENABLE 1 + #endif + #if PIN_EXISTS(E1_DIR) + #define HAS_E1_DIR 1 + #endif + #if PIN_EXISTS(E1_STEP) + #define HAS_E1_STEP 1 + #endif + #if PIN_EXISTS(E1_MS1) + #define HAS_E1_MS_PINS 1 + #endif + #if PIN_EXISTS(SOL1) + #define HAS_SOLENOID_1 1 + #endif -#if PIN_EXISTS(E3_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E3)) - #define HAS_E3_ENABLE 1 -#endif -#if PIN_EXISTS(E3_DIR) - #define HAS_E3_DIR 1 -#endif -#if PIN_EXISTS(E3_STEP) - #define HAS_E3_STEP 1 -#endif -#if PIN_EXISTS(E3_MS1) - #define HAS_E3_MS_PINS 1 -#endif -#if PIN_EXISTS(SOL3) - #define HAS_SOLENOID_3 1 -#endif + #if PIN_EXISTS(E2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E2)) + #define HAS_E2_ENABLE 1 + #endif + #if PIN_EXISTS(E2_DIR) + #define HAS_E2_DIR 1 + #endif + #if PIN_EXISTS(E2_STEP) + #define HAS_E2_STEP 1 + #endif + #if PIN_EXISTS(E2_MS1) + #define HAS_E2_MS_PINS 1 + #endif + #if PIN_EXISTS(SOL2) + #define HAS_SOLENOID_2 1 + #endif -#if PIN_EXISTS(E4_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E4)) - #define HAS_E4_ENABLE 1 -#endif -#if PIN_EXISTS(E4_DIR) - #define HAS_E4_DIR 1 -#endif -#if PIN_EXISTS(E4_STEP) - #define HAS_E4_STEP 1 -#endif -#if PIN_EXISTS(E4_MS1) - #define HAS_E4_MS_PINS 1 -#endif -#if PIN_EXISTS(SOL4) - #define HAS_SOLENOID_4 1 -#endif + #if PIN_EXISTS(E3_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E3)) + #define HAS_E3_ENABLE 1 + #endif + #if PIN_EXISTS(E3_DIR) + #define HAS_E3_DIR 1 + #endif + #if PIN_EXISTS(E3_STEP) + #define HAS_E3_STEP 1 + #endif + #if PIN_EXISTS(E3_MS1) + #define HAS_E3_MS_PINS 1 + #endif + #if PIN_EXISTS(SOL3) + #define HAS_SOLENOID_3 1 + #endif -#if PIN_EXISTS(E5_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E5)) - #define HAS_E5_ENABLE 1 -#endif -#if PIN_EXISTS(E5_DIR) - #define HAS_E5_DIR 1 -#endif -#if PIN_EXISTS(E5_STEP) - #define HAS_E5_STEP 1 -#endif -#if PIN_EXISTS(E5_MS1) - #define HAS_E5_MS_PINS 1 -#endif -#if PIN_EXISTS(SOL5) - #define HAS_SOLENOID_5 1 -#endif + #if PIN_EXISTS(E4_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E4)) + #define HAS_E4_ENABLE 1 + #endif + #if PIN_EXISTS(E4_DIR) + #define HAS_E4_DIR 1 + #endif + #if PIN_EXISTS(E4_STEP) + #define HAS_E4_STEP 1 + #endif + #if PIN_EXISTS(E4_MS1) + #define HAS_E4_MS_PINS 1 + #endif + #if PIN_EXISTS(SOL4) + #define HAS_SOLENOID_4 1 + #endif -#if PIN_EXISTS(E6_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E6)) - #define HAS_E6_ENABLE 1 -#endif -#if PIN_EXISTS(E6_DIR) - #define HAS_E6_DIR 1 -#endif -#if PIN_EXISTS(E6_STEP) - #define HAS_E6_STEP 1 -#endif -#if PIN_EXISTS(E6_MS1) - #define HAS_E6_MS_PINS 1 -#endif -#if PIN_EXISTS(SOL6) - #define HAS_SOLENOID_6 1 -#endif + #if PIN_EXISTS(E5_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E5)) + #define HAS_E5_ENABLE 1 + #endif + #if PIN_EXISTS(E5_DIR) + #define HAS_E5_DIR 1 + #endif + #if PIN_EXISTS(E5_STEP) + #define HAS_E5_STEP 1 + #endif + #if PIN_EXISTS(E5_MS1) + #define HAS_E5_MS_PINS 1 + #endif + #if PIN_EXISTS(SOL5) + #define HAS_SOLENOID_5 1 + #endif -#if PIN_EXISTS(E7_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E7)) - #define HAS_E7_ENABLE 1 -#endif -#if PIN_EXISTS(E7_DIR) - #define HAS_E7_DIR 1 -#endif -#if PIN_EXISTS(E7_STEP) - #define HAS_E7_STEP 1 -#endif -#if PIN_EXISTS(E7_MS1) - #define HAS_E7_MS_PINS 1 -#endif -#if PIN_EXISTS(SOL7) - #define HAS_SOLENOID_7 1 -#endif + #if PIN_EXISTS(E6_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E6)) + #define HAS_E6_ENABLE 1 + #endif + #if PIN_EXISTS(E6_DIR) + #define HAS_E6_DIR 1 + #endif + #if PIN_EXISTS(E6_STEP) + #define HAS_E6_STEP 1 + #endif + #if PIN_EXISTS(E6_MS1) + #define HAS_E6_MS_PINS 1 + #endif + #if PIN_EXISTS(SOL6) + #define HAS_SOLENOID_6 1 + #endif + + #if PIN_EXISTS(E7_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E7)) + #define HAS_E7_ENABLE 1 + #endif + #if PIN_EXISTS(E7_DIR) + #define HAS_E7_DIR 1 + #endif + #if PIN_EXISTS(E7_STEP) + #define HAS_E7_STEP 1 + #endif + #if PIN_EXISTS(E7_MS1) + #define HAS_E7_MS_PINS 1 + #endif + #if PIN_EXISTS(SOL7) + #define HAS_SOLENOID_7 1 + #endif + +#endif // HAS_EXTRUDERS // // Trinamic Stepper Drivers // #if HAS_TRINAMIC_CONFIG - #if ANY(STEALTHCHOP_XY, STEALTHCHOP_Z, STEALTHCHOP_E) + #if ANY(STEALTHCHOP_E, STEALTHCHOP_XY, STEALTHCHOP_Z, STEALTHCHOP_I, STEALTHCHOP_J, STEALTHCHOP_K) #define STEALTHCHOP_ENABLED 1 #endif #if EITHER(SENSORLESS_HOMING, SENSORLESS_PROBING) @@ -1733,6 +2052,65 @@ #if defined(Z4_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z4) #define Z4_SENSORLESS 1 #endif + + #if AXIS_HAS_STEALTHCHOP(X) + #define X_HAS_STEALTHCHOP 1 + #endif + #if AXIS_HAS_STEALTHCHOP(X2) + #define X2_HAS_STEALTHCHOP 1 + #endif + #if AXIS_HAS_STEALTHCHOP(Y) + #define Y_HAS_STEALTHCHOP 1 + #endif + #if AXIS_HAS_STEALTHCHOP(Y2) + #define Y2_HAS_STEALTHCHOP 1 + #endif + #if AXIS_HAS_STEALTHCHOP(Z) + #define Z_HAS_STEALTHCHOP 1 + #endif + #if AXIS_HAS_STEALTHCHOP(Z2) + #define Z2_HAS_STEALTHCHOP 1 + #endif + #if AXIS_HAS_STEALTHCHOP(Z3) + #define Z3_HAS_STEALTHCHOP 1 + #endif + #if AXIS_HAS_STEALTHCHOP(Z4) + #define Z4_HAS_STEALTHCHOP 1 + #endif + #if AXIS_HAS_STEALTHCHOP(I) + #define I_HAS_STEALTHCHOP 1 + #endif + #if AXIS_HAS_STEALTHCHOP(J) + #define J_HAS_STEALTHCHOP 1 + #endif + #if AXIS_HAS_STEALTHCHOP(K) + #define K_HAS_STEALTHCHOP 1 + #endif + #if E_STEPPERS > 0 && AXIS_HAS_STEALTHCHOP(E0) + #define E0_HAS_STEALTHCHOP 1 + #endif + #if E_STEPPERS > 1 && AXIS_HAS_STEALTHCHOP(E1) + #define E1_HAS_STEALTHCHOP 1 + #endif + #if E_STEPPERS > 2 && AXIS_HAS_STEALTHCHOP(E2) + #define E2_HAS_STEALTHCHOP 1 + #endif + #if E_STEPPERS > 3 && AXIS_HAS_STEALTHCHOP(E3) + #define E3_HAS_STEALTHCHOP 1 + #endif + #if E_STEPPERS > 4 && AXIS_HAS_STEALTHCHOP(E4) + #define E4_HAS_STEALTHCHOP 1 + #endif + #if E_STEPPERS > 5 && AXIS_HAS_STEALTHCHOP(E5) + #define E5_HAS_STEALTHCHOP 1 + #endif + #if E_STEPPERS > 6 && AXIS_HAS_STEALTHCHOP(E6) + #define E6_HAS_STEALTHCHOP 1 + #endif + #if E_STEPPERS > 7 && AXIS_HAS_STEALTHCHOP(E7) + #define E7_HAS_STEALTHCHOP 1 + #endif + #if ENABLED(SPI_ENDSTOPS) #define X_SPI_SENSORLESS X_SENSORLESS #define Y_SPI_SENSORLESS Y_SENSORLESS @@ -1762,6 +2140,21 @@ #ifndef Z4_INTERPOLATE #define Z4_INTERPOLATE INTERPOLATE #endif + #if LINEAR_AXES >= 4 + #ifndef I_INTERPOLATE + #define I_INTERPOLATE INTERPOLATE + #endif + #endif + #if LINEAR_AXES >= 5 + #ifndef J_INTERPOLATE + #define J_INTERPOLATE INTERPOLATE + #endif + #endif + #if LINEAR_AXES >= 6 + #ifndef K_INTERPOLATE + #define K_INTERPOLATE INTERPOLATE + #endif + #endif #ifndef E0_INTERPOLATE #define E0_INTERPOLATE INTERPOLATE #endif @@ -1795,6 +2188,15 @@ #ifndef Z_SLAVE_ADDRESS #define Z_SLAVE_ADDRESS 0 #endif + #ifndef I_SLAVE_ADDRESS + #define I_SLAVE_ADDRESS 0 + #endif + #ifndef J_SLAVE_ADDRESS + #define J_SLAVE_ADDRESS 0 + #endif + #ifndef K_SLAVE_ADDRESS + #define K_SLAVE_ADDRESS 0 + #endif #ifndef X2_SLAVE_ADDRESS #define X2_SLAVE_ADDRESS 0 #endif @@ -1849,6 +2251,10 @@ #define HAS_TMC_SW_SERIAL 1 #endif +#if !USE_SENSORLESS + #undef SENSORLESS_BACKOFF_MM +#endif + // // Set USING_HW_SERIALn flags for used Serial Ports // @@ -1968,18 +2374,36 @@ #if _HAS_STOP(X,MAX) #define HAS_X_MAX 1 #endif -#if _HAS_STOP(Y,MIN) +#if HAS_Y_AXIS && _HAS_STOP(Y,MIN) #define HAS_Y_MIN 1 #endif -#if _HAS_STOP(Y,MAX) +#if HAS_Y_AXIS && _HAS_STOP(Y,MAX) #define HAS_Y_MAX 1 #endif -#if _HAS_STOP(Z,MIN) +#if BOTH(HAS_Z_AXIS, USE_ZMIN_PLUG) && _HAS_STOP(Z,MIN) #define HAS_Z_MIN 1 #endif -#if _HAS_STOP(Z,MAX) +#if BOTH(HAS_Z_AXIS, USE_ZMAX_PLUG) && _HAS_STOP(Z,MAX) #define HAS_Z_MAX 1 #endif +#if _HAS_STOP(I,MIN) + #define HAS_I_MIN 1 +#endif +#if _HAS_STOP(I,MAX) + #define HAS_I_MAX 1 +#endif +#if _HAS_STOP(J,MIN) + #define HAS_J_MIN 1 +#endif +#if _HAS_STOP(J,MAX) + #define HAS_J_MAX 1 +#endif +#if _HAS_STOP(K,MIN) + #define HAS_K_MIN 1 +#endif +#if _HAS_STOP(K,MAX) + #define HAS_K_MAX 1 +#endif #if PIN_EXISTS(X2_MIN) #define HAS_X2_MIN 1 #endif @@ -2061,6 +2485,9 @@ #if HAS_ADC_TEST(COOLER) #define HAS_TEMP_ADC_COOLER 1 #endif +#if HAS_ADC_TEST(REDUNDANT) + #define HAS_TEMP_ADC_REDUNDANT 1 +#endif #define HAS_TEMP(N) ANY(HAS_TEMP_ADC_##N, TEMP_SENSOR_##N##_IS_MAX_TC, TEMP_SENSOR_##N##_IS_DUMMY) #if HAS_HOTEND && HAS_TEMP(0) @@ -2078,6 +2505,9 @@ #if HAS_TEMP(COOLER) #define HAS_TEMP_COOLER 1 #endif +#if HAS_TEMP(REDUNDANT) + #define HAS_TEMP_REDUNDANT 1 +#endif #if ENABLED(JOYSTICK) #if PIN_EXISTS(JOY_X) @@ -2348,7 +2778,10 @@ #if PIN_EXISTS(DIGIPOTSS) #define HAS_MOTOR_CURRENT_SPI 1 #endif -#if ANY_PIN(MOTOR_CURRENT_PWM_X, MOTOR_CURRENT_PWM_Y, MOTOR_CURRENT_PWM_XY, MOTOR_CURRENT_PWM_Z, MOTOR_CURRENT_PWM_E) +#if HAS_EXTRUDERS && PIN_EXISTS(MOTOR_CURRENT_PWM_E) + #define HAS_MOTOR_CURRENT_PWM_E 1 +#endif +#if HAS_MOTOR_CURRENT_PWM_E || ANY_PIN(MOTOR_CURRENT_PWM_X, MOTOR_CURRENT_PWM_Y, MOTOR_CURRENT_PWM_XY, MOTOR_CURRENT_PWM_Z) #define HAS_MOTOR_CURRENT_PWM 1 #endif @@ -2358,7 +2791,7 @@ #if ANY(HAS_E0_MS_PINS, HAS_E1_MS_PINS, HAS_E2_MS_PINS, HAS_E3_MS_PINS, HAS_E4_MS_PINS, HAS_E5_MS_PINS, HAS_E6_MS_PINS, HAS_E7_MS_PINS) #define HAS_SOME_E_MS_PINS 1 #endif -#if ANY(HAS_X_MS_PINS, HAS_X2_MS_PINS, HAS_Y_MS_PINS, HAS_Y2_MS_PINS, HAS_SOME_Z_MS_PINS, HAS_SOME_E_MS_PINS) +#if ANY(HAS_X_MS_PINS, HAS_X2_MS_PINS, HAS_Y_MS_PINS, HAS_Y2_MS_PINS, HAS_SOME_Z_MS_PINS, HAS_I_MS_PINS, HAS_J_MS_PINS, HAS_K_MS_PINS, HAS_SOME_E_MS_PINS) #define HAS_MICROSTEPS 1 #endif @@ -2666,6 +3099,7 @@ #endif #else #undef NOZZLE_TO_PROBE_OFFSET + #undef PROBING_STEPPERS_OFF #endif /** @@ -2708,18 +3142,26 @@ /** * Heater, Fan, and Probe interactions */ -#if FAN_COUNT == 0 - #undef PROBING_FANS_OFF +#if !HAS_FAN #undef ADAPTIVE_FAN_SLOWING #undef NO_FAN_SLOWING_IN_PID_TUNING #endif - -#if HAS_BED_PROBE && (EITHER(PROBING_HEATERS_OFF, PROBING_FANS_OFF) || DELAY_BEFORE_PROBING > 0) - #define HAS_QUIET_PROBING 1 +#if !BOTH(HAS_BED_PROBE, HAS_FAN) + #undef PROBING_FANS_OFF +#endif +#if !BOTH(HAS_BED_PROBE, HAS_EXTRUDERS) + #undef PROBING_ESTEPPERS_OFF +#endif +#if BOTH(PROBING_STEPPERS_OFF, PROBING_ESTEPPERS_OFF) + #undef PROBING_ESTEPPERS_OFF + #warning "PROBING_STEPPERS_OFF includes PROBING_ESTEPPERS_OFF. Disabling PROBING_ESTEPPERS_OFF." #endif #if EITHER(ADVANCED_PAUSE_FEATURE, PROBING_HEATERS_OFF) #define HEATER_IDLE_HANDLER 1 #endif +#if HAS_BED_PROBE && (ANY(PROBING_HEATERS_OFF, PROBING_STEPPERS_OFF, PROBING_ESTEPPERS_OFF, PROBING_FANS_OFF) || DELAY_BEFORE_PROBING > 0) + #define HAS_QUIET_PROBING 1 +#endif /** * Advanced Pause - Filament Change @@ -2955,9 +3397,14 @@ #endif #endif -// LCD timeout to status screen default is 15s -#ifndef LCD_TIMEOUT_TO_STATUS - #define LCD_TIMEOUT_TO_STATUS 15000 +#if HAS_LCD_MENU + // LCD timeout to status screen default is 15s + #ifndef LCD_TIMEOUT_TO_STATUS + #define LCD_TIMEOUT_TO_STATUS 15000 + #endif + #if LCD_TIMEOUT_TO_STATUS + #define SCREENS_CAN_TIME_OUT 1 + #endif #endif // Add commands that need sub-codes to this list diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 897cb2824fc94..36ccbee9b9c9f 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -34,6 +34,10 @@ #error "Marlin requires C++11 support (gcc >= 4.7, Arduino IDE >= 1.6.8). Please upgrade your toolchain." #endif +// Strings for sanity check messages +#define _LINEAR_AXES_STR LINEAR_AXIS_GANG("X ", "Y ", "Z ", "I ", "J ", "K ") +#define _LOGICAL_AXES_STR LOGICAL_AXIS_GANG("E ", "X ", "Y ", "Z ", "I ", "J ", "K ") + // Make sure macros aren't borked #define TEST1 #define TEST2 1 @@ -562,11 +566,21 @@ #error "CUSTOM_USER_MENUS has been replaced by CUSTOM_MENU_MAIN and CUSTOM_MENU_CONFIG." #elif defined(MKS_LCD12864) #error "MKS_LCD12864 is now MKS_LCD12864A or MKS_LCD12864B." +#elif defined(NEOPIXEL_BKGD_LED_INDEX) + #error "NEOPIXEL_BKGD_LED_INDEX is now NEOPIXEL_BKGD_INDEX_FIRST." +#elif defined(TEMP_SENSOR_1_AS_REDUNDANT) + #error "TEMP_SENSOR_1_AS_REDUNDANT is now TEMP_SENSOR_REDUNDANT, with associated TEMP_SENSOR_REDUNDANT_* config." +#elif defined(MAX_REDUNDANT_TEMP_SENSOR_DIFF) + #error "MAX_REDUNDANT_TEMP_SENSOR_DIFF is now TEMP_SENSOR_REDUNDANT_MAX_DIFF" #endif +constexpr float arm[] = AXIS_RELATIVE_MODES; +static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _LOGICAL_AXES_STR "elements."); + /** * Probe temp compensation requirements */ + #if ENABLED(PROBE_TEMP_COMPENSATION) #if defined(PTC_PARK_POS_X) || defined(PTC_PARK_POS_Y) || defined(PTC_PARK_POS_Z) #error "PTC_PARK_POS_[XYZ] is now PTC_PARK_POS (array)." @@ -577,6 +591,32 @@ #elif !defined(PTC_PROBE_POS) #error "PROBE_TEMP_COMPENSATION requires PTC_PROBE_POS." #endif + + #ifdef PTC_SAMPLE_START + constexpr auto _ptc_sample_start = PTC_SAMPLE_START; + constexpr decltype(_ptc_sample_start) _test_ptc_sample_start = 12.3f; + static_assert(_test_ptc_sample_start != 12.3f, "PTC_SAMPLE_START must be a whole number."); + #endif + #ifdef PTC_SAMPLE_RES + constexpr auto _ptc_sample_res = PTC_SAMPLE_RES; + constexpr decltype(_ptc_sample_res) _test_ptc_sample_res = 12.3f; + static_assert(_test_ptc_sample_res != 12.3f, "PTC_SAMPLE_RES must be a whole number."); + #endif + #ifdef BTC_SAMPLE_START + constexpr auto _btc_sample_start = BTC_SAMPLE_START; + constexpr decltype(_btc_sample_start) _test_btc_sample_start = 12.3f; + static_assert(_test_btc_sample_start != 12.3f, "BTC_SAMPLE_START must be a whole number."); + #endif + #ifdef BTC_SAMPLE_RES + constexpr _btc_sample_res = BTC_SAMPLE_RES; + constexpr decltype(_btc_sample_res) _test_btc_sample_res = 12.3f; + static_assert(_test_btc_sample_res != 12.3f, "BTC_SAMPLE_RES must be a whole number."); + #endif + #ifdef BTC_PROBE_TEMP + constexpr auto _btc_probe_temp = BTC_PROBE_TEMP; + constexpr decltype(_btc_probe_temp) _test_btc_probe_temp = 12.3f; + static_assert(_test_btc_probe_temp != 12.3f, "BTC_PROBE_TEMP must be a whole number."); + #endif #endif /** @@ -642,14 +682,18 @@ #if ENABLED(Y_DUAL_STEPPER_DRIVERS) && !GOOD_AXIS_PINS(Y) #error "Y_DUAL_STEPPER_DRIVERS requires Y2 pins to be defined." -#elif !WITHIN(NUM_Z_STEPPER_DRIVERS, 1, 4) - #error "NUM_Z_STEPPER_DRIVERS must be an integer from 1 to 4." -#elif NUM_Z_STEPPER_DRIVERS == 2 && !GOOD_AXIS_PINS(Z2) - #error "If NUM_Z_STEPPER_DRIVERS is 2, you must define stepper pins for Z2." -#elif NUM_Z_STEPPER_DRIVERS == 3 && !(GOOD_AXIS_PINS(Z2) && GOOD_AXIS_PINS(Z3)) - #error "If NUM_Z_STEPPER_DRIVERS is 3, you must define stepper pins for Z2 and Z3." -#elif NUM_Z_STEPPER_DRIVERS == 4 && !(GOOD_AXIS_PINS(Z2) && GOOD_AXIS_PINS(Z3) && GOOD_AXIS_PINS(Z4)) - #error "If NUM_Z_STEPPER_DRIVERS is 4, you must define stepper pins for Z2, Z3, and Z4." +#endif + +#if HAS_Z_AXIS + #if !WITHIN(NUM_Z_STEPPER_DRIVERS, 1, 4) + #error "NUM_Z_STEPPER_DRIVERS must be an integer from 1 to 4." + #elif NUM_Z_STEPPER_DRIVERS == 2 && !GOOD_AXIS_PINS(Z2) + #error "If NUM_Z_STEPPER_DRIVERS is 2, you must define stepper pins for Z2." + #elif NUM_Z_STEPPER_DRIVERS == 3 && !(GOOD_AXIS_PINS(Z2) && GOOD_AXIS_PINS(Z3)) + #error "If NUM_Z_STEPPER_DRIVERS is 3, you must define stepper pins for Z2 and Z3." + #elif NUM_Z_STEPPER_DRIVERS == 4 && !(GOOD_AXIS_PINS(Z2) && GOOD_AXIS_PINS(Z3) && GOOD_AXIS_PINS(Z4)) + #error "If NUM_Z_STEPPER_DRIVERS is 4, you must define stepper pins for Z2, Z3, and Z4." + #endif #endif /** @@ -702,6 +746,12 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "Enable only one of ENDSTOPPULLUP_Y_MIN or ENDSTOPPULLDOWN_Y_MIN." #elif BOTH(ENDSTOPPULLUP_ZMIN, ENDSTOPPULLDOWN_ZMIN) #error "Enable only one of ENDSTOPPULLUP_Z_MIN or ENDSTOPPULLDOWN_Z_MIN." +#elif BOTH(ENDSTOPPULLUP_IMIN, ENDSTOPPULLDOWN_IMIN) + #error "Enable only one of ENDSTOPPULLUP_I_MIN or ENDSTOPPULLDOWN_I_MIN." +#elif BOTH(ENDSTOPPULLUP_JMIN, ENDSTOPPULLDOWN_JMIN) + #error "Enable only one of ENDSTOPPULLUP_J_MIN or ENDSTOPPULLDOWN_J_MIN." +#elif BOTH(ENDSTOPPULLUP_KMIN, ENDSTOPPULLDOWN_KMIN) + #error "Enable only one of ENDSTOPPULLUP_K_MIN or ENDSTOPPULLDOWN_K_MIN." #endif /** @@ -924,6 +974,13 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS static_assert(WITHIN(npp_xyz.z, Z_MIN_POS, Z_MAX_POS), "NOZZLE_PARK_POINT.Z is out of bounds (Z_MIN_POS, Z_MAX_POS)."); #endif +/** + * Instant Freeze + */ +#if ENABLED(FREEZE_FEATURE) && !PIN_EXISTS(FREEZE) + #error "FREEZE_FEATURE requires a FREEZE_PIN to be defined." +#endif + /** * Individual axis homing is useless for DELTAS */ @@ -952,9 +1009,11 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS * Multi-Material-Unit 2 / EXTENDABLE_EMU_MMU2 requirements */ #if HAS_PRUSA_MMU2 - #if EXTRUDERS != 5 + #if !HAS_EXTENDABLE_MMU && EXTRUDERS != 5 #undef SINGLENOZZLE #error "PRUSA_MMU2(S) requires exactly 5 EXTRUDERS. Please update your Configuration." + #elif HAS_EXTENDABLE_MMU && EXTRUDERS > 15 + #error "EXTRUDERS is too large for MMU(S) emulation mode. The maximum value is 15." #elif DISABLED(NOZZLE_PARK_FEATURE) #error "PRUSA_MMU2(S) requires NOZZLE_PARK_FEATURE. Enable it to continue." #elif HAS_PRUSA_MMU2S && DISABLED(FILAMENT_RUNOUT_SENSOR) @@ -967,23 +1026,28 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS static_assert(nullptr == strstr(MMU2_FILAMENT_RUNOUT_SCRIPT, "M600"), "ADVANCED_PAUSE_FEATURE is required to use M600 with PRUSA_MMU2(S) / HAS_EXTENDABLE_MMU(S)."); #endif #endif -#if HAS_EXTENDABLE_MMU && EXTRUDERS > 15 - #error "Too many extruders for MMU(S) emulation mode. (15 maximum)." -#endif /** * Options only for EXTRUDERS > 1 */ #if HAS_MULTI_EXTRUDER - #if EXTRUDERS > 8 - #error "Marlin supports a maximum of 8 EXTRUDERS." + #if HAS_EXTENDABLE_MMU + #define MAX_EXTRUDERS 15 + #else + #define MAX_EXTRUDERS 8 #endif + static_assert(EXTRUDERS <= MAX_EXTRUDERS, "Marlin supports a maximum of " STRINGIFY(MAX_EXTRUDERS) " EXTRUDERS."); + #undef MAX_EXTRUDERS #if ENABLED(HEATERS_PARALLEL) #error "EXTRUDERS must be 1 with HEATERS_PARALLEL." #endif + #if ENABLED(STATUS_HOTEND_INVERTED) && NONE(STATUS_HOTEND_NUMBERLESS, STATUS_HOTEND_ANIM) + #error "With multiple hotends STATUS_HOTEND_INVERTED requires STATUS_HOTEND_ANIM or STATUS_HOTEND_NUMBERLESS." + #endif + #if ENABLED(TOOLCHANGE_FILAMENT_SWAP) #ifndef TOOLCHANGE_FS_LENGTH #error "TOOLCHANGE_FILAMENT_SWAP requires TOOLCHANGE_FS_LENGTH." @@ -1106,6 +1170,19 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif #endif +/** + * Dual E Steppers requirements + */ +#if ENABLED(E_DUAL_STEPPER_DRIVERS) + #if EXTRUDERS > 1 + #error "E_DUAL_STEPPER_DRIVERS can only be used with EXTRUDERS set to 1." + #elif ENABLED(MIXING_EXTRUDER) + #error "E_DUAL_STEPPER_DRIVERS is incompatible with MIXING_EXTRUDER." + #elif ENABLED(SWITCHING_EXTRUDER) + #error "E_DUAL_STEPPER_DRIVERS is incompatible with SWITCHING_EXTRUDER." + #endif +#endif + /** * Linear Advance 1.5 - Check K value range */ @@ -1177,23 +1254,28 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif /** - * (Electro)magnetic Switching Toolhead requirements + * Magnetic / Electromagnetic Switching Toolhead requirements */ #if EITHER(MAGNETIC_SWITCHING_TOOLHEAD, ELECTROMAGNETIC_SWITCHING_TOOLHEAD) #ifndef SWITCHING_TOOLHEAD_Y_POS - #error "(ELECTRO)MAGNETIC_SWITCHING_TOOLHEAD requires SWITCHING_TOOLHEAD_Y_POS" + #error "(ELECTRO)?MAGNETIC_SWITCHING_TOOLHEAD requires SWITCHING_TOOLHEAD_Y_POS" #elif !defined(SWITCHING_TOOLHEAD_X_POS) - #error "(ELECTRO)MAGNETIC_SWITCHING_TOOLHEAD requires SWITCHING_TOOLHEAD_X_POS" - #elif !defined(SWITCHING_TOOLHEAD_Z_HOP) - #error "(ELECTRO)MAGNETIC_SWITCHING_TOOLHEAD requires SWITCHING_TOOLHEAD_Z_HOP." + #error "(ELECTRO)?MAGNETIC_SWITCHING_TOOLHEAD requires SWITCHING_TOOLHEAD_X_POS" #elif !defined(SWITCHING_TOOLHEAD_Y_CLEAR) - #error "(ELECTRO)MAGNETIC_SWITCHING_TOOLHEAD requires SWITCHING_TOOLHEAD_Y_CLEAR." - #elif ENABLED(ELECTROMAGNETIC_SWITCHING_TOOLHEAD) - #if ENABLED(EXT_SOLENOID) - #error "(ELECTRO)MAGNETIC_SWITCHING_TOOLHEAD and EXT_SOLENOID are incompatible. (Pins are used twice.)" - #elif !PIN_EXISTS(SOL0) - #error "(ELECTRO)MAGNETIC_SWITCHING_TOOLHEAD requires SOL0_PIN." - #endif + #error "(ELECTRO)?MAGNETIC_SWITCHING_TOOLHEAD requires SWITCHING_TOOLHEAD_Y_CLEAR." + #endif +#endif + +/** + * Electromagnetic Switching Toolhead requirements + */ +#if ENABLED(ELECTROMAGNETIC_SWITCHING_TOOLHEAD) + #if ENABLED(EXT_SOLENOID) + #error "ELECTROMAGNETIC_SWITCHING_TOOLHEAD and EXT_SOLENOID are incompatible. (Pins are used twice.)" + #elif !PIN_EXISTS(SOL0) + #error "ELECTROMAGNETIC_SWITCHING_TOOLHEAD requires SOL0_PIN." + #elif !defined(SWITCHING_TOOLHEAD_Z_HOP) + #error "ELECTROMAGNETIC_SWITCHING_TOOLHEAD requires SWITCHING_TOOLHEAD_Z_HOP." #endif #endif @@ -1261,6 +1343,42 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "To use CHAMBER_LIMIT_SWITCHING you must disable PIDTEMPCHAMBER." #endif +/** + * Features that require a min/max/specific LINEAR_AXES + */ +#if HAS_LEVELING && !HAS_Z_AXIS + #error "Leveling in Marlin requires three or more axes, with Z as the vertical axis." +#elif ENABLED(CNC_WORKSPACE_PLANES) && !HAS_Z_AXIS + #error "CNC_WORKSPACE_PLANES currently requires LINEAR_AXES >= 3" +#elif ENABLED(DIRECT_STEPPING) && LINEAR_AXES > XYZ + #error "DIRECT_STEPPING currently requires LINEAR_AXES 3" +#elif ENABLED(FOAMCUTTER_XYUV) && LINEAR_AXES < 5 + #error "FOAMCUTTER_XYUV requires LINEAR_AXES >= 5." +#endif + +/** + * Allow only extra axis codes that do not conflict with G-code parameter names + */ +#if LINEAR_AXES >= 4 + #if AXIS4_NAME != 'A' && AXIS4_NAME != 'B' && AXIS4_NAME != 'C' && AXIS4_NAME != 'U' && AXIS4_NAME != 'V' && AXIS4_NAME != 'W' + #error "AXIS4_NAME can only be one of 'A', 'B', 'C', 'U', 'V', or 'W'." + #endif +#endif +#if LINEAR_AXES >= 5 + #if AXIS5_NAME == AXIS4_NAME || AXIS5_NAME == AXIS6_NAME + #error "AXIS5_NAME must be different from AXIS4_NAME and AXIS6_NAME" + #elif AXIS5_NAME != 'A' && AXIS5_NAME != 'B' && AXIS5_NAME != 'C' && AXIS5_NAME != 'U' && AXIS5_NAME != 'V' && AXIS5_NAME != 'W' + #error "AXIS5_NAME can only be one of 'A', 'B', 'C', 'U', 'V', or 'W'." + #endif +#endif +#if LINEAR_AXES >= 6 + #if AXIS6_NAME == AXIS5_NAME || AXIS6_NAME == AXIS4_NAME + #error "AXIS6_NAME must be different from AXIS5_NAME and AXIS4_NAME." + #elif AXIS6_NAME != 'A' && AXIS6_NAME != 'B' && AXIS6_NAME != 'C' && AXIS6_NAME != 'U' && AXIS6_NAME != 'V' && AXIS6_NAME != 'W' + #error "AXIS6_NAME can only be one of 'A', 'B', 'C', 'U', 'V', or 'W'." + #endif +#endif + /** * Kinematics */ @@ -1268,8 +1386,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS /** * Allow only one kinematic type to be defined */ -#if MANY(DELTA, MORGAN_SCARA, MP_SCARA, AXEL_TPARA, COREXY, COREXZ, COREYZ, COREYX, COREZX, COREZY, MARKFORGED_XY) - #error "Please enable only one of DELTA, MORGAN_SCARA, AXEL_TPARA, COREXY, COREYX, COREXZ, COREZX, COREYZ, COREZY, or MARKFORGED_XY." +#if MANY(DELTA, MORGAN_SCARA, MP_SCARA, AXEL_TPARA, COREXY, COREXZ, COREYZ, COREYX, COREZX, COREZY, MARKFORGED_XY, FOAMCUTTER_XYUV) + #error "Please enable only one of DELTA, MORGAN_SCARA, MP_SCARA, AXEL_TPARA, COREXY, COREXZ, COREYZ, COREYX, COREZX, COREZY, MARKFORGED_XY, or FOAMCUTTER_XYUV." #endif /** @@ -1566,12 +1684,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "MESH_EDIT_GFX_OVERLAY requires AUTO_BED_LEVELING_UBL and a Graphical LCD." #endif -#if ENABLED(G29_RETRY_AND_RECOVER) - #if ENABLED(AUTO_BED_LEVELING_UBL) - #error "G29_RETRY_AND_RECOVER is not compatible with UBL." - #elif ENABLED(MESH_BED_LEVELING) - #error "G29_RETRY_AND_RECOVER is not compatible with MESH_BED_LEVELING." - #endif +#if ENABLED(G29_RETRY_AND_RECOVER) && NONE(AUTO_BED_LEVELING_3POINT, AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_BILINEAR) + #error "G29_RETRY_AND_RECOVER requires AUTO_BED_LEVELING_3POINT, LINEAR, or BILINEAR." #endif /** @@ -1582,6 +1696,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "LCD_BED_LEVELING requires a programmable LCD controller." #elif !(ENABLED(MESH_BED_LEVELING) || HAS_ABL_NOT_UBL) #error "LCD_BED_LEVELING requires MESH_BED_LEVELING or AUTO_BED_LEVELING." + #elif ENABLED(MESH_EDIT_MENU) && !HAS_MESH + #error "MESH_EDIT_MENU requires MESH_BED_LEVELING, AUTO_BED_LEVELING_BILINEAR or AUTO_BED_LEVELING_UBL." #endif #endif @@ -1590,13 +1706,59 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #endif /** - * Homing + * Homing checks */ -constexpr float hbm[] = HOMING_BUMP_MM; -static_assert(COUNT(hbm) == XYZ, "HOMING_BUMP_MM requires X, Y, and Z elements."); -static_assert(hbm[X_AXIS] >= 0, "HOMING_BUMP_MM.X must be greater than or equal to 0."); -static_assert(hbm[Y_AXIS] >= 0, "HOMING_BUMP_MM.Y must be greater than or equal to 0."); -static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal to 0."); +#ifndef HOMING_BUMP_MM + #error "Required setting HOMING_BUMP_MM is missing!" +#elif !defined(HOMING_BUMP_DIVISOR) + #error "Required setting HOMING_BUMP_DIVISOR is missing!" +#else + constexpr float hbm[] = HOMING_BUMP_MM, hbd[] = HOMING_BUMP_DIVISOR; + static_assert(COUNT(hbm) == LINEAR_AXES, "HOMING_BUMP_MM must have " _LINEAR_AXES_STR "elements (and no others)."); + LINEAR_AXIS_CODE( + static_assert(hbm[X_AXIS] >= 0, "HOMING_BUMP_MM.X must be greater than or equal to 0."), + static_assert(hbm[Y_AXIS] >= 0, "HOMING_BUMP_MM.Y must be greater than or equal to 0."), + static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal to 0."), + static_assert(hbm[I_AXIS] >= 0, "HOMING_BUMP_MM.I must be greater than or equal to 0."), + static_assert(hbm[J_AXIS] >= 0, "HOMING_BUMP_MM.J must be greater than or equal to 0."), + static_assert(hbm[K_AXIS] >= 0, "HOMING_BUMP_MM.K must be greater than or equal to 0.") + ); + static_assert(COUNT(hbd) == LINEAR_AXES, "HOMING_BUMP_DIVISOR must have " _LINEAR_AXES_STR "elements (and no others)."); + LINEAR_AXIS_CODE( + static_assert(hbd[X_AXIS] >= 1, "HOMING_BUMP_DIVISOR.X must be greater than or equal to 1."), + static_assert(hbd[Y_AXIS] >= 1, "HOMING_BUMP_DIVISOR.Y must be greater than or equal to 1."), + static_assert(hbd[Z_AXIS] >= 1, "HOMING_BUMP_DIVISOR.Z must be greater than or equal to 1."), + static_assert(hbd[I_AXIS] >= 1, "HOMING_BUMP_DIVISOR.I must be greater than or equal to 1."), + static_assert(hbd[J_AXIS] >= 1, "HOMING_BUMP_DIVISOR.J must be greater than or equal to 1."), + static_assert(hbd[K_AXIS] >= 1, "HOMING_BUMP_DIVISOR.K must be greater than or equal to 1.") + ); +#endif + +#ifdef HOMING_BACKOFF_POST_MM + constexpr float hbp[] = HOMING_BACKOFF_POST_MM; + static_assert(COUNT(hbp) == LINEAR_AXES, "HOMING_BACKOFF_POST_MM must have " _LINEAR_AXES_STR "elements (and no others)."); + LINEAR_AXIS_CODE( + static_assert(hbp[X_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.X must be greater than or equal to 0."), + static_assert(hbp[Y_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.Y must be greater than or equal to 0."), + static_assert(hbp[Z_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.Z must be greater than or equal to 0."), + static_assert(hbp[I_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.I must be greater than or equal to 0."), + static_assert(hbp[J_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.J must be greater than or equal to 0."), + static_assert(hbp[K_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.K must be greater than or equal to 0.") + ); +#endif + +#ifdef SENSORLESS_BACKOFF_MM + constexpr float sbm[] = SENSORLESS_BACKOFF_MM; + static_assert(COUNT(sbm) == LINEAR_AXES, "SENSORLESS_BACKOFF_MM must have " _LINEAR_AXES_STR "elements (and no others)."); + LINEAR_AXIS_CODE( + static_assert(sbm[X_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.X must be greater than or equal to 0."), + static_assert(sbm[Y_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.Y must be greater than or equal to 0."), + static_assert(sbm[Z_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.Z must be greater than or equal to 0."), + static_assert(sbm[I_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.I must be greater than or equal to 0."), + static_assert(sbm[J_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.J must be greater than or equal to 0."), + static_assert(sbm[K_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.K must be greater than or equal to 0.") + ); +#endif #if ENABLED(CODEPENDENT_XY_HOMING) #if ENABLED(QUICK_HOME) @@ -1617,9 +1779,9 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal /** * Make sure DISABLE_[XYZ] compatible with selected homing options */ -#if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z) +#if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z, DISABLE_I, DISABLE_J, DISABLE_K) #if EITHER(HOME_AFTER_DEACTIVATE, Z_SAFE_HOMING) - #error "DISABLE_[XYZ] is not compatible with HOME_AFTER_DEACTIVATE or Z_SAFE_HOMING." + #error "DISABLE_[XYZIJK] is not compatible with HOME_AFTER_DEACTIVATE or Z_SAFE_HOMING." #endif #endif @@ -1742,6 +1904,14 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #endif #endif +#ifdef REDUNDANT_PART_COOLING_FAN + #if FAN_COUNT < 2 + #error "REDUNDANT_PART_COOLING_FAN requires a board with at least two PWM fans." + #else + static_assert(WITHIN(REDUNDANT_PART_COOLING_FAN, 1, FAN_COUNT - 1), "REDUNDANT_PART_COOLING_FAN must be between 1 and " STRINGIFY(DECREMENT(FAN_COUNT)) "."); + #endif +#endif + /** * Case Light requirements */ @@ -1778,19 +1948,88 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #error "TEMP_SENSOR_CHAMBER 1000 requires CHAMBER_PULLUP_RESISTOR_OHMS, CHAMBER_RESISTANCE_25C_OHMS and CHAMBER_BETA in Configuration_adv.h." #elif TEMP_SENSOR_PROBE_IS_CUSTOM && !(defined(PROBE_PULLUP_RESISTOR_OHMS) && defined(PROBE_RESISTANCE_25C_OHMS) && defined(PROBE_BETA)) #error "TEMP_SENSOR_PROBE 1000 requires PROBE_PULLUP_RESISTOR_OHMS, PROBE_RESISTANCE_25C_OHMS and PROBE_BETA in Configuration_adv.h." +#elif TEMP_SENSOR_REDUNDANT_IS_CUSTOM && !(defined(REDUNDANT_PULLUP_RESISTOR_OHMS) && defined(REDUNDANT_RESISTANCE_25C_OHMS) && defined(REDUNDANT_BETA)) + #error "TEMP_SENSOR_REDUNDANT 1000 requires REDUNDANT_PULLUP_RESISTOR_OHMS, REDUNDANT_RESISTANCE_25C_OHMS and REDUNDANT_BETA in Configuration_adv.h." #endif /** * Pins and Sensor IDs must be set for each heater */ #if TEMP_SENSOR_0_IS_MAX6675 && !ANY_PIN(MAX6675_SS, MAX31855_CS, MAX31865_CS, MAX6675_CS) - #error "TEMP_SENSOR_0 requires a MAX6675_SS_PIN, MAX6675_CS_PIN, MAX31855_CS_PIN, or MAX31865_CS_PIN." + #error "TEMP_SENSOR_0 -2 requires a MAX6675_SS_PIN, MAX6675_CS_PIN, MAX31855_CS_PIN, or MAX31865_CS_PIN." #elif HAS_HOTEND && !HAS_TEMP_HOTEND && !TEMP_SENSOR_0_IS_DUMMY #error "TEMP_0_PIN (required for TEMP_SENSOR_0) not defined for this board." #elif EITHER(HAS_MULTI_HOTEND, HEATERS_PARALLEL) && !HAS_HEATER_1 #error "HEATER_1_PIN is not defined. TEMP_SENSOR_1 might not be set, or the board (not EEB / EEF?) doesn't define a pin." #endif +/** + * Redundant temperature sensor config + */ +#if HAS_TEMP_REDUNDANT + #if !defined(TEMP_SENSOR_REDUNDANT_SOURCE) + #error "TEMP_SENSOR_REDUNDANT requires TEMP_SENSOR_REDUNDANT_SOURCE." + #elif !defined(TEMP_SENSOR_REDUNDANT_TARGET) + #error "TEMP_SENSOR_REDUNDANT requires TEMP_SENSOR_REDUNDANT_TARGET." + #elif TEMP_SENSOR_REDUNDANT_SOURCE == TEMP_SENSOR_REDUNDANT_TARGET + #error "TEMP_SENSOR_REDUNDANT_SOURCE can't be the same as TEMP_SENSOR_REDUNDANT_TARGET." + #elif TEMP_SENSOR_REDUNDANT_SOURCE < -5 || TEMP_SENSOR_REDUNDANT_SOURCE > 7 + #error "TEMP_SENSOR_REDUNDANT_SOURCE must be between -5 and 7." + #elif TEMP_SENSOR_REDUNDANT_TARGET < -5 || TEMP_SENSOR_REDUNDANT_TARGET > 7 + #error "TEMP_SENSOR_REDUNDANT_TARGET must be between -5 and 7." + #elif TEMP_SENSOR_REDUNDANT_SOURCE == -3 + #error "TEMP_SENSOR_REDUNDANT_SOURCE can't be -3 (not used)." + #elif TEMP_SENSOR_REDUNDANT_TARGET == -3 + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be -3 (not used)." + #elif HAS_MULTI_HOTEND && TEMP_SENSOR_REDUNDANT_SOURCE < HOTENDS + #error "TEMP_SENSOR_REDUNDANT_SOURCE must be after the last TEMP_SENSOR used with a hotend; you can't use a sensor in the middle of two hotends." + #endif + + #if TEMP_SENSOR_REDUNDANT_SOURCE == 0 && HAS_HOTEND + #error "TEMP_SENSOR_REDUNDANT_SOURCE can not be 0 if a hotend is used. E0 always uses TEMP_SENSOR_0." + #elif TEMP_SENSOR_REDUNDANT_SOURCE == -5 && HAS_TEMP_COOLER + #error "TEMP_SENSOR_REDUNDANT_SOURCE can't be Cooler (-5): TEMP_SENSOR_COOLER has already defined the sensor." + #elif TEMP_SENSOR_REDUNDANT_SOURCE == -4 && HAS_TEMP_PROBE + #error "TEMP_SENSOR_REDUNDANT_SOURCE can't be Probe (-4): TEMP_SENSOR_PROBE has already defined the sensor." + #elif TEMP_SENSOR_REDUNDANT_SOURCE == -2 && HAS_TEMP_CHAMBER + #error "TEMP_SENSOR_REDUNDANT_SOURCE can't be Chamber (-2): TEMP_SENSOR_CHAMBER has already defined the sensor." + #elif TEMP_SENSOR_REDUNDANT_SOURCE == -1 && HAS_TEMP_BED + #error "TEMP_SENSOR_REDUNDANT_SOURCE can't be Bed (-1): TEMP_SENSOR_BED has already defined the sensor." + #endif + + #if TEMP_SENSOR_REDUNDANT_TARGET == 0 && !PIN_EXISTS(TEMP_0) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E0 (0): requires TEMP_0_PIN" + #elif TEMP_SENSOR_REDUNDANT_TARGET == 1 && !PIN_EXISTS(TEMP_1) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E1 (1): requires TEMP_1_PIN" + #elif TEMP_SENSOR_REDUNDANT_TARGET == 2 && !PIN_EXISTS(TEMP_2) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E2 (2): requires TEMP_2_PIN" + #elif TEMP_SENSOR_REDUNDANT_TARGET == 3 && !PIN_EXISTS(TEMP_3) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E3 (3): requires TEMP_3_PIN" + #elif TEMP_SENSOR_REDUNDANT_TARGET == 4 && !PIN_EXISTS(TEMP_4) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E4 (4): requires TEMP_4_PIN" + #elif TEMP_SENSOR_REDUNDANT_TARGET == 5 && !PIN_EXISTS(TEMP_5) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E5 (5): requires TEMP_5_PIN" + #elif TEMP_SENSOR_REDUNDANT_TARGET == 6 && !PIN_EXISTS(TEMP_6) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E6 (6): requires TEMP_6_PIN" + #elif TEMP_SENSOR_REDUNDANT_TARGET == 7 && !PIN_EXISTS(TEMP_7) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be E7 (7): requires TEMP_7_PIN" + #elif TEMP_SENSOR_REDUNDANT_TARGET == -1 && !PIN_EXISTS(TEMP_BED) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be Bed (-1): requires TEMP_BED_PIN" + #elif TEMP_SENSOR_REDUNDANT_TARGET == -2 && !PIN_EXISTS(TEMP_CHAMBER) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be Chamber (-2): requires TEMP_CHAMBER_PIN" + #elif TEMP_SENSOR_REDUNDANT_TARGET == -4 && !PIN_EXISTS(TEMP_PROBE) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be Probe (-4): requires TEMP_PROBE_PIN" + #elif TEMP_SENSOR_REDUNDANT_TARGET == -5 && !PIN_EXISTS(TEMP_COOLER) + #error "TEMP_SENSOR_REDUNDANT_TARGET can't be Cooler (-5): requires TEMP_COOLER_PIN" + #endif + + #if TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 0 && !PIN_EXISTS(MAX6675_SS) + #error "TEMP_SENSOR_REDUNDANT MAX Thermocouple with TEMP_SENSOR_REDUNDANT_SOURCE 0 requires a MAX6675_SS_PIN, MAX6675_CS_PIN, MAX31855_CS_PIN, or MAX31865_CS_PIN." + #elif TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 1 && !PIN_EXISTS(MAX6675_SS2) + #error "TEMP_SENSOR_REDUNDANT MAX Thermocouple with TEMP_SENSOR_REDUNDANT_SOURCE 1 requires a MAX6675_SS2_PIN, MAX6675_CS_PIN, MAX31855_CS_PIN, or MAX31865_CS_PIN." + #endif +#endif + #if HAS_MULTI_HOTEND #if TEMP_SENSOR_1_IS_MAX6675 && !ANY_PIN(MAX6675_SS2, MAX31855_CS2, MAX31865_CS2, MAX6675_CS2) #error "TEMP_SENSOR_1 requires a MAX6675_SS2_PIN, MAX6675_CS2_PIN, MAX31855_CS2_PIN, or MAX31865_CS2_PIN." @@ -1798,8 +2037,6 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #error "TEMP_SENSOR_1 is required with 2 or more HOTENDS." #elif !ANY_PIN(TEMP_1, MAX6675_SS2) && !TEMP_SENSOR_1_IS_DUMMY #error "TEMP_1_PIN or MAX6675_SS2_PIN not defined for this board." - #elif ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - #error "HOTENDS must be 1 with TEMP_SENSOR_1_AS_REDUNDANT." #endif #if HOTENDS > 2 #if TEMP_SENSOR_2 == 0 @@ -1897,7 +2134,7 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #elif TEMP_SENSOR_7 != 0 #error "TEMP_SENSOR_7 shouldn't be set with only 2 HOTENDS." #endif -#elif TEMP_SENSOR_1 != 0 && DISABLED(TEMP_SENSOR_1_AS_REDUNDANT) +#elif TEMP_SENSOR_1 != 0 #error "TEMP_SENSOR_1 shouldn't be set with only 1 HOTEND." #elif TEMP_SENSOR_2 != 0 #error "TEMP_SENSOR_2 shouldn't be set with only 1 HOTEND." @@ -1959,14 +2196,10 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #endif #endif -#if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) && TEMP_SENSOR_1 == 0 - #error "TEMP_SENSOR_1 is required with TEMP_SENSOR_1_AS_REDUNDANT." -#endif - -#if TEMP_SENSOR_0_IS_MAX31865 && !(defined(MAX31865_SENSOR_OHMS_0) && defined(MAX31865_CALIBRATION_OHMS_0)) - #error "MAX31865_SENSOR_OHMS_0 and MAX31865_CALIBRATION_OHMS_0 must be set if TEMP_SENSOR_0 is MAX31865." -#elif TEMP_SENSOR_1_IS_MAX31865 && !(defined(MAX31865_SENSOR_OHMS_1) && defined(MAX31865_CALIBRATION_OHMS_1)) - #error "MAX31865_SENSOR_OHMS_1 and MAX31865_CALIBRATION_OHMS_1 must be set if TEMP_SENSOR_1 is MAX31865." +#if TEMP_SENSOR_IS_MAX(0, MAX31865) && !(defined(MAX31865_SENSOR_OHMS_0) && defined(MAX31865_CALIBRATION_OHMS_0)) + #error "MAX31865_SENSOR_OHMS_0 and MAX31865_CALIBRATION_OHMS_0 must be set if TEMP_SENSOR_0/TEMP_SENSOR_REDUNDANT is MAX31865." +#elif TEMP_SENSOR_IS_MAX(1, MAX31865) && !(defined(MAX31865_SENSOR_OHMS_1) && defined(MAX31865_CALIBRATION_OHMS_1)) + #error "MAX31865_SENSOR_OHMS_1 and MAX31865_CALIBRATION_OHMS_1 must be set if TEMP_SENSOR_1/TEMP_SENSOR_REDUNDANT is MAX31865." #endif /** @@ -1976,12 +2209,16 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #error "HEATER_0_PIN not defined for this board." #elif !ANY_PIN(TEMP_0, MAX6675_SS) #error "TEMP_0_PIN or MAX6675_SS not defined for this board." -#elif ((defined(__AVR_ATmega644P__) || defined(__AVR_ATmega1284P__)) && !PINS_EXIST(E0_STEP, E0_DIR)) - #error "E0_STEP_PIN or E0_DIR_PIN not defined for this board." -#elif ( !(defined(__AVR_ATmega644P__) || defined(__AVR_ATmega1284P__)) && (!PINS_EXIST(E0_STEP, E0_DIR) || !HAS_E0_ENABLE)) - #error "E0_STEP_PIN, E0_DIR_PIN, or E0_ENABLE_PIN not defined for this board." -#elif EXTRUDERS && TEMP_SENSOR_0 == 0 - #error "TEMP_SENSOR_0 is required if there are any extruders." +#endif + +#if HAS_EXTRUDERS + #if ((defined(__AVR_ATmega644P__) || defined(__AVR_ATmega1284P__)) && !PINS_EXIST(E0_STEP, E0_DIR)) + #error "E0_STEP_PIN or E0_DIR_PIN not defined for this board." + #elif ( !(defined(__AVR_ATmega644P__) || defined(__AVR_ATmega1284P__)) && (!PINS_EXIST(E0_STEP, E0_DIR) || !HAS_E0_ENABLE)) + #error "E0_STEP_PIN, E0_DIR_PIN, or E0_ENABLE_PIN not defined for this board." + #elif EXTRUDERS && TEMP_SENSOR_0 == 0 + #error "TEMP_SENSOR_0 is required if there are any extruders." + #endif #endif /** @@ -2073,7 +2310,7 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #define _PLUG_UNUSED_TEST(A,P) (DISABLED(USE_##P##MIN_PLUG, USE_##P##MAX_PLUG) \ && !(ENABLED(A##_DUAL_ENDSTOPS) && WITHIN(A##2_USE_ENDSTOP, _##P##MAX_, _##P##MIN_)) \ && !(ENABLED(A##_MULTI_ENDSTOPS) && WITHIN(A##2_USE_ENDSTOP, _##P##MAX_, _##P##MIN_)) ) -#define _AXIS_PLUG_UNUSED_TEST(A) (_PLUG_UNUSED_TEST(A,X) && _PLUG_UNUSED_TEST(A,Y) && _PLUG_UNUSED_TEST(A,Z)) +#define _AXIS_PLUG_UNUSED_TEST(A) (1 LINEAR_AXIS_GANG(&& _PLUG_UNUSED_TEST(A,X), && _PLUG_UNUSED_TEST(A,Y), && _PLUG_UNUSED_TEST(A,Z), && _PLUG_UNUSED_TEST(A,I), && _PLUG_UNUSED_TEST(A,J), && _PLUG_UNUSED_TEST(A,K) ) ) // A machine with endstops must have a minimum of 3 #if HAS_ENDSTOPS @@ -2086,6 +2323,15 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #if _AXIS_PLUG_UNUSED_TEST(Z) #error "You must enable USE_ZMIN_PLUG or USE_ZMAX_PLUG." #endif + #if LINEAR_AXES >= 4 && _AXIS_PLUG_UNUSED_TEST(I) + #error "You must enable USE_IMIN_PLUG or USE_IMAX_PLUG." + #endif + #if LINEAR_AXES >= 5 && _AXIS_PLUG_UNUSED_TEST(J) + #error "You must enable USE_JMIN_PLUG or USE_JMAX_PLUG." + #endif + #if LINEAR_AXES >= 6 && _AXIS_PLUG_UNUSED_TEST(K) + #error "You must enable USE_KMIN_PLUG or USE_KMAX_PLUG." + #endif // Delta and Cartesian use 3 homing endstops #if NONE(IS_SCARA, SPI_ENDSTOPS) @@ -2097,6 +2343,18 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #error "Enable USE_YMIN_PLUG when homing Y to MIN." #elif Y_HOME_TO_MAX && DISABLED(USE_YMAX_PLUG) #error "Enable USE_YMAX_PLUG when homing Y to MAX." + #elif LINEAR_AXES >= 4 && I_HOME_TO_MIN && DISABLED(USE_IMIN_PLUG) + #error "Enable USE_IMIN_PLUG when homing I to MIN." + #elif LINEAR_AXES >= 4 && I_HOME_TO_MAX && DISABLED(USE_IMAX_PLUG) + #error "Enable USE_IMAX_PLUG when homing I to MAX." + #elif LINEAR_AXES >= 5 && J_HOME_TO_MIN && DISABLED(USE_JMIN_PLUG) + #error "Enable USE_JMIN_PLUG when homing J to MIN." + #elif LINEAR_AXES >= 5 && J_HOME_TO_MAX && DISABLED(USE_JMAX_PLUG) + #error "Enable USE_JMAX_PLUG when homing J to MAX." + #elif LINEAR_AXES >= 6 && K_HOME_TO_MIN && DISABLED(USE_KMIN_PLUG) + #error "Enable USE_KMIN_PLUG when homing K to MIN." + #elif LINEAR_AXES >= 6 && K_HOME_TO_MAX && DISABLED(USE_KMAX_PLUG) + #error "Enable USE_KMAX_PLUG when homing K to MAX." #endif #endif @@ -2491,6 +2749,12 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #error "An SPI driven TMC driver on E6 requires E6_CS_PIN." #elif INVALID_TMC_SPI(E7) #error "An SPI driven TMC driver on E7 requires E7_CS_PIN." +#elif INVALID_TMC_SPI(I) + #error "An SPI driven TMC on I requires I_CS_PIN." +#elif INVALID_TMC_SPI(J) + #error "An SPI driven TMC on J requires J_CS_PIN." +#elif INVALID_TMC_SPI(K) + #error "An SPI driven TMC on K requires K_CS_PIN." #endif #undef INVALID_TMC_SPI @@ -2530,6 +2794,12 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #error "TMC2208 or TMC2209 on E6 requires E6_HARDWARE_SERIAL or E6_SERIAL_(RX|TX)_PIN." #elif INVALID_TMC_UART(E7) #error "TMC2208 or TMC2209 on E7 requires E7_HARDWARE_SERIAL or E7_SERIAL_(RX|TX)_PIN." +#elif LINEAR_AXES >= 4 && INVALID_TMC_UART(I) + #error "TMC2208 or TMC2209 on I requires I_HARDWARE_SERIAL or I_SERIAL_(RX|TX)_PIN." +#elif LINEAR_AXES >= 5 && INVALID_TMC_UART(J) + #error "TMC2208 or TMC2209 on J requires J_HARDWARE_SERIAL or J_SERIAL_(RX|TX)_PIN." +#elif LINEAR_AXES >= 6 && INVALID_TMC_UART(K) + #error "TMC2208 or TMC2209 on K requires K_HARDWARE_SERIAL or K_SERIAL_(RX|TX)_PIN." #endif #undef INVALID_TMC_UART @@ -2553,6 +2823,12 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal INVALID_TMC_ADDRESS(Z3); #elif AXIS_DRIVER_TYPE_Z4(TMC2209) INVALID_TMC_ADDRESS(Z4); +#elif AXIS_DRIVER_TYPE_I(TMC2209) + INVALID_TMC_ADDRESS(I); +#elif AXIS_DRIVER_TYPE_J(TMC2209) + INVALID_TMC_ADDRESS(J); +#elif AXIS_DRIVER_TYPE_K(TMC2209) + INVALID_TMC_ADDRESS(K); #elif AXIS_DRIVER_TYPE_E0(TMC2209) INVALID_TMC_ADDRESS(E0); #elif AXIS_DRIVER_TYPE_E1(TMC2209) @@ -2608,6 +2884,12 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal INVALID_TMC_MS(E6) #elif !TMC_MICROSTEP_IS_VALID(E7) INVALID_TMC_MS(E7) +#elif LINEAR_AXES >= 4 && !TMC_MICROSTEP_IS_VALID(I) + INVALID_TMC_MS(I) +#elif LINEAR_AXES >= 5 && !TMC_MICROSTEP_IS_VALID(J) + INVALID_TMC_MS(J) +#elif LINEAR_AXES >= 6 && !TMC_MICROSTEP_IS_VALID(K) + INVALID_TMC_MS(K) #endif #undef INVALID_TMC_MS #undef TMC_MICROSTEP_IS_VALID @@ -2628,6 +2910,15 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #define X_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(X,TMC2209) #define Y_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(Y,TMC2209) #define Z_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(Z,TMC2209) + #if LINEAR_AXES >= 4 + #define I_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(I,TMC2209) + #endif + #if LINEAR_AXES >= 5 + #define J_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(J,TMC2209) + #endif + #if LINEAR_AXES >= 6 + #define K_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(K,TMC2209) + #endif #if NONE(SPI_ENDSTOPS, ONBOARD_ENDSTOPPULLUPS, ENDSTOPPULLUPS) #if X_SENSORLESS && X_HOME_TO_MIN && DISABLED(ENDSTOPPULLUP_XMIN) @@ -2642,6 +2933,12 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_ZMIN (or ENDSTOPPULLUPS) when homing to Z_MIN." #elif Z_SENSORLESS && Z_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_ZMAX) #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_ZMAX (or ENDSTOPPULLUPS) when homing to Z_MAX." + #elif LINEAR_AXES >= 4 && I_SENSORLESS && I_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_IMAX) + #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_IMAX (or ENDSTOPPULLUPS) when homing to I_MAX." + #elif LINEAR_AXES >= 5 && J_SENSORLESS && J_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_JMAX) + #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_JMAX (or ENDSTOPPULLUPS) when homing to J_MAX." + #elif LINEAR_AXES >= 6 && K_SENSORLESS && K_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_KMAX) + #error "SENSORLESS_HOMING requires ENDSTOPPULLUP_KMAX (or ENDSTOPPULLUPS) when homing to K_MAX." #endif #endif @@ -2686,6 +2983,42 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #else #error "SENSORLESS_HOMING requires Z_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to Z_MAX." #endif + #elif LINEAR_AXES >= 4 && I_SENSORLESS && I_HOME_TO_MIN && I_MIN_ENDSTOP_INVERTING != I_ENDSTOP_INVERTING + #if I_ENDSTOP_INVERTING + #error "SENSORLESS_HOMING requires I_MIN_ENDSTOP_INVERTING = true when homing to I_MIN." + #else + #error "SENSORLESS_HOMING requires I_MIN_ENDSTOP_INVERTING = false when homing TMC2209 to I_MIN." + #endif + #elif LINEAR_AXES >= 4 && I_SENSORLESS && I_HOME_TO_MAX && I_MAX_ENDSTOP_INVERTING != I_ENDSTOP_INVERTING + #if I_ENDSTOP_INVERTING + #error "SENSORLESS_HOMING requires I_MAX_ENDSTOP_INVERTING = true when homing to I_MAX." + #else + #error "SENSORLESS_HOMING requires I_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to I_MAX." + #endif + #elif LINEAR_AXES >= 5 && J_SENSORLESS && J_HOME_TO_MIN && J_MIN_ENDSTOP_INVERTING != J_ENDSTOP_INVERTING + #if J_ENDSTOP_INVERTING + #error "SENSORLESS_HOMING requires J_MIN_ENDSTOP_INVERTING = true when homing to J_MIN." + #else + #error "SENSORLESS_HOMING requires J_MIN_ENDSTOP_INVERTING = false when homing TMC2209 to J_MIN." + #endif + #elif LINEAR_AXES >= 5 && J_SENSORLESS && J_HOME_TO_MAX && J_MAX_ENDSTOP_INVERTING != J_ENDSTOP_INVERTING + #if J_ENDSTOP_INVERTING + #error "SENSORLESS_HOMING requires J_MAX_ENDSTOP_INVERTING = true when homing to J_MAX." + #else + #error "SENSORLESS_HOMING requires J_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to J_MAX." + #endif + #elif LINEAR_AXES >= 6 && K_SENSORLESS && K_HOME_TO_MIN && K_MIN_ENDSTOP_INVERTING != K_ENDSTOP_INVERTING + #if K_ENDSTOP_INVERTING + #error "SENSORLESS_HOMING requires K_MIN_ENDSTOP_INVERTING = true when homing to K_MIN." + #else + #error "SENSORLESS_HOMING requires K_MIN_ENDSTOP_INVERTING = false when homing TMC2209 to K_MIN." + #endif + #elif LINEAR_AXES >= 6 && K_SENSORLESS && K_HOME_TO_MAX && K_MAX_ENDSTOP_INVERTING != K_ENDSTOP_INVERTING + #if K_ENDSTOP_INVERTING + #error "SENSORLESS_HOMING requires K_MAX_ENDSTOP_INVERTING = true when homing to K_MAX." + #else + #error "SENSORLESS_HOMING requires K_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to K_MAX." + #endif #endif #endif @@ -2700,6 +3033,9 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #undef X_ENDSTOP_INVERTING #undef Y_ENDSTOP_INVERTING #undef Z_ENDSTOP_INVERTING + #undef I_ENDSTOP_INVERTING + #undef J_ENDSTOP_INVERTING + #undef K_ENDSTOP_INVERTING #endif // Sensorless probing requirements @@ -2762,6 +3098,12 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #define CS_COMPARE Z2_CS_PIN #elif IN_CHAIN(Z3) #define CS_COMPARE Z3_CS_PIN + #elif IN_CHAIN(I) + #define CS_COMPARE I_CS_PIN + #elif IN_CHAIN(J) + #define CS_COMPARE J_CS_PIN + #elif IN_CHAIN(K) + #define CS_COMPARE K_CS_PIN #elif IN_CHAIN(E0) #define CS_COMPARE E0_CS_PIN #elif IN_CHAIN(E1) @@ -2781,6 +3123,7 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #endif #define BAD_CS_PIN(A) (IN_CHAIN(A) && A##_CS_PIN != CS_COMPARE) #if BAD_CS_PIN(X ) || BAD_CS_PIN(Y ) || BAD_CS_PIN(Z ) || BAD_CS_PIN(X2) || BAD_CS_PIN(Y2) || BAD_CS_PIN(Z2) || BAD_CS_PIN(Z3) || BAD_CS_PIN(Z4) \ + || BAD_CS_PIN(I) || BAD_CS_PIN(J) || BAD_CS_PIN(K) \ || BAD_CS_PIN(E0) || BAD_CS_PIN(E1) || BAD_CS_PIN(E2) || BAD_CS_PIN(E3) || BAD_CS_PIN(E4) || BAD_CS_PIN(E5) || BAD_CS_PIN(E6) || BAD_CS_PIN(E7) #error "All chained TMC drivers must use the same CS pin." #endif @@ -2791,6 +3134,13 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #endif #undef IN_CHAIN +/** + * L64XX requirement + */ +#if HAS_L64XX && LINEAR_AXES >= 4 + #error "L64XX requires LINEAR_AXES 3. Homing with L64XX is not yet implemented for LINEAR_AXES > 3." +#endif + /** * Digipot requirement */ @@ -2808,43 +3158,48 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal */ constexpr float sanity_arr_1[] = DEFAULT_AXIS_STEPS_PER_UNIT, sanity_arr_2[] = DEFAULT_MAX_FEEDRATE, - sanity_arr_3[] = DEFAULT_MAX_ACCELERATION; + sanity_arr_3[] = DEFAULT_MAX_ACCELERATION, + sanity_arr_7[] = HOMING_FEEDRATE_MM_M; #define _ARR_TEST(N,I) (sanity_arr_##N[_MIN(I,int(COUNT(sanity_arr_##N))-1)] > 0) #if HAS_MULTI_EXTRUDER #define _EXTRA_NOTE " (Did you forget to enable DISTINCT_E_FACTORS?)" -#elif EXTRUDERS == 0 - #define _EXTRA_NOTE " (Note: EXTRUDERS is set to 0.)" #else - #define _EXTRA_NOTE "" + #define _EXTRA_NOTE " (Should be " STRINGIFY(LINEAR_AXES) "+" STRINGIFY(E_STEPPERS) ")" #endif -static_assert(COUNT(sanity_arr_1) >= LOGICAL_AXES, "DEFAULT_AXIS_STEPS_PER_UNIT requires X, Y, Z and E elements."); +static_assert(COUNT(sanity_arr_1) >= LOGICAL_AXES, "DEFAULT_AXIS_STEPS_PER_UNIT requires " _LOGICAL_AXES_STR "elements."); static_assert(COUNT(sanity_arr_1) <= DISTINCT_AXES, "DEFAULT_AXIS_STEPS_PER_UNIT has too many elements." _EXTRA_NOTE); static_assert( _ARR_TEST(1,0) && _ARR_TEST(1,1) && _ARR_TEST(1,2) && _ARR_TEST(1,3) && _ARR_TEST(1,4) && _ARR_TEST(1,5) && _ARR_TEST(1,6) && _ARR_TEST(1,7) && _ARR_TEST(1,8), "DEFAULT_AXIS_STEPS_PER_UNIT values must be positive."); -static_assert(COUNT(sanity_arr_2) >= LOGICAL_AXES, "DEFAULT_MAX_FEEDRATE requires X, Y, Z and E elements."); +static_assert(COUNT(sanity_arr_2) >= LOGICAL_AXES, "DEFAULT_MAX_FEEDRATE requires " _LOGICAL_AXES_STR "elements."); static_assert(COUNT(sanity_arr_2) <= DISTINCT_AXES, "DEFAULT_MAX_FEEDRATE has too many elements." _EXTRA_NOTE); static_assert( _ARR_TEST(2,0) && _ARR_TEST(2,1) && _ARR_TEST(2,2) && _ARR_TEST(2,3) && _ARR_TEST(2,4) && _ARR_TEST(2,5) && _ARR_TEST(2,6) && _ARR_TEST(2,7) && _ARR_TEST(2,8), "DEFAULT_MAX_FEEDRATE values must be positive."); -static_assert(COUNT(sanity_arr_3) >= LOGICAL_AXES, "DEFAULT_MAX_ACCELERATION requires X, Y, Z and E elements."); +static_assert(COUNT(sanity_arr_3) >= LOGICAL_AXES, "DEFAULT_MAX_ACCELERATION requires " _LOGICAL_AXES_STR "elements."); static_assert(COUNT(sanity_arr_3) <= DISTINCT_AXES, "DEFAULT_MAX_ACCELERATION has too many elements." _EXTRA_NOTE); static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) && _ARR_TEST(3,3) && _ARR_TEST(3,4) && _ARR_TEST(3,5) && _ARR_TEST(3,6) && _ARR_TEST(3,7) && _ARR_TEST(3,8), "DEFAULT_MAX_ACCELERATION values must be positive."); +static_assert(COUNT(sanity_arr_7) == LINEAR_AXES, "HOMING_FEEDRATE_MM_M requires " _LINEAR_AXES_STR "elements (and no others)."); +static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) + && _ARR_TEST(3,3) && _ARR_TEST(3,4) && _ARR_TEST(3,5) + && _ARR_TEST(3,6) && _ARR_TEST(3,7) && _ARR_TEST(3,8), + "HOMING_FEEDRATE_MM_M values must be positive."); + #if ENABLED(LIMITED_MAX_ACCEL_EDITING) #ifdef MAX_ACCEL_EDIT_VALUES constexpr float sanity_arr_4[] = MAX_ACCEL_EDIT_VALUES; - static_assert(COUNT(sanity_arr_4) >= LOGICAL_AXES, "MAX_ACCEL_EDIT_VALUES requires X, Y, Z and E elements."); - static_assert(COUNT(sanity_arr_4) <= LOGICAL_AXES, "MAX_ACCEL_EDIT_VALUES has too many elements. X, Y, Z and E elements only."); + static_assert(COUNT(sanity_arr_4) >= LOGICAL_AXES, "MAX_ACCEL_EDIT_VALUES requires " _LOGICAL_AXES_STR "elements."); + static_assert(COUNT(sanity_arr_4) <= LOGICAL_AXES, "MAX_ACCEL_EDIT_VALUES has too many elements. " _LOGICAL_AXES_STR "elements only."); static_assert( _ARR_TEST(4,0) && _ARR_TEST(4,1) && _ARR_TEST(4,2) && _ARR_TEST(4,3) && _ARR_TEST(4,4) && _ARR_TEST(4,5) && _ARR_TEST(4,6) && _ARR_TEST(4,7) && _ARR_TEST(4,8), @@ -2855,8 +3210,8 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #if ENABLED(LIMITED_MAX_FR_EDITING) #ifdef MAX_FEEDRATE_EDIT_VALUES constexpr float sanity_arr_5[] = MAX_FEEDRATE_EDIT_VALUES; - static_assert(COUNT(sanity_arr_5) >= LOGICAL_AXES, "MAX_FEEDRATE_EDIT_VALUES requires X, Y, Z and E elements."); - static_assert(COUNT(sanity_arr_5) <= LOGICAL_AXES, "MAX_FEEDRATE_EDIT_VALUES has too many elements. X, Y, Z and E elements only."); + static_assert(COUNT(sanity_arr_5) >= LOGICAL_AXES, "MAX_FEEDRATE_EDIT_VALUES requires " _LOGICAL_AXES_STR "elements."); + static_assert(COUNT(sanity_arr_5) <= LOGICAL_AXES, "MAX_FEEDRATE_EDIT_VALUES has too many elements. " _LOGICAL_AXES_STR "elements only."); static_assert( _ARR_TEST(5,0) && _ARR_TEST(5,1) && _ARR_TEST(5,2) && _ARR_TEST(5,3) && _ARR_TEST(5,4) && _ARR_TEST(5,5) && _ARR_TEST(5,6) && _ARR_TEST(5,7) && _ARR_TEST(5,8), @@ -2867,8 +3222,8 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #if ENABLED(LIMITED_JERK_EDITING) #ifdef MAX_JERK_EDIT_VALUES constexpr float sanity_arr_6[] = MAX_JERK_EDIT_VALUES; - static_assert(COUNT(sanity_arr_6) >= LOGICAL_AXES, "MAX_JERK_EDIT_VALUES requires X, Y, Z and E elements."); - static_assert(COUNT(sanity_arr_6) <= LOGICAL_AXES, "MAX_JERK_EDIT_VALUES has too many elements. X, Y, Z and E elements only."); + static_assert(COUNT(sanity_arr_6) >= LOGICAL_AXES, "MAX_JERK_EDIT_VALUES requires " _LOGICAL_AXES_STR "elements."); + static_assert(COUNT(sanity_arr_6) <= LOGICAL_AXES, "MAX_JERK_EDIT_VALUES has too many elements. " _LOGICAL_AXES_STR "elements only."); static_assert( _ARR_TEST(6,0) && _ARR_TEST(6,1) && _ARR_TEST(6,2) && _ARR_TEST(6,3) && _ARR_TEST(6,4) && _ARR_TEST(6,5) && _ARR_TEST(6,6) && _ARR_TEST(6,7) && _ARR_TEST(6,8), @@ -2947,6 +3302,10 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #error "MECHANICAL_GANTRY_CALIBRATION Requires GANTRY_CALIBRATION_EXTRA_HEIGHT to be set." #elif !defined(GANTRY_CALIBRATION_FEEDRATE) #error "MECHANICAL_GANTRY_CALIBRATION Requires GANTRY_CALIBRATION_FEEDRATE to be set." + #elif ENABLED(Z_MULTI_ENDSTOPS) + #error "Sorry! MECHANICAL_GANTRY_CALIBRATION cannot be used with Z_MULTI_ENDSTOPS." + #elif ENABLED(Z_STEPPER_AUTO_ALIGN) + #error "Sorry! MECHANICAL_GANTRY_CALIBRATION cannot be used with Z_STEPPER_AUTO_ALIGN." #endif #if defined(GANTRY_CALIBRATION_SAFE_POSITION) && !defined(GANTRY_CALIBRATION_XY_PARK_FEEDRATE) #error "GANTRY_CALIBRATION_SAFE_POSITION Requires GANTRY_CALIBRATION_XY_PARK_FEEDRATE to be set." @@ -3229,6 +3588,13 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #error "Either enable MEATPACK_ON_SERIAL_PORT_* or BINARY_FILE_TRANSFER, not both." #endif +/** + * Sanity Check for Slim LCD Menus and Probe Offset Wizard + */ +#if BOTH(SLIM_LCD_MENUS, PROBE_OFFSET_WIZARD) + #error "SLIM_LCD_MENUS disables \"Advanced Settings > Probe Offsets > PROBE_OFFSET_WIZARD.\"" +#endif + /** * Sanity check for unique start and stop values in NOZZLE_CLEAN_FEATURE */ @@ -3264,6 +3630,22 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) #if _BAD_DRIVER(Z) #error "Z_DRIVER_TYPE is not recognized." #endif +#if LINEAR_AXES >= 4 + #if _BAD_DRIVER(I) + #error "I_DRIVER_TYPE is not recognized." + #endif +#endif +#if LINEAR_AXES >= 5 + #if _BAD_DRIVER(J) + #error "J_DRIVER_TYPE is not recognized." + #endif +#endif +#if LINEAR_AXES >= 6 + #if _BAD_DRIVER(K) + #error "K_DRIVER_TYPE is not recognized." + #endif +#endif + #if _BAD_DRIVER(X2) #error "X2_DRIVER_TYPE is not recognized." #endif @@ -3307,7 +3689,5 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2) // Misc. Cleanup #undef _TEST_PWM - -#if ENABLED(FREEZE_FEATURE) && !PIN_EXISTS(FREEZE) - #error "FREEZE_FEATURE requires a FREEZE_PIN to be defined." -#endif +#undef _LINEAR_AXES_STR +#undef _LOGICAL_AXES_STR diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 6baa52dd3dff3..47faf32aad687 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -25,7 +25,7 @@ * Release version. Leave the Marlin version or apply a custom scheme. */ #ifndef SHORT_BUILD_VERSION - #define SHORT_BUILD_VERSION "2.0.8.1" + #define SHORT_BUILD_VERSION "2.0.9.1" #endif /** @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2021-05-15" + #define STRING_DISTRIBUTION_DATE "2021-06-27" #endif /** @@ -52,7 +52,7 @@ * to alert users to major changes. */ -#define MARLIN_HEX_VERSION 02000801 +#define MARLIN_HEX_VERSION 02000901 #ifndef REQUIRED_CONFIGURATION_H_VERSION #define REQUIRED_CONFIGURATION_H_VERSION MARLIN_HEX_VERSION #endif diff --git a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp index 50c80c9fa074f..0c87c3dc3fa1e 100644 --- a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp +++ b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp @@ -50,6 +50,10 @@ #include "../../feature/cooler.h" #endif +#if ENABLED(I2C_AMMETER) + #include "../../feature/ammeter.h" +#endif + #if ENABLED(AUTO_BED_LEVELING_UBL) #include "../../feature/bedlevel/bedlevel.h" #endif @@ -64,11 +68,7 @@ #elif EITHER(LCD_I2C_TYPE_MCP23017, LCD_I2C_TYPE_MCP23008) - LCD_CLASS lcd(LCD_I2C_ADDRESS - #ifdef DETECT_DEVICE - , 1 - #endif - ); + LCD_CLASS lcd(LCD_I2C_ADDRESS OPTARG(DETECT_I2C_LCD_DEVICE, 1)); #elif ENABLED(LCD_I2C_TYPE_PCA8574) @@ -376,11 +376,7 @@ void MarlinUI::init_lcd() { } bool MarlinUI::detected() { - return (true - #if EITHER(LCD_I2C_TYPE_MCP23017, LCD_I2C_TYPE_MCP23008) && defined(DETECT_DEVICE) - && lcd.LcdDetected() == 1 - #endif - ); + return TERN1(DETECT_I2C_LCD_DEVICE, lcd.LcdDetected() == 1); } #if HAS_SLOW_BUTTONS @@ -588,12 +584,27 @@ FORCE_INLINE void _draw_cooler_status(const char prefix, const bool blink) { #if ENABLED(LASER_COOLANT_FLOW_METER) FORCE_INLINE void _draw_flowmeter_status() { - lcd_put_u8str("~ "); + lcd_put_u8str("~"); lcd_put_u8str(ftostr11ns(cooler.flowrate)); lcd_put_wchar('L'); } #endif +#if ENABLED(I2C_AMMETER) + FORCE_INLINE void _draw_ammeter_status() { + lcd_put_u8str(" "); + ammeter.read(); + if (ammeter.current <= 0.999f) { + lcd_put_u8str(ui16tostr3rj(uint16_t(ammeter.current * 1000 + 0.5f))); + lcd_put_u8str("mA"); + } + else { + lcd_put_u8str(ftostr12ns(ammeter.current)); + lcd_put_wchar('A'); + } + } +#endif + FORCE_INLINE void _draw_bed_status(const bool blink) { _draw_heater_status(H_BED, TERN0(HAS_LEVELING, blink && planner.leveling_active) ? '_' : LCD_STR_BEDTEMP[0], blink); } @@ -829,12 +840,9 @@ void MarlinUI::draw_status_screen() { #endif #endif - #if HAS_COOLER - _draw_cooler_status('*', blink); - #endif - #if ENABLED(LASER_COOLANT_FLOW_METER) - _draw_flowmeter_status(); - #endif + TERN_(HAS_COOLER, _draw_cooler_status('*', blink)); + TERN_(LASER_COOLANT_FLOW_METER, _draw_flowmeter_status()); + TERN_(I2C_AMMETER, _draw_ammeter_status()); #endif // LCD_WIDTH >= 20 diff --git a/Marlin/src/lcd/dogm/dogm_Statusscreen.h b/Marlin/src/lcd/dogm/dogm_Statusscreen.h index 61d22a28ec1b7..6aa2bab0da936 100644 --- a/Marlin/src/lcd/dogm/dogm_Statusscreen.h +++ b/Marlin/src/lcd/dogm/dogm_Statusscreen.h @@ -107,7 +107,17 @@ #define STATUS_FLOWMETER_BYTEWIDTH BW(STATUS_FLOWMETER_WIDTH) #endif - +// +// Laser Ammeter +// +#if ENABLED(I2C_AMMETER) + #if !STATUS_AMMETER_WIDTH + #include "status/ammeter.h" + #endif + #ifndef STATUS_AMMETER_WIDTH + #define STATUS_AMMETER_WIDTH 0 + #endif +#endif // // Bed @@ -603,6 +613,31 @@ #endif #endif +// +// I2C Laser Ammeter +// +#if ENABLED(I2C_AMMETER) && STATUS_AMMETER_WIDTH + #ifndef STATUS_AMMETER_BYTEWIDTH + #define STATUS_AMMETER_BYTEWIDTH BW(STATUS_AMMETER_WIDTH) + #endif + #ifndef STATUS_AMMETER_X + #define STATUS_AMMETER_X (LCD_PIXEL_WIDTH - (STATUS_AMMETER_BYTEWIDTH + STATUS_FLOWMETER_BYTEWIDTH + STATUS_FAN_BYTEWIDTH + STATUS_CUTTER_BYTEWIDTH + STATUS_COOLER_BYTEWIDTH) * 8) + #endif + #ifndef STATUS_AMMETER_HEIGHT + #define STATUS_AMMETER_HEIGHT(S) (sizeof(status_ammeter_bmp1) / (STATUS_AMMETER_BYTEWIDTH)) + #endif + #ifndef STATUS_AMMETER_Y + #define STATUS_AMMETER_Y(S) (18 - STATUS_AMMETER_HEIGHT(S)) + #endif + #ifndef STATUS_AMMETER_TEXT_X + #define STATUS_AMMETER_TEXT_X (STATUS_AMMETER_X + 7) + #endif + static_assert( + sizeof(status_ammeter_bmp1) == (STATUS_AMMETER_BYTEWIDTH) * STATUS_AMMETER_HEIGHT(0), + "Status ammeter bitmap (status_ammeter_bmp1) dimensions don't match data." + ); +#endif + // // Bed Bitmap Properties // @@ -696,6 +731,9 @@ #if ENABLED(LASER_COOLANT_FLOW_METER) #define DO_DRAW_FLOWMETER 1 #endif +#if ENABLED(I2C_AMMETER) + #define DO_DRAW_AMMETER 1 +#endif #if HAS_TEMP_CHAMBER && STATUS_CHAMBER_WIDTH && HOTENDS <= 4 #define DO_DRAW_CHAMBER 1 diff --git a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp index 1a07b7ab757b1..726eb2cc39d88 100644 --- a/Marlin/src/lcd/dogm/marlinui_DOGM.cpp +++ b/Marlin/src/lcd/dogm/marlinui_DOGM.cpp @@ -369,13 +369,12 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop void MenuItem_static::draw(const uint8_t row, PGM_P const pstr, const uint8_t style/*=SS_DEFAULT*/, const char * const vstr/*=nullptr*/) { if (mark_as_selected(row, style & SS_INVERT)) { - pixel_len_t n = LCD_PIXEL_WIDTH; // pixel width of string allowed - - const int8_t plen = pstr ? utf8_strlen_P(pstr) : 0, - vlen = vstr ? utf8_strlen(vstr) : 0; + + const int plen = pstr ? calculateWidth(pstr) : 0, + vlen = vstr ? utf8_strlen(vstr) : 0; if (style & SS_CENTER) { - int8_t pad = (LCD_WIDTH - plen - vlen) / 2; + int pad = (LCD_PIXEL_WIDTH - plen - vlen * MENU_FONT_WIDTH) / MENU_FONT_WIDTH / 2; while (--pad >= 0) n -= lcd_put_wchar(' '); } @@ -400,8 +399,9 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop if (mark_as_selected(row, sel)) { const uint8_t vallen = (pgm ? utf8_strlen_P(inStr) : utf8_strlen((char*)inStr)), pixelwidth = (pgm ? uxg_GetUtf8StrPixelWidthP(u8g.getU8g(), inStr) : uxg_GetUtf8StrPixelWidth(u8g.getU8g(), (char*)inStr)); + const u8g_uint_t prop = USE_WIDE_GLYPH ? 2 : 1; - pixel_len_t n = lcd_put_u8str_ind_P(pstr, itemIndex, itemString, LCD_WIDTH - 2 - vallen) * (MENU_FONT_WIDTH); + pixel_len_t n = lcd_put_u8str_ind_P(pstr, itemIndex, itemString, LCD_WIDTH - 2 - vallen * prop) * (MENU_FONT_WIDTH); if (vallen) { lcd_put_wchar(':'); while (n > MENU_FONT_WIDTH) n -= lcd_put_wchar(' '); @@ -414,15 +414,16 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop void MenuEditItemBase::draw_edit_screen(PGM_P const pstr, const char * const value/*=nullptr*/) { ui.encoder_direction_normal(); + const u8g_uint_t prop = USE_WIDE_GLYPH ? 2 : 1; const u8g_uint_t labellen = utf8_strlen_P(pstr), vallen = utf8_strlen(value); - bool extra_row = labellen > LCD_WIDTH - 2 - vallen; + bool extra_row = labellen * prop > LCD_WIDTH - 2 - vallen * prop; #if ENABLED(USE_BIG_EDIT_FONT) // Use the menu font if the label won't fit on a single line constexpr u8g_uint_t lcd_edit_width = (LCD_PIXEL_WIDTH) / (EDIT_FONT_WIDTH); u8g_uint_t lcd_chr_fit, one_chr_width; - if (labellen <= lcd_edit_width - 1) { - if (labellen + vallen + 1 > lcd_edit_width) extra_row = true; + if (labellen * prop <= lcd_edit_width - 1) { + if (labellen * prop + vallen * prop + 1 > lcd_edit_width) extra_row = true; lcd_chr_fit = lcd_edit_width + 1; one_chr_width = EDIT_FONT_WIDTH; ui.set_font(FONT_EDIT); @@ -454,7 +455,7 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop onpage = PAGE_CONTAINS(baseline - (EDIT_FONT_ASCENT - 1), baseline); } if (onpage) { - lcd_put_wchar(((lcd_chr_fit - 1) - (vallen + 1)) * one_chr_width, baseline, ' '); // Right-justified, padded, add a leading space + lcd_put_wchar(((lcd_chr_fit - 1) - (vallen * prop + 1)) * one_chr_width, baseline, ' '); // Right-justified, padded, add a leading space lcd_put_u8str(value); } } @@ -468,7 +469,7 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop const pixel_len_t bw = len * prop * (MENU_FONT_WIDTH), bx = x * prop * (MENU_FONT_WIDTH); if (inv) { u8g.setColorIndex(1); - u8g.drawBox(bx / prop - 1, by - (MENU_FONT_ASCENT) + 1, bw / prop + 2, MENU_FONT_HEIGHT - 1); + u8g.drawBox(bx / prop - 1, by - (MENU_FONT_ASCENT), bw + 2, MENU_FONT_HEIGHT); u8g.setColorIndex(0); } lcd_put_u8str_P(bx / prop, by, pstr); @@ -478,8 +479,7 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const bool yesno, PGM_P const pref, const char * const string/*=nullptr*/, PGM_P const suff/*=nullptr*/) { ui.draw_select_screen_prompt(pref, string, suff); draw_boxed_string(1, LCD_HEIGHT - 1, no, !yesno); - const u8g_uint_t xpos = (LCD_WIDTH) / (USE_WIDE_GLYPH ? 2 : 1); - draw_boxed_string(xpos - (utf8_strlen_P(yes) + 1), LCD_HEIGHT - 1, yes, yesno); + draw_boxed_string(LCD_WIDTH - (utf8_strlen_P(yes) * (USE_WIDE_GLYPH ? 2 : 1) + 1), LCD_HEIGHT - 1, yes, yesno); } #if ENABLED(SDSUPPORT) diff --git a/Marlin/src/lcd/dogm/status/ammeter.h b/Marlin/src/lcd/dogm/status/ammeter.h new file mode 100644 index 0000000000000..d99ea6949a64d --- /dev/null +++ b/Marlin/src/lcd/dogm/status/ammeter.h @@ -0,0 +1,68 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +// +// lcd/dogm/status/ammeter.h - Status Screen Laser Ammeter bitmaps +// + +#define STATUS_AMMETER_WIDTH 20 + +const unsigned char status_ammeter_bmp_mA[] PROGMEM = { + B00000000,B11111100,B00000000, + B00000011,B00000011,B00000000, + B00000100,B00000000,B10000000, + B00001000,B00000000,B01000000, + B00010000,B00000110,B00100000, + B00010000,B00001001,B00100000, + B00100000,B00001001,B00010000, + B00100011,B01001111,B00010000, + B11100010,B10101001,B00011100, + B00100010,B10101001,B00010000, + B00100010,B10101001,B00010000, + B00010000,B00000000,B00100000, + B00010000,B00000000,B00100000, + B00001000,B00000000,B01000000, + B00000100,B00000000,B10000000, + B00000011,B00000011,B00000000, + B00000000,B11111100,B00000000 +}; + +const unsigned char status_ammeter_bmp_A[] PROGMEM = { + B00000000,B11111100,B00000000, + B00000011,B00000011,B00000000, + B00000100,B00000000,B10000000, + B00001000,B00000000,B01000000, + B00010000,B00000000,B00100000, + B00010000,B00110000,B00100000, + B00100000,B01001000,B00010000, + B00100000,B01001000,B00010000, + B11100000,B01111000,B00011100, + B00100000,B01001000,B00010000, + B00100000,B01001000,B00010000, + B00010000,B01001000,B00100000, + B00010000,B00000000,B00100000, + B00001000,B00000000,B01000000, + B00000100,B00000000,B10000000, + B00000011,B00000011,B00000000, + B00000000,B11111100,B00000000, +}; diff --git a/Marlin/src/lcd/dogm/status/cooler.h b/Marlin/src/lcd/dogm/status/cooler.h index 6cf67a4b62644..65c28ec28e15c 100644 --- a/Marlin/src/lcd/dogm/status/cooler.h +++ b/Marlin/src/lcd/dogm/status/cooler.h @@ -29,40 +29,40 @@ #define STATUS_COOLER_WIDTH 22 const unsigned char status_cooler_bmp2[] PROGMEM = { - B00000100,B00000010,B00000000, - B00000100,B10010010,B01000000, - B00010101,B00001010,B10000000, - B00001110,B00000111,B00000000, - B00111111,B10111111,B11000000, - B00001110,B00000111,B00000000, - B00010101,B00001010,B10000000, - B00100100,B00100010,B01000000, - B00000100,B00100000,B00000000, - B00000001,B00100100,B00000000, - B00000000,B10101000,B00000000, - B00000000,B01110000,B00000000, - B00000111,B11111111,B00000000, - B00000000,B01110000,B00000000, - B00000000,B10101000,B00000000, - B00000001,B00100100,B00000000 + B00000001,B00000000,B10000000, + B00000001,B00100100,B10010000, + B00000101,B01000010,B10100000, + B00000011,B10000001,B11000000, + B00001111,B11101111,B11110000, + B00000011,B10000001,B11000000, + B00000101,B01000010,B10100000, + B00001001,B00001000,B10010000, + B00000001,B00001000,B00000000, + B00000000,B01001001,B00000000, + B00000000,B00101010,B00000000, + B00000000,B00011100,B00000000, + B00000001,B11111111,B11000000, + B00000000,B00011100,B00000000, + B00000000,B00101010,B00000000, + B00000000,B01001001,B00000000 }; const unsigned char status_cooler_bmp1[] PROGMEM = { - B00000100,B00000010,B00000000, - B00000100,B10010010,B01000000, - B00010101,B00001010,B10000000, - B00001010,B00000101,B00000000, - B00110001,B11011000,B11000000, - B00001010,B00000101,B00000000, - B00010101,B00001010,B10000000, - B00100100,B00100010,B01000000, - B00000100,B00100000,B00000000, - B00000001,B00100100,B00000000, - B00000000,B10101000,B00000000, - B00000000,B01010000,B00000000, - B00000111,B10001111,B00000000, - B00000000,B01010000,B00000000, - B00000000,B10101000,B00000000, - B00000001,B00100100,B00000000 + B00000001,B00000000,B10000000, + B00000001,B00100100,B10010000, + B00000101,B01000010,B10100000, + B00000010,B10000001,B01000000, + B00001100,B01110110,B00110000, + B00000010,B10000001,B01000000, + B00000101,B01000010,B10100000, + B00001001,B00001000,B10010000, + B00000001,B00001000,B00000000, + B00000000,B01001001,B00000000, + B00000000,B00101010,B00000000, + B00000000,B00010100,B00000000, + B00000001,B11100011,B11000000, + B00000000,B00010100,B00000000, + B00000000,B00101010,B00000000, + B00000000,B01001001,B00000000 }; #endif diff --git a/Marlin/src/lcd/dogm/status/hotend.h b/Marlin/src/lcd/dogm/status/hotend.h index 3a6e02acb6067..aac29da45122d 100644 --- a/Marlin/src/lcd/dogm/status/hotend.h +++ b/Marlin/src/lcd/dogm/status/hotend.h @@ -39,20 +39,33 @@ #define STATUS_HOTEND1_WIDTH 16 -#if STATUS_HOTEND_BITMAPS == 1 || ENABLED(STATUS_HOTEND_NUMBERLESS) +#if STATUS_HOTEND_BITMAPS == 1 || defined(STATUS_HOTEND_NUMBERLESS) const unsigned char status_hotend_a_bmp[] PROGMEM = { B00011111,B11100000, - B00111111,B11110000, - B00111111,B11110000, - B00111111,B11110000, - B00011111,B11100000, - B00011111,B11100000, - B00111111,B11110000, - B00111111,B11110000, - B00111111,B11110000, - B00001111,B11000000, - B00000111,B10000000, + #if defined(STATUS_HOTEND_INVERTED) && !defined(STATUS_HOTEND_ANIM) + B00100000,B00010000, + B00100000,B00010000, + B00100000,B00010000, + B00010000,B00100000, + B00010000,B00100000, + B00100000,B00010000, + B00100000,B00010000, + B00110000,B00110000, + B00001000,B01000000, + B00000100,B10000000, + #else + B00111111,B11110000, + B00111111,B11110000, + B00111111,B11110000, + B00011111,B11100000, + B00011111,B11100000, + B00111111,B11110000, + B00111111,B11110000, + B00111111,B11110000, + B00001111,B11000000, + B00000111,B10000000, + #endif B00000011,B00000000 }; diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index 010d9a668034f..d58be4dbaf5c8 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -205,6 +205,14 @@ FORCE_INLINE void _draw_centered_temp(const celsius_t temp, const uint8_t tx, co } #endif +#if DO_DRAW_AMMETER + FORCE_INLINE void _draw_centered_current(const float current, const uint8_t tx, const uint8_t ty) { + const char *str = ftostr31ns(current); + const uint8_t len = str[0] != ' ' ? 3 : str[1] != ' ' ? 2 : 1; + lcd_put_u8str(tx - len * (INFO_FONT_WIDTH) / 2 + 1, ty, &str[3-len]); + } +#endif + #if DO_DRAW_HOTENDS // Draw hotend bitmap with current and target temperatures @@ -228,18 +236,12 @@ FORCE_INLINE void _draw_centered_temp(const celsius_t temp, const uint8_t tx, co #define HOTEND_DOT false #endif - #if ANIM_HOTEND && BOTH(STATUS_HOTEND_INVERTED, STATUS_HOTEND_NUMBERLESS) - #define OFF_BMP(N) status_hotend_b_bmp - #define ON_BMP(N) status_hotend_a_bmp - #elif ANIM_HOTEND && DISABLED(STATUS_HOTEND_INVERTED) && ENABLED(STATUS_HOTEND_NUMBERLESS) - #define OFF_BMP(N) status_hotend_a_bmp - #define ON_BMP(N) status_hotend_b_bmp - #elif BOTH(ANIM_HOTEND, STATUS_HOTEND_INVERTED) - #define OFF_BMP(N) status_hotend##N##_b_bmp - #define ON_BMP(N) status_hotend##N##_a_bmp + #if ENABLED(STATUS_HOTEND_NUMBERLESS) + #define OFF_BMP(N) TERN(STATUS_HOTEND_INVERTED, status_hotend_b_bmp, status_hotend_a_bmp) + #define ON_BMP(N) TERN(STATUS_HOTEND_INVERTED, status_hotend_a_bmp, status_hotend_b_bmp) #else - #define OFF_BMP(N) status_hotend##N##_a_bmp - #define ON_BMP(N) status_hotend##N##_b_bmp + #define OFF_BMP(N) TERN(STATUS_HOTEND_INVERTED, status_hotend##N##_b_bmp, status_hotend##N##_a_bmp) + #define ON_BMP(N) TERN(STATUS_HOTEND_INVERTED, status_hotend##N##_a_bmp, status_hotend##N##_b_bmp) #endif #if STATUS_HOTEND_BITMAPS > 1 @@ -267,20 +269,18 @@ FORCE_INLINE void _draw_centered_temp(const celsius_t temp, const uint8_t tx, co uint8_t tall = uint8_t(perc * BAR_TALL + 0.5f); NOMORE(tall, BAR_TALL); - #if ANIM_HOTEND - // Draw hotend bitmap, either whole or split by the heating percent - const uint8_t hx = STATUS_HOTEND_X(heater_id), - bw = STATUS_HOTEND_BYTEWIDTH(heater_id); - #if ENABLED(STATUS_HEAT_PERCENT) - if (isHeat && tall <= BAR_TALL) { - const uint8_t ph = STATUS_HEATERS_HEIGHT - 1 - tall; - u8g.drawBitmapP(hx, STATUS_HEATERS_Y, bw, ph, HOTEND_BITMAP(TERN(HAS_MMU, active_extruder, heater_id), false)); - u8g.drawBitmapP(hx, STATUS_HEATERS_Y + ph, bw, tall + 1, HOTEND_BITMAP(TERN(HAS_MMU, active_extruder, heater_id), true) + ph * bw); - } - else - #endif - u8g.drawBitmapP(hx, STATUS_HEATERS_Y, bw, STATUS_HEATERS_HEIGHT, HOTEND_BITMAP(TERN(HAS_MMU, active_extruder, heater_id), isHeat)); + // Draw hotend bitmap, either whole or split by the heating percent + const uint8_t hx = STATUS_HOTEND_X(heater_id), + bw = STATUS_HOTEND_BYTEWIDTH(heater_id); + #if ENABLED(STATUS_HEAT_PERCENT) + if (isHeat && tall <= BAR_TALL) { + const uint8_t ph = STATUS_HEATERS_HEIGHT - 1 - tall; + u8g.drawBitmapP(hx, STATUS_HEATERS_Y, bw, ph, HOTEND_BITMAP(TERN(HAS_MMU, active_extruder, heater_id), false)); + u8g.drawBitmapP(hx, STATUS_HEATERS_Y + ph, bw, tall + 1, HOTEND_BITMAP(TERN(HAS_MMU, active_extruder, heater_id), true) + ph * bw); + } + else #endif + u8g.drawBitmapP(hx, STATUS_HEATERS_Y, bw, STATUS_HEATERS_HEIGHT, HOTEND_BITMAP(TERN(HAS_MMU, active_extruder, heater_id), isHeat)); } // PAGE_CONTAINS @@ -404,6 +404,13 @@ FORCE_INLINE void _draw_centered_temp(const celsius_t temp, const uint8_t tx, co } #endif +#if DO_DRAW_AMMETER + FORCE_INLINE void _draw_ammeter_status() { + if (PAGE_CONTAINS(28 - INFO_FONT_ASCENT, 28 - 1)) + _draw_centered_current(ammeter.read(), STATUS_AMMETER_TEXT_X, 28); + } +#endif + // // Before homing, blink '123' <-> '???'. // Homed but unknown... '123' <-> ' '. @@ -677,6 +684,13 @@ void MarlinUI::draw_status_screen() { u8g.drawBitmapP(STATUS_FLOWMETER_X, flowmetery, STATUS_FLOWMETER_BYTEWIDTH, flowmeterh, blink && cooler.flowpulses ? status_flowmeter_bmp2 : status_flowmeter_bmp1); #endif + // Laser Ammeter + #if DO_DRAW_AMMETER + const uint8_t ammetery = STATUS_AMMETER_Y(status_ammeter_bmp_mA), + ammeterh = STATUS_AMMETER_HEIGHT(status_ammeter_bmp_mA); + if (PAGE_CONTAINS(ammetery, ammetery + ammeterh - 1)) + u8g.drawBitmapP(STATUS_AMMETER_X, ammetery, STATUS_AMMETER_BYTEWIDTH, ammeterh, (ammeter.current < 0.1f) ? status_ammeter_bmp_mA : status_ammeter_bmp_A); + #endif // Heated Bed TERN_(DO_DRAW_BED, _draw_bed_status(blink)); @@ -690,6 +704,9 @@ void MarlinUI::draw_status_screen() { // Flowmeter TERN_(DO_DRAW_FLOWMETER, _draw_flowmeter_status()); + // Flowmeter + TERN_(DO_DRAW_AMMETER, _draw_ammeter_status()); + // Fan, if a bitmap was provided #if DO_DRAW_FAN if (PAGE_CONTAINS(STATUS_FAN_TEXT_Y - INFO_FONT_ASCENT, STATUS_FAN_TEXT_Y - 1)) { @@ -856,8 +873,10 @@ void MarlinUI::draw_status_screen() { #else if (show_e_total) { - _draw_axis_value(E_AXIS, xstring, true); - lcd_put_u8str_P(PSTR(" ")); + #if ENABLED(LCD_SHOW_E_TOTAL) + _draw_axis_value(E_AXIS, xstring, true); + lcd_put_u8str_P(PSTR(" ")); + #endif } else { _draw_axis_value(X_AXIS, xstring, blink); diff --git a/Marlin/src/lcd/dwin/e3v2/dwin.cpp b/Marlin/src/lcd/dwin/e3v2/dwin.cpp index 76118d68140f7..777b56ac0e4d0 100644 --- a/Marlin/src/lcd/dwin/e3v2/dwin.cpp +++ b/Marlin/src/lcd/dwin/e3v2/dwin.cpp @@ -1235,7 +1235,7 @@ inline ENCODER_DiffState get_encoder_state() { void HMI_Plan_Move(const feedRate_t fr_mm_s) { if (!planner.is_full()) { planner.synchronize(); - planner.buffer_line(current_position, fr_mm_s, active_extruder); + planner.buffer_line(current_position, fr_mm_s); DWIN_UpdateLCD(); } } diff --git a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp index a1de499f463c2..2e8df757eba5e 100644 --- a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp @@ -180,7 +180,7 @@ void DGUSScreenHandler::DGUSLCD_SendStringToDisplayPGM(DGUS_VP_Variable &var) { float valuesend = 0; switch (var.VP) { default: return; - #if HOTENDS >= 1 + #if HAS_HOTEND case VP_E0_PID_P: valuesend = value; break; case VP_E0_PID_I: valuesend = unscalePID_i(value); break; case VP_E0_PID_D: valuesend = unscalePID_d(value); break; @@ -393,7 +393,7 @@ void DGUSScreenHandler::HandleTemperatureChanged(DGUS_VP_Variable &var, void *va switch (var.VP) { default: return; - #if HOTENDS >= 1 + #if HAS_HOTEND case VP_T_E0_Set: NOMORE(newvalue, HEATER_0_MAXTEMP); thermalManager.setTargetHotend(newvalue, 0); @@ -427,10 +427,8 @@ void DGUSScreenHandler::HandleFlowRateChanged(DGUS_VP_Variable &var, void *val_p uint8_t target_extruder; switch (var.VP) { default: return; - #if HOTENDS >= 1 - case VP_Flowrate_E0: target_extruder = 0; break; - #endif - #if HOTENDS >= 2 + case VP_Flowrate_E0: target_extruder = 0; break; + #if HAS_MULTI_EXTRUDER case VP_Flowrate_E1: target_extruder = 1; break; #endif } @@ -450,11 +448,11 @@ void DGUSScreenHandler::HandleManualExtrude(DGUS_VP_Variable &var, void *val_ptr ExtUI::extruder_t target_extruder; switch (var.VP) { - #if HOTENDS >= 1 + #if HAS_HOTEND case VP_MOVE_E0: target_extruder = ExtUI::extruder_t::E0; break; - #endif - #if HOTENDS >= 2 - case VP_MOVE_E1: target_extruder = ExtUI::extruder_t::E1; break; + #if HAS_MULTI_EXTRUDER + case VP_MOVE_E1: target_extruder = ExtUI::extruder_t::E1; break; + #endif #endif default: return; } @@ -526,11 +524,11 @@ void DGUSScreenHandler::HandleStepPerMMExtruderChanged(DGUS_VP_Variable &var, vo ExtUI::extruder_t extruder; switch (var.VP) { default: return; - #if HOTENDS >= 1 + #if HAS_EXTRUDERS case VP_E0_STEP_PER_MM: extruder = ExtUI::extruder_t::E0; break; - #endif - #if HOTENDS >= 2 - case VP_E1_STEP_PER_MM: extruder = ExtUI::extruder_t::E1; break; + #if HAS_MULTI_EXTRUDER + case VP_E1_STEP_PER_MM: extruder = ExtUI::extruder_t::E1; break; + #endif #endif } DEBUG_ECHOLNPAIR_F("value:", value); @@ -548,7 +546,7 @@ void DGUSScreenHandler::HandleStepPerMMExtruderChanged(DGUS_VP_Variable &var, vo switch (var.VP) { default: break; #if ENABLED(PIDTEMP) - #if HOTENDS >= 1 + #if HAS_HOTEND case VP_PID_AUTOTUNE_E0: // Autotune Extruder 0 sprintf_P(buf, PSTR("M303 E%d C5 S210 U1"), ExtUI::extruder_t::E0); break; @@ -598,17 +596,17 @@ void DGUSScreenHandler::HandleHeaterControl(DGUS_VP_Variable &var, void *val_ptr uint8_t preheat_temp = 0; switch (var.VP) { - #if HOTENDS >= 1 + #if HAS_HOTEND case VP_E0_CONTROL: + #if HOTENDS >= 2 + case VP_E1_CONTROL: + #if HOTENDS >= 3 + case VP_E2_CONTROL: + #endif + #endif + preheat_temp = PREHEAT_1_TEMP_HOTEND; + break; #endif - #if HOTENDS >= 2 - case VP_E1_CONTROL: - #endif - #if HOTENDS >= 3 - case VP_E2_CONTROL: - #endif - preheat_temp = PREHEAT_1_TEMP_HOTEND; - break; case VP_BED_CONTROL: preheat_temp = PREHEAT_1_TEMP_BED; @@ -660,7 +658,7 @@ void DGUSScreenHandler::HandleHeaterControl(DGUS_VP_Variable &var, void *val_ptr switch (var.VP) { default: return; - #if HOTENDS >= 1 + #if HAS_HOTEND case VP_E0_BED_PREHEAT: thermalManager.setTargetHotend(e_temp, 0); TERN_(HAS_HEATED_BED, thermalManager.setTargetBed(bed_temp)); diff --git a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.h index 9aeb5b73b1cb3..8ee2761c899ba 100644 --- a/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/DGUSScreenHandler.h @@ -56,3 +56,21 @@ inline uint16_t swap16(const uint16_t value) { return (value & 0xFFU) << 8U | (v #endif extern DGUSScreenHandler ScreenHandler; + +// Helper to define a DGUS_VP_Variable for common use-cases. +#define VPHELPER(VPADR, VPADRVAR, RXFPTR, TXFPTR) { \ + .VP = VPADR, \ + .memadr = VPADRVAR, \ + .size = sizeof(VPADRVAR), \ + .set_by_display_handler = RXFPTR, \ + .send_to_display_handler = TXFPTR \ +} + +// Helper to define a DGUS_VP_Variable when the size of the var cannot be determined automatically (e.g., a string) +#define VPHELPER_STR(VPADR, VPADRVAR, STRLEN, RXFPTR, TXFPTR) { \ + .VP = VPADR, \ + .memadr = VPADRVAR, \ + .size = STRLEN, \ + .set_by_display_handler = RXFPTR, \ + .send_to_display_handler = TXFPTR \ +} diff --git a/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp index 5e164d289ee23..79f39f93d80b0 100644 --- a/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.cpp @@ -41,14 +41,11 @@ uint16_t distanceToMove = 10; #endif -const uint16_t VPList_Boot[] PROGMEM = { - VP_MARLIN_VERSION, - 0x0000 -}; +const uint16_t VPList_Boot[] PROGMEM = { VP_MARLIN_VERSION, 0x0000 }; const uint16_t VPList_Main[] PROGMEM = { - /* VP_M117, for completeness, but it cannot be auto-uploaded. */ - #if HOTENDS >= 1 + // VP_M117, for completeness, but it cannot be auto-uploaded. + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, VP_E0_STATUS, #endif #if HOTENDS >= 2 @@ -70,7 +67,7 @@ const uint16_t VPList_Main[] PROGMEM = { }; const uint16_t VPList_Temp[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, #endif #if HOTENDS >= 2 @@ -83,8 +80,8 @@ const uint16_t VPList_Temp[] PROGMEM = { }; const uint16_t VPList_Status[] PROGMEM = { - /* VP_M117, for completeness, but it cannot be auto-uploaded */ - #if HOTENDS >= 1 + // VP_M117, for completeness, but it cannot be auto-uploaded + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, #endif #if HOTENDS >= 2 @@ -105,11 +102,11 @@ const uint16_t VPList_Status[] PROGMEM = { const uint16_t VPList_Status2[] PROGMEM = { /* VP_M117, for completeness, but it cannot be auto-uploaded */ - #if HOTENDS >= 1 + #if HAS_HOTEND VP_Flowrate_E0, - #endif - #if HOTENDS >= 2 - VP_Flowrate_E1, + #if HAS_MULTI_EXTRUDER + VP_Flowrate_E1, + #endif #endif VP_PrintProgress_Percentage, VP_PrintTime, @@ -117,7 +114,7 @@ const uint16_t VPList_Status2[] PROGMEM = { }; const uint16_t VPList_Preheat[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, #endif #if HOTENDS >= 2 @@ -135,11 +132,11 @@ const uint16_t VPList_ManualMove[] PROGMEM = { }; const uint16_t VPList_ManualExtrude[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, + #if HAS_MULTI_EXTRUDER + VP_T_E1_Is, VP_T_E1_Set, + #endif #endif VP_EPos, 0x0000 @@ -156,23 +153,23 @@ const uint16_t VPList_SD_FlowRates[] PROGMEM = { }; const uint16_t VPList_Filament_heating[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, VP_E0_FILAMENT_LOAD_UNLOAD, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, - VP_E1_FILAMENT_LOAD_UNLOAD, + #if HAS_MULTI_EXTRUDER + VP_T_E1_Is, VP_T_E1_Set, + VP_E1_FILAMENT_LOAD_UNLOAD, + #endif #endif 0x0000 }; const uint16_t VPList_Filament_load_unload[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_E0_FILAMENT_LOAD_UNLOAD, - #endif - #if HOTENDS >= 2 - VP_E1_FILAMENT_LOAD_UNLOAD, + #if HAS_MULTI_EXTRUDER + VP_E1_FILAMENT_LOAD_UNLOAD, + #endif #endif 0x0000 }; @@ -184,7 +181,7 @@ const uint16_t VPList_SDFileList[] PROGMEM = { const uint16_t VPList_SD_PrintManipulation[] PROGMEM = { VP_PrintProgress_Percentage, VP_PrintTime, - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, #endif #if HOTENDS >= 2 @@ -204,11 +201,11 @@ const uint16_t VPList_SD_PrintManipulation[] PROGMEM = { }; const uint16_t VPList_SDPrintTune[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, VP_Flowrate_E0, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, VP_Flowrate_E1, + #if HAS_MULTI_EXTRUDER + VP_T_E1_Is, VP_T_E1_Set, VP_Flowrate_E1, // ERROR: Flowrate is per-extruder, not per-hotend + #endif #endif #if HAS_HEATED_BED VP_T_Bed_Is, VP_T_Bed_Set, @@ -222,11 +219,11 @@ const uint16_t VPList_StepPerMM[] PROGMEM = { VP_X_STEP_PER_MM, VP_Y_STEP_PER_MM, VP_Z_STEP_PER_MM, - #if HOTENDS >= 1 + #if HAS_EXTRUDERS VP_E0_STEP_PER_MM, - #endif - #if HOTENDS >= 2 - VP_E1_STEP_PER_MM, + #if HAS_MULTI_EXTRUDER + VP_E1_STEP_PER_MM, + #endif #endif 0x0000 }; @@ -265,7 +262,7 @@ const uint16_t VPList_PIDTuningWaiting[] PROGMEM = { }; const uint16_t VPList_FLCPreheat[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, #endif #if HAS_HEATED_BED @@ -275,14 +272,14 @@ const uint16_t VPList_FLCPreheat[] PROGMEM = { }; const uint16_t VPList_FLCPrinting[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_SD_Print_ProbeOffsetZ, #endif 0x0000 }; const uint16_t VPList_Z_Offset[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_SD_Print_ProbeOffsetZ, #endif 0x0000 @@ -316,14 +313,6 @@ const struct VPMapping VPMap[] PROGMEM = { const char MarlinVersion[] PROGMEM = SHORT_BUILD_VERSION; -// Helper to define a DGUS_VP_Variable for common use cases. -#define VPHELPER(VPADR, VPADRVAR, RXFPTR, TXFPTR ) { .VP=VPADR, .memadr=VPADRVAR, .size=sizeof(VPADRVAR), \ - .set_by_display_handler = RXFPTR, .send_to_display_handler = TXFPTR } - -// Helper to define a DGUS_VP_Variable when the sizeo of the var cannot be determined automaticalyl (eg. a string) -#define VPHELPER_STR(VPADR, VPADRVAR, STRLEN, RXFPTR, TXFPTR ) { .VP=VPADR, .memadr=VPADRVAR, .size=STRLEN, \ - .set_by_display_handler = RXFPTR, .send_to_display_handler = TXFPTR } - const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { // Helper to detect touch events VPHELPER(VP_SCREENCHANGE, nullptr, ScreenHandler.ScreenChangeHook, nullptr), @@ -333,96 +322,96 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { #endif VPHELPER(VP_CONFIRMED, nullptr, ScreenHandler.ScreenConfirmedOK, nullptr), - VPHELPER(VP_TEMP_ALL_OFF, nullptr, &ScreenHandler.HandleAllHeatersOff, nullptr), + VPHELPER(VP_TEMP_ALL_OFF, nullptr, ScreenHandler.HandleAllHeatersOff, nullptr), #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) - VPHELPER(VP_MOVE_OPTION, &distanceToMove, &ScreenHandler.HandleManualMoveOption, nullptr), + VPHELPER(VP_MOVE_OPTION, &distanceToMove, ScreenHandler.HandleManualMoveOption, nullptr), #endif #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) - VPHELPER(VP_MOVE_X, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Y, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Z, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_HOME_ALL, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_X, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Y, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Z, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_HOME_ALL, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), #else - VPHELPER(VP_MOVE_X, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Y, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Z, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_HOME_ALL, nullptr, &ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_X, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Y, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Z, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_HOME_ALL, nullptr, ScreenHandler.HandleManualMove, nullptr), #endif - VPHELPER(VP_MOTOR_LOCK_UNLOK, nullptr, &ScreenHandler.HandleMotorLockUnlock, nullptr), + VPHELPER(VP_MOTOR_LOCK_UNLOK, nullptr, ScreenHandler.HandleMotorLockUnlock, nullptr), #if ENABLED(POWER_LOSS_RECOVERY) - VPHELPER(VP_POWER_LOSS_RECOVERY, nullptr, &ScreenHandler.HandlePowerLossRecovery, nullptr), + VPHELPER(VP_POWER_LOSS_RECOVERY, nullptr, ScreenHandler.HandlePowerLossRecovery, nullptr), #endif - VPHELPER(VP_SETTINGS, nullptr, &ScreenHandler.HandleSettings, nullptr), + VPHELPER(VP_SETTINGS, nullptr, ScreenHandler.HandleSettings, nullptr), #if ENABLED(SINGLE_Z_CALIBRATION) - VPHELPER(VP_Z_CALIBRATE, nullptr, &ScreenHandler.HandleZCalibration, nullptr), + VPHELPER(VP_Z_CALIBRATE, nullptr, ScreenHandler.HandleZCalibration, nullptr), #endif #if ENABLED(FIRST_LAYER_CAL) - VPHELPER(VP_Z_FIRST_LAYER_CAL, nullptr, &ScreenHandler.HandleFirstLayerCal, nullptr), + VPHELPER(VP_Z_FIRST_LAYER_CAL, nullptr, ScreenHandler.HandleFirstLayerCal, nullptr), #endif - { .VP = VP_MARLIN_VERSION, .memadr = (void*)MarlinVersion, .size = VP_MARLIN_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler =&ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MARLIN_VERSION, .memadr = (void*)MarlinVersion, .size = VP_MARLIN_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, // M117 LCD String (We don't need the string in memory but "just" push it to the display on demand, hence the nullptr - { .VP = VP_M117, .memadr = nullptr, .size = VP_M117_LEN, .set_by_display_handler = nullptr, .send_to_display_handler =&ScreenHandler.DGUSLCD_SendStringToDisplay }, + { .VP = VP_M117, .memadr = nullptr, .size = VP_M117_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplay }, // Temperature Data - #if HOTENDS >= 1 - VPHELPER(VP_T_E0_Is, &thermalManager.temp_hotend[0].celsius, nullptr, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_T_E0_Set, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleTemperatureChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Flowrate_E0, &planner.flow_percentage[ExtUI::extruder_t::E0], ScreenHandler.HandleFlowRateChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), + #if HAS_HOTEND + VPHELPER(VP_T_E0_Is, &thermalManager.temp_hotend[0].celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), + VPHELPER(VP_T_E0_Set, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Flowrate_E0, &planner.flow_percentage[ExtUI::extruder_t::E0], ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_EPos, &destination.e, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), - VPHELPER(VP_MOVE_E0, nullptr, &ScreenHandler.HandleManualExtrude, nullptr), - VPHELPER(VP_E0_CONTROL, &thermalManager.temp_hotend[0].target, &ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_E0_STATUS, &thermalManager.temp_hotend[0].target, nullptr, &ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_MOVE_E0, nullptr, ScreenHandler.HandleManualExtrude, nullptr), + VPHELPER(VP_E0_CONTROL, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_E0_STATUS, &thermalManager.temp_hotend[0].target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), #if ENABLED(DGUS_PREHEAT_UI) - VPHELPER(VP_E0_BED_PREHEAT, nullptr, &ScreenHandler.HandlePreheat, nullptr), + VPHELPER(VP_E0_BED_PREHEAT, nullptr, ScreenHandler.HandlePreheat, nullptr), #endif #if ENABLED(PIDTEMP) VPHELPER(VP_E0_PID_P, &thermalManager.temp_hotend[0].pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), VPHELPER(VP_E0_PID_I, &thermalManager.temp_hotend[0].pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), VPHELPER(VP_E0_PID_D, &thermalManager.temp_hotend[0].pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_PID_AUTOTUNE_E0, nullptr, &ScreenHandler.HandlePIDAutotune, nullptr), + VPHELPER(VP_PID_AUTOTUNE_E0, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), #endif #if ENABLED(DGUS_FILAMENT_LOADUNLOAD) - VPHELPER(VP_E0_FILAMENT_LOAD_UNLOAD, nullptr, &ScreenHandler.HandleFilamentOption, &ScreenHandler.HandleFilamentLoadUnload), + VPHELPER(VP_E0_FILAMENT_LOAD_UNLOAD, nullptr, ScreenHandler.HandleFilamentOption, ScreenHandler.HandleFilamentLoadUnload), #endif #endif #if HOTENDS >= 2 - VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleTemperatureChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Flowrate_E1, &planner.flow_percentage[ExtUI::extruder_t::E1], ScreenHandler.HandleFlowRateChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_MOVE_E1, nullptr, &ScreenHandler.HandleManualExtrude, nullptr), - VPHELPER(VP_E1_CONTROL, &thermalManager.temp_hotend[1].target, &ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_E1_STATUS, &thermalManager.temp_hotend[1].target, nullptr, &ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), + VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Flowrate_E1, &planner.flow_percentage[ExtUI::extruder_t::E1], ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), // ERROR: Flow is per-extruder, not per-hotend + VPHELPER(VP_MOVE_E1, nullptr, ScreenHandler.HandleManualExtrude, nullptr), + VPHELPER(VP_E1_CONTROL, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_E1_STATUS, &thermalManager.temp_hotend[1].target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), #if ENABLED(PIDTEMP) - VPHELPER(VP_PID_AUTOTUNE_E1, nullptr, &ScreenHandler.HandlePIDAutotune, nullptr), + VPHELPER(VP_PID_AUTOTUNE_E1, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), #endif - VPHELPER(VP_E1_FILAMENT_LOAD_UNLOAD, nullptr, &ScreenHandler.HandleFilamentOption, &ScreenHandler.HandleFilamentLoadUnload), + VPHELPER(VP_E1_FILAMENT_LOAD_UNLOAD, nullptr, ScreenHandler.HandleFilamentOption, ScreenHandler.HandleFilamentLoadUnload), #endif #if HAS_HEATED_BED VPHELPER(VP_T_Bed_Is, &thermalManager.temp_bed.celsius, nullptr, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_T_Bed_Set, &thermalManager.temp_bed.target, ScreenHandler.HandleTemperatureChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_BED_CONTROL, &thermalManager.temp_bed.target, &ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_BED_STATUS, &thermalManager.temp_bed.target, nullptr, &ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_T_Bed_Set, &thermalManager.temp_bed.target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_BED_CONTROL, &thermalManager.temp_bed.target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_BED_STATUS, &thermalManager.temp_bed.target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), #if ENABLED(PIDTEMPBED) VPHELPER(VP_BED_PID_P, &thermalManager.temp_bed.pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), VPHELPER(VP_BED_PID_I, &thermalManager.temp_bed.pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), VPHELPER(VP_BED_PID_D, &thermalManager.temp_bed.pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_PID_AUTOTUNE_BED, nullptr, &ScreenHandler.HandlePIDAutotune, nullptr), + VPHELPER(VP_PID_AUTOTUNE_BED, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), #endif #endif // Fan Data #if HAS_FAN #define FAN_VPHELPER(N) \ - VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], ScreenHandler.DGUSLCD_PercentageToUint8, &ScreenHandler.DGUSLCD_SendPercentageToDisplay), \ - VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], &ScreenHandler.HandleFanControl, nullptr), \ - VPHELPER(VP_FAN##N##_STATUS, &thermalManager.fan_speed[N], nullptr, &ScreenHandler.DGUSLCD_SendFanStatusToDisplay), + VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], ScreenHandler.DGUSLCD_PercentageToUint8, ScreenHandler.DGUSLCD_SendPercentageToDisplay), \ + VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], ScreenHandler.HandleFanControl, nullptr), \ + VPHELPER(VP_FAN##N##_STATUS, &thermalManager.fan_speed[N], nullptr, ScreenHandler.DGUSLCD_SendFanStatusToDisplay), REPEAT(FAN_COUNT, FAN_VPHELPER) #endif // Feedrate - VPHELPER(VP_Feedrate_Percentage, &feedrate_percentage, ScreenHandler.DGUSLCD_SetValueDirectly, &ScreenHandler.DGUSLCD_SendWordValueToDisplay ), + VPHELPER(VP_Feedrate_Percentage, &feedrate_percentage, ScreenHandler.DGUSLCD_SetValueDirectly, ScreenHandler.DGUSLCD_SendWordValueToDisplay), // Position Data VPHELPER(VP_XPos, ¤t_position.x, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), @@ -430,7 +419,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_ZPos, ¤t_position.z, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), // Print Progress - VPHELPER(VP_PrintProgress_Percentage, nullptr, nullptr, ScreenHandler.DGUSLCD_SendPrintProgressToDisplay ), + VPHELPER(VP_PrintProgress_Percentage, nullptr, nullptr, ScreenHandler.DGUSLCD_SendPrintProgressToDisplay), // Print Time VPHELPER_STR(VP_PrintTime, nullptr, VP_PrintTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintTimeToDisplay), @@ -442,11 +431,11 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_X_STEP_PER_MM, &planner.settings.axis_steps_per_mm[X_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), VPHELPER(VP_Y_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Y_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), VPHELPER(VP_Z_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Z_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), - #if HOTENDS >= 1 + #if HAS_EXTRUDERS VPHELPER(VP_E0_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(0)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), - #endif - #if HOTENDS >= 2 - VPHELPER(VP_E1_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(1)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + #if HAS_MULTI_EXTRUDER + VPHELPER(VP_E1_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(1)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + #endif #endif // SDCard File listing. @@ -463,7 +452,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_SD_AbortPrintConfirmed, nullptr, ScreenHandler.DGUSLCD_SD_ReallyAbort, nullptr), VPHELPER(VP_SD_Print_Setting, nullptr, ScreenHandler.DGUSLCD_SD_PrintTune, nullptr), #if HAS_BED_PROBE - VPHELPER(VP_SD_Print_ProbeOffsetZ, &probe.offset.z, ScreenHandler.HandleProbeOffsetZChanged, &ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<2>), + VPHELPER(VP_SD_Print_ProbeOffsetZ, &probe.offset.z, ScreenHandler.HandleProbeOffsetZChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<2>), #if ENABLED(BABYSTEPPING) VPHELPER(VP_SD_Print_LiveAdjustZ, nullptr, ScreenHandler.HandleLiveAdjustZ, nullptr), #endif @@ -475,10 +464,10 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { #endif // Messages for the User, shared by the popup and the kill screen. They cant be autouploaded as we do not buffer content. - { .VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, VPHELPER(0, 0, 0, 0) // must be last entry. }; diff --git a/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.h b/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.h index 910f5f7791f9d..79aee9a57647c 100644 --- a/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.h +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSDisplayDef.h @@ -51,7 +51,7 @@ enum DGUSLCD_Screens : uint8_t { DGUSLCD_SCREEN_KILL = 250, ///< Kill Screen. Must always be 250 (to be able to display "Error wrong LCD Version") DGUSLCD_SCREEN_WAITING = 251, DGUSLCD_SCREEN_POPUP = 252, ///< special target, popup screen will also return this code to say "return to previous screen" - DGUSLDC_SCREEN_UNUSED = 255 + DGUSLCD_SCREEN_UNUSED = 255 }; // Display Memory layout used (T5UID) diff --git a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp index 8b97003f6fcb7..78828e14c50b1 100644 --- a/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/fysetc/DGUSScreenHandler.cpp @@ -249,7 +249,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { switch (var.VP) { default: return; - #if HOTENDS >= 1 + #if HAS_HOTEND case VP_E0_PID_P: newvalue = value; break; case VP_E0_PID_I: newvalue = scalePID_i(value); break; case VP_E0_PID_D: newvalue = scalePID_d(value); break; @@ -329,7 +329,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { } if (filament_data.action == 0) { // Go back to utility screen - #if HOTENDS >= 1 + #if HAS_HOTEND thermalManager.setTargetHotend(e_temp, ExtUI::extruder_t::E0); #endif #if HOTENDS >= 2 @@ -340,13 +340,13 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { else { // Go to the preheat screen to show the heating progress switch (var.VP) { default: return; - #if HOTENDS >= 1 + #if HAS_HOTEND case VP_E0_FILAMENT_LOAD_UNLOAD: filament_data.extruder = ExtUI::extruder_t::E0; thermalManager.setTargetHotend(e_temp, filament_data.extruder); break; #endif - #if HOTENDS >= 2 + #if HAS_MULTI_EXTRUDER case VP_E1_FILAMENT_LOAD_UNLOAD: filament_data.extruder = ExtUI::extruder_t::E1; thermalManager.setTargetHotend(e_temp, filament_data.extruder); diff --git a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp index a9fa407dd3e00..3d0e073e5c3ae 100644 --- a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.cpp @@ -48,11 +48,11 @@ const uint16_t VPList_Boot[] PROGMEM = { const uint16_t VPList_Main[] PROGMEM = { /* VP_M117, for completeness, but it cannot be auto-uploaded. */ - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, VP_E0_STATUS, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, + #if HOTENDS >= 2 + VP_T_E1_Is, VP_T_E1_Set, + #endif #endif #if HAS_HEATED_BED VP_T_Bed_Is, VP_T_Bed_Set, VP_BED_STATUS, @@ -70,11 +70,11 @@ const uint16_t VPList_Main[] PROGMEM = { }; const uint16_t VPList_Temp[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, + #if HOTENDS >= 2 + VP_T_E1_Is, VP_T_E1_Set, + #endif #endif #if HAS_HEATED_BED VP_T_Bed_Is, VP_T_Bed_Set, @@ -84,11 +84,11 @@ const uint16_t VPList_Temp[] PROGMEM = { const uint16_t VPList_Status[] PROGMEM = { /* VP_M117, for completeness, but it cannot be auto-uploaded */ - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, + #if HOTENDS >= 2 + VP_T_E1_Is, VP_T_E1_Set, + #endif #endif #if HAS_HEATED_BED VP_T_Bed_Is, VP_T_Bed_Set, @@ -105,11 +105,11 @@ const uint16_t VPList_Status[] PROGMEM = { const uint16_t VPList_Status2[] PROGMEM = { /* VP_M117, for completeness, but it cannot be auto-uploaded */ - #if HOTENDS >= 1 + #if HAS_HOTEND VP_Flowrate_E0, - #endif - #if HOTENDS >= 2 - VP_Flowrate_E1, + #if HOTENDS >= 2 + VP_Flowrate_E1, + #endif #endif VP_PrintProgress_Percentage, VP_PrintTime, @@ -117,11 +117,11 @@ const uint16_t VPList_Status2[] PROGMEM = { }; const uint16_t VPList_Preheat[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, + #if HOTENDS >= 2 + VP_T_E1_Is, VP_T_E1_Set, + #endif #endif #if HAS_HEATED_BED VP_T_Bed_Is, VP_T_Bed_Set, @@ -135,11 +135,11 @@ const uint16_t VPList_ManualMove[] PROGMEM = { }; const uint16_t VPList_ManualExtrude[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, + #if HOTENDS >= 2 + VP_T_E1_Is, VP_T_E1_Set, + #endif #endif VP_EPos, 0x0000 @@ -156,22 +156,22 @@ const uint16_t VPList_SD_FlowRates[] PROGMEM = { }; const uint16_t VPList_Filament_heating[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, VP_E0_FILAMENT_LOAD_UNLOAD, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, + #if HOTENDS >= 2 + VP_T_E1_Is, VP_T_E1_Set, + #endif #endif 0x0000 }; const uint16_t VPList_Filament_load_unload[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_E0_FILAMENT_LOAD_UNLOAD, - #endif - #if HOTENDS >= 2 - VP_E1_FILAMENT_LOAD_UNLOAD, + #if HOTENDS >= 2 + VP_E1_FILAMENT_LOAD_UNLOAD, + #endif #endif 0x0000 }; @@ -183,11 +183,11 @@ const uint16_t VPList_SDFileList[] PROGMEM = { const uint16_t VPList_SD_PrintManipulation[] PROGMEM = { VP_PrintProgress_Percentage, VP_PrintTime, - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, + #if HOTENDS >= 2 + VP_T_E1_Is, VP_T_E1_Set, + #endif #endif #if HAS_HEATED_BED VP_T_Bed_Is, VP_T_Bed_Set, @@ -203,11 +203,11 @@ const uint16_t VPList_SD_PrintManipulation[] PROGMEM = { }; const uint16_t VPList_SDPrintTune[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, + #if HOTENDS >= 2 + VP_T_E1_Is, VP_T_E1_Set, + #endif #endif #if HAS_HEATED_BED VP_T_Bed_Is, VP_T_Bed_Set, @@ -225,11 +225,11 @@ const uint16_t VPList_StepPerMM[] PROGMEM = { VP_X_STEP_PER_MM, VP_Y_STEP_PER_MM, VP_Z_STEP_PER_MM, - #if HOTENDS >= 1 + #if HAS_HOTEND VP_E0_STEP_PER_MM, - #endif - #if HOTENDS >= 2 - VP_E1_STEP_PER_MM, + #if HOTENDS >= 2 + VP_E1_STEP_PER_MM, + #endif #endif 0x0000 }; @@ -268,7 +268,7 @@ const uint16_t VPList_PIDTuningWaiting[] PROGMEM = { }; const uint16_t VPList_FLCPreheat[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, #endif #if HAS_HEATED_BED @@ -278,14 +278,14 @@ const uint16_t VPList_FLCPreheat[] PROGMEM = { }; const uint16_t VPList_FLCPrinting[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_SD_Print_ProbeOffsetZ, #endif 0x0000 }; const uint16_t VPList_Z_Offset[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_SD_Print_ProbeOffsetZ, #endif 0x0000 @@ -319,14 +319,6 @@ const struct VPMapping VPMap[] PROGMEM = { const char MarlinVersion[] PROGMEM = SHORT_BUILD_VERSION; -// Helper to define a DGUS_VP_Variable for common use cases. -#define VPHELPER(VPADR, VPADRVAR, RXFPTR, TXFPTR ) { .VP=VPADR, .memadr=VPADRVAR, .size=sizeof(VPADRVAR), \ - .set_by_display_handler = RXFPTR, .send_to_display_handler = TXFPTR } - -// Helper to define a DGUS_VP_Variable when the sizeo of the var cannot be determined automaticalyl (eg. a string) -#define VPHELPER_STR(VPADR, VPADRVAR, STRLEN, RXFPTR, TXFPTR ) { .VP=VPADR, .memadr=VPADRVAR, .size=STRLEN, \ - .set_by_display_handler = RXFPTR, .send_to_display_handler = TXFPTR } - const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { // Helper to detect touch events VPHELPER(VP_SCREENCHANGE, nullptr, ScreenHandler.ScreenChangeHook, nullptr), @@ -336,92 +328,92 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { #endif VPHELPER(VP_CONFIRMED, nullptr, ScreenHandler.ScreenConfirmedOK, nullptr), - VPHELPER(VP_TEMP_ALL_OFF, nullptr, &ScreenHandler.HandleAllHeatersOff, nullptr), + VPHELPER(VP_TEMP_ALL_OFF, nullptr, ScreenHandler.HandleAllHeatersOff, nullptr), #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) - VPHELPER(VP_MOVE_OPTION, &distanceToMove, &ScreenHandler.HandleManualMoveOption, nullptr), + VPHELPER(VP_MOVE_OPTION, &distanceToMove, ScreenHandler.HandleManualMoveOption, nullptr), #endif #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) - VPHELPER(VP_MOVE_X, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Y, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Z, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_HOME_ALL, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_X, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Y, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Z, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_HOME_ALL, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), #else - VPHELPER(VP_MOVE_X, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Y, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Z, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_HOME_ALL, nullptr, &ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_X, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Y, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Z, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_HOME_ALL, nullptr, ScreenHandler.HandleManualMove, nullptr), #endif - VPHELPER(VP_MOTOR_LOCK_UNLOK, nullptr, &ScreenHandler.HandleMotorLockUnlock, nullptr), + VPHELPER(VP_MOTOR_LOCK_UNLOK, nullptr, ScreenHandler.HandleMotorLockUnlock, nullptr), #if ENABLED(POWER_LOSS_RECOVERY) - VPHELPER(VP_POWER_LOSS_RECOVERY, nullptr, &ScreenHandler.HandlePowerLossRecovery, nullptr), + VPHELPER(VP_POWER_LOSS_RECOVERY, nullptr, ScreenHandler.HandlePowerLossRecovery, nullptr), #endif - VPHELPER(VP_SETTINGS, nullptr, &ScreenHandler.HandleSettings, nullptr), + VPHELPER(VP_SETTINGS, nullptr, ScreenHandler.HandleSettings, nullptr), #if ENABLED(SINGLE_Z_CALIBRATION) - VPHELPER(VP_Z_CALIBRATE, nullptr, &ScreenHandler.HandleZCalibration, nullptr), + VPHELPER(VP_Z_CALIBRATE, nullptr, ScreenHandler.HandleZCalibration, nullptr), #endif #if ENABLED(FIRST_LAYER_CAL) - VPHELPER(VP_Z_FIRST_LAYER_CAL, nullptr, &ScreenHandler.HandleFirstLayerCal, nullptr), + VPHELPER(VP_Z_FIRST_LAYER_CAL, nullptr, ScreenHandler.HandleFirstLayerCal, nullptr), #endif - { .VP = VP_MARLIN_VERSION, .memadr = (void*)MarlinVersion, .size = VP_MARLIN_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MARLIN_VERSION, .memadr = (void*)MarlinVersion, .size = VP_MARLIN_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, // M117 LCD String (We don't need the string in memory but "just" push it to the display on demand, hence the nullptr - { .VP = VP_M117, .memadr = nullptr, .size = VP_M117_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplay }, + { .VP = VP_M117, .memadr = nullptr, .size = VP_M117_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplay }, // Temperature Data - #if HOTENDS >= 1 - VPHELPER(VP_T_E0_Is, &thermalManager.temp_hotend[0].celsius, nullptr, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_T_E0_Set, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleTemperatureChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Flowrate_E0, &planner.flow_percentage[ExtUI::extruder_t::E0], ScreenHandler.HandleFlowRateChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), + #if HAS_HOTEND + VPHELPER(VP_T_E0_Is, &thermalManager.temp_hotend[0].celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), + VPHELPER(VP_T_E0_Set, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Flowrate_E0, &planner.flow_percentage[ExtUI::extruder_t::E0], ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_EPos, &destination.e, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), - VPHELPER(VP_MOVE_E0, nullptr, &ScreenHandler.HandleManualExtrude, nullptr), - VPHELPER(VP_E0_CONTROL, &thermalManager.temp_hotend[0].target, &ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_E0_STATUS, &thermalManager.temp_hotend[0].target, nullptr, &ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_MOVE_E0, nullptr, ScreenHandler.HandleManualExtrude, nullptr), + VPHELPER(VP_E0_CONTROL, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_E0_STATUS, &thermalManager.temp_hotend[0].target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), #if ENABLED(DGUS_PREHEAT_UI) - VPHELPER(VP_E0_BED_PREHEAT, nullptr, &ScreenHandler.HandlePreheat, nullptr), + VPHELPER(VP_E0_BED_PREHEAT, nullptr, ScreenHandler.HandlePreheat, nullptr), #endif #if ENABLED(DGUS_FILAMENT_LOADUNLOAD) - VPHELPER(VP_E0_FILAMENT_LOAD_UNLOAD, nullptr, &ScreenHandler.HandleFilamentOption, &ScreenHandler.HandleFilamentLoadUnload), + VPHELPER(VP_E0_FILAMENT_LOAD_UNLOAD, nullptr, ScreenHandler.HandleFilamentOption, ScreenHandler.HandleFilamentLoadUnload), #endif #if ENABLED(PIDTEMP) VPHELPER(VP_E0_PID_P, &thermalManager.temp_hotend[0].pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), VPHELPER(VP_E0_PID_I, &thermalManager.temp_hotend[0].pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), VPHELPER(VP_E0_PID_D, &thermalManager.temp_hotend[0].pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_PID_AUTOTUNE_E0, nullptr, &ScreenHandler.HandlePIDAutotune, nullptr), + VPHELPER(VP_PID_AUTOTUNE_E0, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), #endif #endif #if HOTENDS >= 2 - VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleTemperatureChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Flowrate_E1, nullptr, ScreenHandler.HandleFlowRateChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_MOVE_E1, nullptr, &ScreenHandler.HandleManualExtrude, nullptr), - VPHELPER(VP_E1_CONTROL, &thermalManager.temp_hotend[1].target, &ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_E1_STATUS, &thermalManager.temp_hotend[1].target, nullptr, &ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), + VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Flowrate_E1, nullptr, ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_MOVE_E1, nullptr, ScreenHandler.HandleManualExtrude, nullptr), + VPHELPER(VP_E1_CONTROL, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_E1_STATUS, &thermalManager.temp_hotend[1].target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), #endif #if HAS_HEATED_BED VPHELPER(VP_T_Bed_Is, &thermalManager.temp_bed.celsius, nullptr, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_T_Bed_Set, &thermalManager.temp_bed.target, ScreenHandler.HandleTemperatureChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_BED_CONTROL, &thermalManager.temp_bed.target, &ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_BED_STATUS, &thermalManager.temp_bed.target, nullptr, &ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_T_Bed_Set, &thermalManager.temp_bed.target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_BED_CONTROL, &thermalManager.temp_bed.target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_BED_STATUS, &thermalManager.temp_bed.target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), #if ENABLED(PIDTEMP) VPHELPER(VP_BED_PID_P, &thermalManager.temp_bed.pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), VPHELPER(VP_BED_PID_I, &thermalManager.temp_bed.pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), VPHELPER(VP_BED_PID_D, &thermalManager.temp_bed.pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_PID_AUTOTUNE_BED, nullptr, &ScreenHandler.HandlePIDAutotune, nullptr), + VPHELPER(VP_PID_AUTOTUNE_BED, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), #endif #endif // Fan Data #if HAS_FAN #define FAN_VPHELPER(N) \ - VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], ScreenHandler.DGUSLCD_PercentageToUint8, &ScreenHandler.DGUSLCD_SendPercentageToDisplay), \ - VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], &ScreenHandler.HandleFanControl, nullptr), \ - VPHELPER(VP_FAN##N##_STATUS, &thermalManager.fan_speed[N], nullptr, &ScreenHandler.DGUSLCD_SendFanStatusToDisplay), + VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], ScreenHandler.DGUSLCD_PercentageToUint8, ScreenHandler.DGUSLCD_SendPercentageToDisplay), \ + VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], ScreenHandler.HandleFanControl, nullptr), \ + VPHELPER(VP_FAN##N##_STATUS, &thermalManager.fan_speed[N], nullptr, ScreenHandler.DGUSLCD_SendFanStatusToDisplay), REPEAT(FAN_COUNT, FAN_VPHELPER) #endif // Feedrate - VPHELPER(VP_Feedrate_Percentage, &feedrate_percentage, ScreenHandler.DGUSLCD_SetValueDirectly, &ScreenHandler.DGUSLCD_SendWordValueToDisplay ), + VPHELPER(VP_Feedrate_Percentage, &feedrate_percentage, ScreenHandler.DGUSLCD_SetValueDirectly, ScreenHandler.DGUSLCD_SendWordValueToDisplay), // Position Data VPHELPER(VP_XPos, ¤t_position.x, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), @@ -429,23 +421,23 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_ZPos, ¤t_position.z, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), // Print Progress - VPHELPER(VP_PrintProgress_Percentage, nullptr, nullptr, ScreenHandler.DGUSLCD_SendPrintProgressToDisplay ), + VPHELPER(VP_PrintProgress_Percentage, nullptr, nullptr, ScreenHandler.DGUSLCD_SendPrintProgressToDisplay), // Print Time - VPHELPER_STR(VP_PrintTime, nullptr, VP_PrintTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintTimeToDisplay ), + VPHELPER_STR(VP_PrintTime, nullptr, VP_PrintTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintTimeToDisplay), #if ENABLED(PRINTCOUNTER) - VPHELPER_STR(VP_PrintAccTime, nullptr, VP_PrintAccTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintAccTimeToDisplay ), - VPHELPER_STR(VP_PrintsTotal, nullptr, VP_PrintsTotal_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintsTotalToDisplay ), + VPHELPER_STR(VP_PrintAccTime, nullptr, VP_PrintAccTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintAccTimeToDisplay), + VPHELPER_STR(VP_PrintsTotal, nullptr, VP_PrintsTotal_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintsTotalToDisplay), #endif VPHELPER(VP_X_STEP_PER_MM, &planner.settings.axis_steps_per_mm[X_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), VPHELPER(VP_Y_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Y_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), VPHELPER(VP_Z_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Z_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), - #if HOTENDS >= 1 + #if HAS_HOTEND VPHELPER(VP_E0_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(0)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), - #endif - #if HOTENDS >= 2 - VPHELPER(VP_E1_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(1)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + #if HOTENDS >= 2 + VPHELPER(VP_E1_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(1)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + #endif #endif // SDCard File listing. @@ -462,7 +454,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_SD_AbortPrintConfirmed, nullptr, ScreenHandler.DGUSLCD_SD_ReallyAbort, nullptr), VPHELPER(VP_SD_Print_Setting, nullptr, ScreenHandler.DGUSLCD_SD_PrintTune, nullptr), #if HAS_BED_PROBE - VPHELPER(VP_SD_Print_ProbeOffsetZ, &probe.offset.z, ScreenHandler.HandleProbeOffsetZChanged, &ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<2>), + VPHELPER(VP_SD_Print_ProbeOffsetZ, &probe.offset.z, ScreenHandler.HandleProbeOffsetZChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<2>), #if ENABLED(BABYSTEPPING) VPHELPER(VP_SD_Print_LiveAdjustZ, nullptr, ScreenHandler.HandleLiveAdjustZ, nullptr), #endif @@ -474,10 +466,10 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { #endif // Messages for the User, shared by the popup and the kill screen. They cant be autouploaded as we do not buffer content. - { .VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, VPHELPER(0, 0, 0, 0) // must be last entry. }; diff --git a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.h b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.h index d18989a48b007..0c3a6aa35278f 100644 --- a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.h +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSDisplayDef.h @@ -51,7 +51,7 @@ enum DGUSLCD_Screens : uint8_t { DGUSLCD_SCREEN_KILL = 250, ///< Kill Screen. Must always be 250 (to be able to display "Error wrong LCD Version") DGUSLCD_SCREEN_WAITING = 251, DGUSLCD_SCREEN_POPUP = 252, ///< special target, popup screen will also return this code to say "return to previous screen" - DGUSLDC_SCREEN_UNUSED = 255 + DGUSLCD_SCREEN_UNUSED = 255 }; // Display Memory layout used (T5UID) diff --git a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp index f3729d1253450..eab5e2750737a 100644 --- a/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/hiprecy/DGUSScreenHandler.cpp @@ -249,7 +249,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { switch (var.VP) { default: return; - #if HOTENDS >= 1 + #if HAS_HOTEND case VP_E0_PID_P: newvalue = value; break; case VP_E0_PID_I: newvalue = scalePID_i(value); break; case VP_E0_PID_D: newvalue = scalePID_d(value); break; @@ -329,18 +329,18 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { } if (filament_data.action == 0) { // Go back to utility screen - #if HOTENDS >= 1 + #if HAS_HOTEND thermalManager.setTargetHotend(e_temp, ExtUI::extruder_t::E0); - #endif - #if HOTENDS >= 2 - thermalManager.setTargetHotend(e_temp, ExtUI::extruder_t::E1); + #if HOTENDS >= 2 + thermalManager.setTargetHotend(e_temp, ExtUI::extruder_t::E1); + #endif #endif GotoScreen(DGUSLCD_SCREEN_UTILITY); } else { // Go to the preheat screen to show the heating progress switch (var.VP) { default: return; - #if HOTENDS >= 1 + #if HAS_HOTEND case VP_E0_FILAMENT_LOAD_UNLOAD: filament_data.extruder = ExtUI::extruder_t::E0; thermalManager.setTargetHotend(e_temp, filament_data.extruder); diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp index 3d68df7b7f02f..7d8581c9f37ce 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp @@ -120,11 +120,11 @@ const uint16_t VPList_Boot[] PROGMEM = { const uint16_t VPList_Main[] PROGMEM = { // VP_M117, for completeness, but it cannot be auto-uploaded. - #if HOTENDS >= 1 + #if HAS_HOTEND MKSLIST_E_ITEM(0) VP_E0_STATUS, - #endif - #if HOTENDS >= 2 - MKSLIST_E_ITEM(1) + #if HOTENDS >= 2 + MKSLIST_E_ITEM(1) VP_E1_STATUS, + #endif #endif #if HAS_HEATED_BED VP_T_Bed_Is, VP_T_Bed_Set, VP_BED_STATUS, @@ -498,20 +498,6 @@ const char MarlinVersion[] PROGMEM = SHORT_BUILD_VERSION; const char H43Version[] PROGMEM = "MKS H43_V1.30"; const char Updata_Time[] PROGMEM = STRING_DISTRIBUTION_DATE; -// Helper to define a DGUS_VP_Variable for common use cases. -#define VPHELPER(VPADR, VPADRVAR, RXFPTR, TXFPTR) \ - { \ - .VP = VPADR, .memadr = VPADRVAR, .size = sizeof(VPADRVAR), \ - .set_by_display_handler = RXFPTR, .send_to_display_handler = TXFPTR \ - } - -// Helper to define a DGUS_VP_Variable when the sizeo of the var cannot be determined automaticalyl (eg. a string) -#define VPHELPER_STR(VPADR, VPADRVAR, STRLEN, RXFPTR, TXFPTR) \ - { \ - .VP = VPADR, .memadr = VPADRVAR, .size = STRLEN, \ - .set_by_display_handler = RXFPTR, .send_to_display_handler = TXFPTR \ - } - const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { // Helper to detect touch events VPHELPER(VP_SCREENCHANGE, nullptr, ScreenHandler.ScreenChangeHook, nullptr), @@ -522,109 +508,109 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_CONFIRMED, nullptr, ScreenHandler.ScreenConfirmedOK, nullptr), // Back Button - VPHELPER(VP_BACK_PAGE, nullptr, &ScreenHandler.ScreenBackChange, nullptr), - VPHELPER(VP_TEMP_ALL_OFF, nullptr, &ScreenHandler.HandleAllHeatersOff, nullptr), + VPHELPER(VP_BACK_PAGE, nullptr, ScreenHandler.ScreenBackChange, nullptr), + VPHELPER(VP_TEMP_ALL_OFF, nullptr, ScreenHandler.HandleAllHeatersOff, nullptr), - VPHELPER(VP_MOVE_X, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Y, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Z, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_HOME_ALL, nullptr, &ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_X, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Y, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Z, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_HOME_ALL, nullptr, ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_X_HOME, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_Y_HOME, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_Z_HOME, nullptr, &ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_X_HOME, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_Y_HOME, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_Z_HOME, nullptr, ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_DISTANCE, &manualMoveStep, &ScreenHandler.GetManualMovestep, nullptr), + VPHELPER(VP_MOVE_DISTANCE, &manualMoveStep, ScreenHandler.GetManualMovestep, nullptr), - VPHELPER(VP_MOTOR_LOCK_UNLOK, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_LEVEL_POINT, nullptr, &ScreenHandler.ManualAssistLeveling, nullptr), + VPHELPER(VP_MOTOR_LOCK_UNLOK, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_LEVEL_POINT, nullptr, ScreenHandler.ManualAssistLeveling, nullptr), #if ENABLED(POWER_LOSS_RECOVERY) - VPHELPER(VP_POWER_LOSS_RECOVERY, nullptr, &ScreenHandler.HandlePowerLossRecovery, nullptr), + VPHELPER(VP_POWER_LOSS_RECOVERY, nullptr, ScreenHandler.HandlePowerLossRecovery, nullptr), #endif - VPHELPER(VP_SETTINGS, nullptr, &ScreenHandler.HandleSettings, nullptr), + VPHELPER(VP_SETTINGS, nullptr, ScreenHandler.HandleSettings, nullptr), #if ENABLED(SINGLE_Z_CALIBRATION) - VPHELPER(VP_Z_CALIBRATE, nullptr, &ScreenHandler.HandleZCalibration, nullptr), + VPHELPER(VP_Z_CALIBRATE, nullptr, ScreenHandler.HandleZCalibration, nullptr), #endif #if ENABLED(FIRST_LAYER_CAL) - VPHELPER(VP_Z_FIRST_LAYER_CAL, nullptr, &ScreenHandler.HandleFirstLayerCal, nullptr), + VPHELPER(VP_Z_FIRST_LAYER_CAL, nullptr, ScreenHandler.HandleFirstLayerCal, nullptr), #endif - {.VP = VP_MARLIN_VERSION, .memadr = (void *)MarlinVersion, .size = VP_MARLIN_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, + {.VP = VP_MARLIN_VERSION, .memadr = (void *)MarlinVersion, .size = VP_MARLIN_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, // M117 LCD String (We don't need the string in memory but "just" push it to the display on demand, hence the nullptr - {.VP = VP_M117, .memadr = nullptr, .size = VP_M117_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplay}, - {.VP = VP_MKS_H43_VERSION, .memadr = (void *)H43Version, .size = VP_MKS_H43_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, - {.VP = VP_MKS_H43_UpdataVERSION, .memadr = (void *)Updata_Time, .size = VP_MKS_H43_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, + {.VP = VP_M117, .memadr = nullptr, .size = VP_M117_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplay}, + {.VP = VP_MKS_H43_VERSION, .memadr = (void *)H43Version, .size = VP_MKS_H43_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, + {.VP = VP_MKS_H43_UpdataVERSION, .memadr = (void *)Updata_Time, .size = VP_MKS_H43_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, // Temperature Data - #if HOTENDS >= 1 - VPHELPER(VP_T_E0_Is, &thermalManager.temp_hotend[0].celsius, nullptr, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_T_E0_Set, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleTemperatureChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Flowrate_E0, &planner.flow_percentage[ExtUI::extruder_t::E0], ScreenHandler.HandleFlowRateChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), + #if HAS_HOTEND + VPHELPER(VP_T_E0_Is, &thermalManager.temp_hotend[0].celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), + VPHELPER(VP_T_E0_Set, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Flowrate_E0, &planner.flow_percentage[ExtUI::extruder_t::E0], ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_EPos, &destination.e, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), - VPHELPER(VP_MOVE_E0, nullptr, &ScreenHandler.HandleManualExtrude, nullptr), - VPHELPER(VP_E0_CONTROL, &thermalManager.temp_hotend[0].target, &ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_E0_STATUS, &thermalManager.temp_hotend[0].target, nullptr, &ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_MOVE_E0, nullptr, ScreenHandler.HandleManualExtrude, nullptr), + VPHELPER(VP_E0_CONTROL, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_E0_STATUS, &thermalManager.temp_hotend[0].target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), #if ENABLED(DGUS_PREHEAT_UI) - VPHELPER(VP_E0_BED_PREHEAT, nullptr, &ScreenHandler.HandlePreheat, nullptr), + VPHELPER(VP_E0_BED_PREHEAT, nullptr, ScreenHandler.HandlePreheat, nullptr), #endif #if ENABLED(PIDTEMP) VPHELPER(VP_E0_PID_P, &thermalManager.temp_hotend[0].pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), VPHELPER(VP_E0_PID_I, &thermalManager.temp_hotend[0].pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), VPHELPER(VP_E0_PID_D, &thermalManager.temp_hotend[0].pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_PID_AUTOTUNE_E0, nullptr, &ScreenHandler.HandlePIDAutotune, nullptr), + VPHELPER(VP_PID_AUTOTUNE_E0, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), #endif #if ENABLED(DGUS_FILAMENT_LOADUNLOAD) - VPHELPER(VP_LOAD_Filament, nullptr, &ScreenHandler.MKS_FilamentLoad, nullptr), - VPHELPER(VP_UNLOAD_Filament, nullptr, &ScreenHandler.MKS_FilamentUnLoad, nullptr), - VPHELPER(VP_Filament_distance, &distanceFilament, &ScreenHandler.GetManualFilament, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Filament_speed, &filamentSpeed_mm_s, &ScreenHandler.GetManualFilamentSpeed, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_LOAD_Filament, nullptr, ScreenHandler.MKS_FilamentLoad, nullptr), + VPHELPER(VP_UNLOAD_Filament, nullptr, ScreenHandler.MKS_FilamentUnLoad, nullptr), + VPHELPER(VP_Filament_distance, &distanceFilament, ScreenHandler.GetManualFilament, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Filament_speed, &filamentSpeed_mm_s, ScreenHandler.GetManualFilamentSpeed, ScreenHandler.DGUSLCD_SendWordValueToDisplay), #endif #endif #if HOTENDS >= 2 - VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleTemperatureChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Flowrate_E1, &planner.flow_percentage[ExtUI::extruder_t::E1], ScreenHandler.HandleFlowRateChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_MOVE_E1, nullptr, &ScreenHandler.HandleManualExtrude, nullptr), - VPHELPER(VP_E1_CONTROL, &thermalManager.temp_hotend[1].target, &ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_E1_STATUS, &thermalManager.temp_hotend[1].target, nullptr, &ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), + VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Flowrate_E1, &planner.flow_percentage[ExtUI::extruder_t::E1], ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_MOVE_E1, nullptr, ScreenHandler.HandleManualExtrude, nullptr), + VPHELPER(VP_E1_CONTROL, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_E1_STATUS, &thermalManager.temp_hotend[1].target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), #if ENABLED(DGUS_FILAMENT_LOADUNLOAD) - VPHELPER(VP_Filament_distance, &distanceFilament, &ScreenHandler.GetManualFilament, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), - VPHELPER(VP_Filament_speed, &filamentSpeed_mm_s, &ScreenHandler.GetManualFilamentSpeed, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Filament_distance, &distanceFilament, ScreenHandler.GetManualFilament, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), + VPHELPER(VP_Filament_speed, &filamentSpeed_mm_s, ScreenHandler.GetManualFilamentSpeed, ScreenHandler.DGUSLCD_SendWordValueToDisplay), #endif #if ENABLED(PIDTEMP) - VPHELPER(VP_PID_AUTOTUNE_E1, nullptr, &ScreenHandler.HandlePIDAutotune, nullptr), + VPHELPER(VP_PID_AUTOTUNE_E1, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), #endif - VPHELPER(VP_E1_FILAMENT_LOAD_UNLOAD, nullptr, &ScreenHandler.HandleFilamentOption, &ScreenHandler.HandleFilamentLoadUnload), + VPHELPER(VP_E1_FILAMENT_LOAD_UNLOAD, nullptr, ScreenHandler.HandleFilamentOption, ScreenHandler.HandleFilamentLoadUnload), #endif #if HAS_HEATED_BED - VPHELPER(VP_T_Bed_Is, &thermalManager.temp_bed.celsius, nullptr, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_T_Bed_Set, &thermalManager.temp_bed.target, ScreenHandler.HandleTemperatureChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_BED_CONTROL, &thermalManager.temp_bed.target, &ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_BED_STATUS, &thermalManager.temp_bed.target, nullptr, &ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_T_Bed_Is, &thermalManager.temp_bed.celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), + VPHELPER(VP_T_Bed_Set, &thermalManager.temp_bed.target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_BED_CONTROL, &thermalManager.temp_bed.target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_BED_STATUS, &thermalManager.temp_bed.target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), #if ENABLED(PIDTEMPBED) VPHELPER(VP_BED_PID_P, &thermalManager.temp_bed.pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), VPHELPER(VP_BED_PID_I, &thermalManager.temp_bed.pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), VPHELPER(VP_BED_PID_D, &thermalManager.temp_bed.pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_PID_AUTOTUNE_BED, nullptr, &ScreenHandler.HandlePIDAutotune, nullptr), + VPHELPER(VP_PID_AUTOTUNE_BED, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), #endif #endif // Fan Data #if HAS_FAN #define FAN_VPHELPER(N) \ - VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], ScreenHandler.DGUSLCD_SetUint8, &ScreenHandler.DGUSLCD_SendFanToDisplay), \ - VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], &ScreenHandler.HandleFanControl, nullptr), \ - VPHELPER(VP_FAN##N##_STATUS, &thermalManager.fan_speed[N], nullptr, &ScreenHandler.DGUSLCD_SendFanStatusToDisplay), + VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], ScreenHandler.DGUSLCD_SetUint8, ScreenHandler.DGUSLCD_SendFanToDisplay), \ + VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], ScreenHandler.HandleFanControl, nullptr), \ + VPHELPER(VP_FAN##N##_STATUS, &thermalManager.fan_speed[N], nullptr, ScreenHandler.DGUSLCD_SendFanStatusToDisplay), REPEAT(FAN_COUNT, FAN_VPHELPER) #endif // Feedrate - VPHELPER(VP_Feedrate_Percentage, &feedrate_percentage, ScreenHandler.DGUSLCD_SetValueDirectly, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Feedrate_Percentage, &feedrate_percentage, ScreenHandler.DGUSLCD_SetValueDirectly, ScreenHandler.DGUSLCD_SendWordValueToDisplay), // Position Data VPHELPER(VP_XPos, ¤t_position.x, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), @@ -646,8 +632,11 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { // Print Progress VPHELPER(VP_PrintProgress_Percentage, nullptr, nullptr, ScreenHandler.DGUSLCD_SendPrintProgressToDisplay), - //LCD Control - VPHELPER(VP_LCD_BLK, &lcd_default_light, &ScreenHandler.LCD_BLK_Adjust, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + // LCD Control + VPHELPER(VP_LCD_BLK, &lcd_default_light, ScreenHandler.LCD_BLK_Adjust, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + + // SD File - Back + VPHELPER(VP_SD_FileSelect_Back, nullptr, ScreenHandler.SD_FileBack, nullptr), // Print Time VPHELPER_STR(VP_PrintTime, nullptr, VP_PrintTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintTimeToDisplay_MKS), @@ -665,22 +654,22 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_Y_MAX_SPEED, &planner.settings.max_feedrate_mm_s[Y_AXIS], ScreenHandler.HandleMaxSpeedChange_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), VPHELPER(VP_Z_MAX_SPEED, &planner.settings.max_feedrate_mm_s[Z_AXIS], ScreenHandler.HandleMaxSpeedChange_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), - #if HOTENDS >= 1 - VPHELPER(VP_E0_MAX_SPEED, &planner.settings.max_feedrate_mm_s[E0_AXIS], ScreenHandler.HandleExtruderMaxSpeedChange_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), - #endif - #if HOTENDS >= 2 - VPHELPER(VP_E1_MAX_SPEED, &planner.settings.max_feedrate_mm_s[E1_AXIS], ScreenHandler.HandleExtruderMaxSpeedChange_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), + #if HAS_HOTEND + VPHELPER(VP_E0_MAX_SPEED, &planner.settings.max_feedrate_mm_s[E_AXIS_N(0)], ScreenHandler.HandleExtruderMaxSpeedChange_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), + #if HOTENDS >= 2 + VPHELPER(VP_E1_MAX_SPEED, &planner.settings.max_feedrate_mm_s[E_AXIS_N(1)], ScreenHandler.HandleExtruderMaxSpeedChange_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), + #endif #endif VPHELPER(VP_X_ACC_MAX_SPEED, (uint16_t *)&planner.settings.max_acceleration_mm_per_s2[X_AXIS], ScreenHandler.HandleMaxAccChange_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_Y_ACC_MAX_SPEED, (uint16_t *)&planner.settings.max_acceleration_mm_per_s2[Y_AXIS], ScreenHandler.HandleMaxAccChange_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_Z_ACC_MAX_SPEED, (uint16_t *)&planner.settings.max_acceleration_mm_per_s2[Z_AXIS], ScreenHandler.HandleMaxAccChange_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - #if HOTENDS >= 1 - VPHELPER(VP_E0_ACC_MAX_SPEED, (uint16_t *)&planner.settings.max_acceleration_mm_per_s2[E0_AXIS], ScreenHandler.HandleExtruderAccChange_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - #endif - #if HOTENDS >= 2 - VPHELPER(VP_E1_ACC_MAX_SPEED, (uint16_t *)&planner.settings.max_acceleration_mm_per_s2[E1_AXIS], ScreenHandler.HandleExtruderAccChange_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + #if HAS_HOTEND + VPHELPER(VP_E0_ACC_MAX_SPEED, (uint16_t *)&planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(0)], ScreenHandler.HandleExtruderAccChange_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + #if HOTENDS >= 2 + VPHELPER(VP_E1_ACC_MAX_SPEED, (uint16_t *)&planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(1)], ScreenHandler.HandleExtruderAccChange_MKS, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + #endif #endif VPHELPER(VP_TRAVEL_SPEED, (uint16_t *)&planner.settings.travel_acceleration, ScreenHandler.HandleTravelAccChange_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), @@ -697,13 +686,13 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { #endif #if ENABLED(SENSORLESS_HOMING) // TMC SENSORLESS Setting - #if AXIS_HAS_STEALTHCHOP(X) + #if X_HAS_STEALTHCHOP VPHELPER(VP_TMC_X_STEP, &tmc_step.x, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendTMCStepValue), #endif - #if AXIS_HAS_STEALTHCHOP(Y) + #if Y_HAS_STEALTHCHOP VPHELPER(VP_TMC_Y_STEP, &tmc_step.y, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendTMCStepValue), #endif - #if AXIS_HAS_STEALTHCHOP(Z) + #if Z_HAS_STEALTHCHOP VPHELPER(VP_TMC_Z_STEP, &tmc_step.z, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendTMCStepValue), #endif #endif @@ -748,18 +737,17 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_MESH_LEVEL_POINT,nullptr, ScreenHandler.MeshLevel,nullptr), #if ENABLED(PREVENT_COLD_EXTRUSION) - VPHELPER(VP_Min_EX_T_E, &thermalManager.extrude_min_temp, &ScreenHandler.GetMinExtrudeTemp, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Min_EX_T_E, &thermalManager.extrude_min_temp, ScreenHandler.GetMinExtrudeTemp, ScreenHandler.DGUSLCD_SendWordValueToDisplay), #endif - VPHELPER(VP_AutoTurnOffSw, nullptr, &ScreenHandler.GetTurnOffCtrl, nullptr), + VPHELPER(VP_AutoTurnOffSw, nullptr, ScreenHandler.GetTurnOffCtrl, nullptr), - #if HOTENDS >= 1 + #if HAS_HOTEND VPHELPER(VP_E0_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(0)], ScreenHandler.HandleStepPerMMExtruderChanged_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), + #if HOTENDS >= 2 + VPHELPER(VP_E1_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(1)], ScreenHandler.HandleStepPerMMExtruderChanged_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), + #endif #endif - #if HOTENDS >= 2 - VPHELPER(VP_E1_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(1)], ScreenHandler.HandleStepPerMMExtruderChanged_MKS, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<0>), - #endif - // SDCard File listing @@ -781,8 +769,8 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_SD_AbortPrintConfirmed, nullptr, ScreenHandler.DGUSLCD_SD_ReallyAbort, nullptr), VPHELPER(VP_SD_Print_Setting, nullptr, ScreenHandler.DGUSLCD_SD_PrintTune, nullptr), #if ENABLED(BABYSTEPPING) - VPHELPER(VP_SD_Print_LiveAdjustZ, nullptr, ScreenHandler.HandleLiveAdjustZ, &ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<2>), - VPHELPER(VP_ZOffset_DE_DIS, &z_offset_add, nullptr, &ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), + VPHELPER(VP_SD_Print_LiveAdjustZ, nullptr, ScreenHandler.HandleLiveAdjustZ, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<2>), + VPHELPER(VP_ZOffset_DE_DIS, &z_offset_add, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), #endif #if HAS_BED_PROBE VPHELPER(VP_OFFSET_X, &probe.offset.x, ScreenHandler.GetOffsetValue,ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), @@ -798,15 +786,15 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { #endif // Messages for the User, shared by the popup and the kill screen. They cant be autouploaded as we do not buffer content. - //{.VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, - //{.VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, - //{.VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, - //{.VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, - - {.VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplay_Language_MKS}, - {.VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplay_Language_MKS}, - {.VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplay_Language_MKS}, - {.VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplay_Language_MKS}, + //{.VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, + //{.VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, + //{.VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, + //{.VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM}, + + {.VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplay_Language_MKS}, + {.VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplay_Language_MKS}, + {.VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplay_Language_MKS}, + {.VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplay_Language_MKS}, VPHELPER(0, 0, 0, 0) // must be last entry. }; diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h index f174f38d9604b..5c9ff02bfed96 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h @@ -59,19 +59,19 @@ extern xyz_int_t tmc_step; extern uint16_t lcd_default_light; -#if AXIS_HAS_STEALTHCHOP(X) +#if X_HAS_STEALTHCHOP extern uint16_t tmc_x_current; #endif -#if AXIS_HAS_STEALTHCHOP(Y) +#if Y_HAS_STEALTHCHOP extern uint16_t tmc_y_current; #endif -#if AXIS_HAS_STEALTHCHOP(Z) +#if Z_HAS_STEALTHCHOP extern uint16_t tmc_z_current; #endif -#if AXIS_HAS_STEALTHCHOP(E0) +#if E0_HAS_STEALTHCHOP extern uint16_t tmc_e0_current; #endif -#if AXIS_HAS_STEALTHCHOP(E1) +#if E1_HAS_STEALTHCHOP extern uint16_t tmc_e1_current; #endif @@ -238,194 +238,14 @@ enum DGUSLCD_Screens : uint8_t { DGUSLCD_SCREEN_KILL = 250, ///< Kill Screen. Must always be 250 (to be able to display "Error wrong LCD Version") DGUSLCD_SCREEN_WAITING = 251, DGUSLCD_SCREEN_POPUP = 252, ///< special target, popup screen will also return this code to say "return to previous screen" - DGUSLDC_SCREEN_UNUSED = 255 + DGUSLCD_SCREEN_UNUSED = 255 }; -// Display Memory layout used (T5UID) -// Except system variables this is arbitrary, just to organize stuff.... - -// 0x0000 .. 0x0FFF -- System variables and reserved by the display -// 0x1000 .. 0x1FFF -- Variables to never change location, regardless of UI Version -// 0x2000 .. 0x2FFF -- Controls (VPs that will trigger some action) -// 0x3000 .. 0x4FFF -- Marlin Data to be displayed -// 0x5000 .. -- SPs (if we want to modify display elements, e.g change color or like) -- currently unused - -// As there is plenty of space (at least most displays have >8k RAM), we do not pack them too tight, -// so that we can keep variables nicely together in the address space. - -// UI Version always on 0x1000...0x1002 so that the firmware can check this and bail out. - -// constexpr uint16_t VP_UI_VERSION_MAJOR = 0x1000; // Major -- incremented when incompatible -// constexpr uint16_t VP_UI_VERSION_MINOR = 0x1001; // Minor -- incremented on new features, but compatible -// constexpr uint16_t VP_UI_VERSION_PATCH = 0x1002; // Patch -- fixed which do not change functionality. -// constexpr uint16_t VP_UI_FLAVOUR = 0x1010; // lets reserve 16 bytes here to determine if UI is suitable for this Marlin. tbd. - -// Storage space for the Killscreen messages. 0x1100 - 0x1200 . Reused for the popup. -// constexpr uint16_t VP_MSGSTR1 = 0x1100; -// constexpr uint8_t VP_MSGSTR1_LEN = 0x20; // might be more place for it... -// constexpr uint16_t VP_MSGSTR2 = 0x1140; -// constexpr uint8_t VP_MSGSTR2_LEN = 0x20; -// constexpr uint16_t VP_MSGSTR3 = 0x1180; -// constexpr uint8_t VP_MSGSTR3_LEN = 0x20; -// constexpr uint16_t VP_MSGSTR4 = 0x11C0; -// constexpr uint8_t VP_MSGSTR4_LEN = 0x20; - -// Screenchange request for screens that only make sense when printer is idle. -// e.g movement is only allowed if printer is not printing. -// Marlin must confirm by setting the screen manually. -// constexpr uint16_t VP_SCREENCHANGE_ASK = 0x2000; -// constexpr uint16_t VP_SCREENCHANGE = 0x2001; // Key-Return button to new menu pressed. Data contains target screen in low byte and info in high byte. -// constexpr uint16_t VP_TEMP_ALL_OFF = 0x2002; // Turn all heaters off. Value arbitrary ;)= -// constexpr uint16_t VP_SCREENCHANGE_WHENSD = 0x2003; // "Print" Button touched -- go only there if there is an SD Card. -// constexpr uint16_t VP_CONFIRMED = 0x2010; // OK on confirm screen. - -// // Buttons on the SD-Card File listing. -// constexpr uint16_t VP_SD_ScrollEvent = 0x2020; // Data: 0 for "up a directory", numbers are the amount to scroll, e.g -1 one up, 1 one down -// constexpr uint16_t VP_SD_FileSelected = 0x2022; // Number of file field selected. -// constexpr uint16_t VP_SD_FileSelectConfirm = 0x2024; // (This is a virtual VP and emulated by the Confirm Screen when a file has been confirmed) - -// constexpr uint16_t VP_SD_ResumePauseAbort = 0x2026; // Resume(Data=0), Pause(Data=1), Abort(Data=2) SD Card prints -// constexpr uint16_t VP_SD_AbortPrintConfirmed = 0x2028; // Abort print confirmation (virtual, will be injected by the confirm dialog) -// constexpr uint16_t VP_SD_Print_Setting = 0x2040; -// constexpr uint16_t VP_SD_Print_LiveAdjustZ = 0x2050; // Data: 0 down, 1 up - -// Controls for movement (we can't use the incremental / decremental feature of the display at this feature works only with 16 bit values -// (which would limit us to 655.35mm, which is likely not a problem for common setups, but i don't want to rule out hangprinters support) -// A word about the coding: The VP will be per axis and the return code will be an signed 16 bit value in 0.01 mm resolution, telling us -// the relative travel amount t he user wants to do. So eg. if the display sends us VP=2100 with value 100, the user wants us to move X by +1 mm. -// constexpr uint16_t VP_MOVE_X = 0x2100; -// constexpr uint16_t VP_MOVE_Y = 0x2102; -// constexpr uint16_t VP_MOVE_Z = 0x2104; -// constexpr uint16_t VP_MOVE_E0 = 0x2110; -// constexpr uint16_t VP_MOVE_E1 = 0x2112; -// //constexpr uint16_t VP_MOVE_E2 = 0x2114; -// //constexpr uint16_t VP_MOVE_E3 = 0x2116; -// //constexpr uint16_t VP_MOVE_E4 = 0x2118; -// //constexpr uint16_t VP_MOVE_E5 = 0x211A; -// constexpr uint16_t VP_HOME_ALL = 0x2120; -// constexpr uint16_t VP_MOTOR_LOCK_UNLOK = 0x2130; -// constexpr uint16_t VP_XYZ_HOME = 0x2132; - -// Power loss recovery -// constexpr uint16_t VP_POWER_LOSS_RECOVERY = 0x2180; - -// // Fan Control Buttons , switch between "off" and "on" -// constexpr uint16_t VP_FAN0_CONTROL = 0x2200; -// constexpr uint16_t VP_FAN1_CONTROL = 0x2202; -// constexpr uint16_t VP_FAN2_CONTROL = 0x2204; -// constexpr uint16_t VP_FAN3_CONTROL = 0x2206; - -// // Heater Control Buttons , triged between "cool down" and "heat PLA" state -// constexpr uint16_t VP_E0_CONTROL = 0x2210; -// constexpr uint16_t VP_E1_CONTROL = 0x2212; -// //constexpr uint16_t VP_E2_CONTROL = 0x2214; -// //constexpr uint16_t VP_E3_CONTROL = 0x2216; -// //constexpr uint16_t VP_E4_CONTROL = 0x2218; -// //constexpr uint16_t VP_E5_CONTROL = 0x221A; -// constexpr uint16_t VP_BED_CONTROL = 0x221C; - -// // Preheat -// constexpr uint16_t VP_E0_BED_PREHEAT = 0x2220; -// constexpr uint16_t VP_E1_BED_PREHEAT = 0x2222; -// //constexpr uint16_t VP_E2_BED_PREHEAT = 0x2224; -// //constexpr uint16_t VP_E3_BED_PREHEAT = 0x2226; -// //constexpr uint16_t VP_E4_BED_PREHEAT = 0x2228; -// //constexpr uint16_t VP_E5_BED_PREHEAT = 0x222A; - -// // Filament load and unload -// // constexpr uint16_t VP_E0_FILAMENT_LOAD_UNLOAD = 0x2300; -// // constexpr uint16_t VP_E1_FILAMENT_LOAD_UNLOAD = 0x2302; - -// // Settings store , reset - -// // PID autotune -// constexpr uint16_t VP_PID_AUTOTUNE_E0 = 0x2410; -// constexpr uint16_t VP_PID_AUTOTUNE_E1 = 0x2412; -// //constexpr uint16_t VP_PID_AUTOTUNE_E2 = 0x2414; -// //constexpr uint16_t VP_PID_AUTOTUNE_E3 = 0x2416; -// //constexpr uint16_t VP_PID_AUTOTUNE_E4 = 0x2418; -// //constexpr uint16_t VP_PID_AUTOTUNE_E5 = 0x241A; -// constexpr uint16_t VP_PID_AUTOTUNE_BED = 0x2420; -// // Calibrate Z -// constexpr uint16_t VP_Z_CALIBRATE = 0x2430; - -// First layer cal -// constexpr uint16_t VP_Z_FIRST_LAYER_CAL = 0x2500; // Data: 0 - Cancel first layer cal progress, >0 filament type have loaded - -// Firmware version on the boot screen. -// constexpr uint16_t VP_MARLIN_VERSION = 0x3000; -// constexpr uint8_t VP_MARLIN_VERSION_LEN = 16; // there is more space on the display, if needed. // Place for status messages. constexpr uint16_t VP_M117 = 0x7020; constexpr uint8_t VP_M117_LEN = 0x20; -// // Temperatures. -// constexpr uint16_t VP_T_E0_Is = 0x3060; // 4 Byte Integer -// constexpr uint16_t VP_T_E0_Set = 0x3062; // 2 Byte Integer -// constexpr uint16_t VP_T_E1_Is = 0x3064; // 4 Byte Integer -// // reserved to support up to 6 Extruders: -// constexpr uint16_t VP_T_E1_Set = 0x3066; // 2 Byte Integer -// constexpr uint16_t VP_T_E2_Is = 0x3068; // 4 Byte Integer -// constexpr uint16_t VP_T_E2_Set = 0x306A; // 2 Byte Integer -// constexpr uint16_t VP_T_E3_Is = 0x306C; // 4 Byte Integer -// constexpr uint16_t VP_T_E3_Set = 0x306E; // 2 Byte Integer -// constexpr uint16_t VP_T_E4_Is = 0x3070; // 4 Byte Integer -// constexpr uint16_t VP_T_E4_Set = 0x3072; // 2 Byte Integer -// constexpr uint16_t VP_T_E5_Is = 0x3074; // 4 Byte Integer -// constexpr uint16_t VP_T_E5_Set = 0x3076; // 2 Byte Integer -// constexpr uint16_t VP_T_E6_Is = 0x3078; // 4 Byte Integer -// constexpr uint16_t VP_T_E6_Set = 0x307A; // 2 Byte Integer -// constexpr uint16_t VP_T_E7_Is = 0x3078; // 4 Byte Integer -// constexpr uint16_t VP_T_E7_Set = 0x307A; // 2 Byte Integer - - -// constexpr uint16_t VP_T_Bed_Is = 0x3080; // 4 Byte Integer -// constexpr uint16_t VP_T_Bed_Set = 0x3082; // 2 Byte Integer - -// constexpr uint16_t VP_Flowrate_E0 = 0x3090; // 2 Byte Integer -// constexpr uint16_t VP_Flowrate_E1 = 0x3092; // 2 Byte Integer -// // reserved for up to 6 Extruders: -// constexpr uint16_t VP_Flowrate_E2 = 0x3094; -// constexpr uint16_t VP_Flowrate_E3 = 0x3096; -// constexpr uint16_t VP_Flowrate_E4 = 0x3098; -// constexpr uint16_t VP_Flowrate_E5 = 0x309A; - -// constexpr uint16_t VP_Fan0_Percentage = 0x3100; // 2 Byte Integer (0..100) -// constexpr uint16_t VP_Fan1_Percentage = 0x3102; // 2 Byte Integer (0..100) -// constexpr uint16_t VP_Fan2_Percentage = 0x3104; // 2 Byte Integer (0..100) -// constexpr uint16_t VP_Fan3_Percentage = 0x3106; // 2 Byte Integer (0..100) -// constexpr uint16_t VP_Feedrate_Percentage = 0x3108; // 2 Byte Integer (0..100) - -// Actual Position -// constexpr uint16_t VP_XPos = 0x3110; // 4 Byte Fixed point number; format xxx.yy -// constexpr uint16_t VP_YPos = 0x3112; // 4 Byte Fixed point number; format xxx.yy -// constexpr uint16_t VP_ZPos = 0x3114; // 4 Byte Fixed point number; format xxx.yy -// constexpr uint16_t VP_EPos = 0x3120; // 4 Byte Fixed point number; format xxx.yy - -// constexpr uint16_t VP_PrintProgress_Percentage = 0x3130; // 2 Byte Integer (0..100) - -// constexpr uint16_t VP_PrintTime = 0x3140; -// constexpr uint16_t VP_PrintTime_LEN = 32; - -// constexpr uint16_t VP_PrintAccTime = 0x3160; -// constexpr uint16_t VP_PrintAccTime_LEN = 32; - -// constexpr uint16_t VP_PrintsTotal = 0x3180; -// constexpr uint16_t VP_PrintsTotal_LEN = 16; - -// // SDCard File Listing -// constexpr uint16_t VP_SD_FileName_LEN = 32; // LEN is shared for all entries. -// constexpr uint16_t DGUS_SD_FILESPERSCREEN = 8; // FIXME move that info to the display and read it from there. -// constexpr uint16_t VP_SD_FileName0 = 0x3200; -// constexpr uint16_t VP_SD_FileName1 = 0x3220; -// constexpr uint16_t VP_SD_FileName2 = 0x3240; -// constexpr uint16_t VP_SD_FileName3 = 0x3260; -// constexpr uint16_t VP_SD_FileName4 = 0x3280; -// constexpr uint16_t VP_SD_FileName5 = 0x32A0; -// constexpr uint16_t VP_SD_FileName6 = 0x32C0; -// constexpr uint16_t VP_SD_FileName7 = 0x32E0; - // Heater status constexpr uint16_t VP_E0_STATUS = 0x3410; constexpr uint16_t VP_E1_STATUS = 0x3412; @@ -635,6 +455,7 @@ constexpr uint16_t SP_T_Bed_Set = 0x5040; constexpr uint16_t VP_SD_Print_LiveAdjustZ_Confirm = 0x3060; constexpr uint16_t VP_ZOffset_Distance = 0x3070; constexpr uint16_t VP_ZOffset_DE_DIS = 0x3080; + constexpr uint16_t VP_SD_FileSelect_Back = 0x3082; // SDCard File Listing constexpr uint16_t VP_SD_FileName_LEN = 32; // LEN is shared for all entries. constexpr uint16_t DGUS_SD_FILESPERSCREEN = 10; // FIXME move that info to the display and read it from there. diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp index 6d12d529a9432..aabe6fc531899 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp @@ -134,15 +134,15 @@ void DGUSScreenHandler::DGUSLCD_SendStringToDisplay_Language_MKS(DGUS_VP_Variabl void DGUSScreenHandler::DGUSLCD_SendTMCStepValue(DGUS_VP_Variable &var) { #if ENABLED(SENSORLESS_HOMING) - #if AXIS_HAS_STEALTHCHOP(X) + #if X_HAS_STEALTHCHOP tmc_step.x = stepperX.homing_threshold(); dgusdisplay.WriteVariable(var.VP, *(int16_t*)var.memadr); #endif - #if AXIS_HAS_STEALTHCHOP(Y) + #if Y_HAS_STEALTHCHOP tmc_step.y = stepperY.homing_threshold(); dgusdisplay.WriteVariable(var.VP, *(int16_t*)var.memadr); #endif - #if AXIS_HAS_STEALTHCHOP(Z) + #if Z_HAS_STEALTHCHOP tmc_step.z = stepperZ.homing_threshold(); dgusdisplay.WriteVariable(var.VP, *(int16_t*)var.memadr); #endif @@ -575,7 +575,6 @@ void DGUSScreenHandler::MeshLevel(DGUS_VP_Variable &var, void *val_ptr) { settings.save(); } else if (mesh_point_count == 0) { - mesh_point_count = GRID_MAX_POINTS; soft_endstop._enabled = true; settings.save(); @@ -589,6 +588,10 @@ void DGUSScreenHandler::MeshLevel(DGUS_VP_Variable &var, void *val_ptr) { #endif // MESH_BED_LEVELING } +void DGUSScreenHandler::SD_FileBack(DGUS_VP_Variable&, void*) { + GotoScreen(MKSLCD_SCREEN_HOME); +} + void DGUSScreenHandler::LCD_BLK_Adjust(DGUS_VP_Variable &var, void *val_ptr) { const uint16_t lcd_value = swap16(*(uint16_t *)val_ptr); @@ -659,7 +662,7 @@ void DGUSScreenHandler::TMC_ChangeConfig(DGUS_VP_Variable &var, void *val_ptr) { switch (var.VP) { case VP_TMC_X_STEP: #if USE_SENSORLESS - #if AXIS_HAS_STEALTHCHOP(X) + #if X_HAS_STEALTHCHOP stepperX.homing_threshold(mks_min(tmc_value, 255)); settings.save(); //tmc_step.x = stepperX.homing_threshold(); @@ -668,7 +671,7 @@ void DGUSScreenHandler::TMC_ChangeConfig(DGUS_VP_Variable &var, void *val_ptr) { break; case VP_TMC_Y_STEP: #if USE_SENSORLESS - #if AXIS_HAS_STEALTHCHOP(Y) + #if Y_HAS_STEALTHCHOP stepperY.homing_threshold(mks_min(tmc_value, 255)); settings.save(); //tmc_step.y = stepperY.homing_threshold(); @@ -677,7 +680,7 @@ void DGUSScreenHandler::TMC_ChangeConfig(DGUS_VP_Variable &var, void *val_ptr) { break; case VP_TMC_Z_STEP: #if USE_SENSORLESS - #if AXIS_HAS_STEALTHCHOP(Z) + #if Z_HAS_STEALTHCHOP stepperZ.homing_threshold(mks_min(tmc_value, 255)); settings.save(); //tmc_step.z = stepperZ.homing_threshold(); @@ -737,15 +740,9 @@ void DGUSScreenHandler::TMC_ChangeConfig(DGUS_VP_Variable &var, void *val_ptr) { break; } #if USE_SENSORLESS - #if AXIS_HAS_STEALTHCHOP(X) - tmc_step.x = stepperX.homing_threshold(); - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - tmc_step.y = stepperY.homing_threshold(); - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - tmc_step.z = stepperZ.homing_threshold(); - #endif + TERN_(X_HAS_STEALTHCHOP, tmc_step.x = stepperX.homing_threshold()); + TERN_(Y_HAS_STEALTHCHOP, tmc_step.y = stepperY.homing_threshold()); + TERN_(Z_HAS_STEALTHCHOP, tmc_step.z = stepperZ.homing_threshold()); #endif } @@ -1419,15 +1416,9 @@ bool DGUSScreenHandler::loop() { if (!booted && ELAPSED(ms, TERN(USE_MKS_GREEN_UI, 1000, BOOTSCREEN_TIMEOUT))) { booted = true; #if USE_SENSORLESS - #if AXIS_HAS_STEALTHCHOP(X) - tmc_step.x = stepperX.homing_threshold(); - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - tmc_step.y = stepperY.homing_threshold(); - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - tmc_step.z = stepperZ.homing_threshold(); - #endif + TERN_(X_HAS_STEALTHCHOP, tmc_step.x = stepperX.homing_threshold()); + TERN_(Y_HAS_STEALTHCHOP, tmc_step.y = stepperY.homing_threshold()); + TERN_(Z_HAS_STEALTHCHOP, tmc_step.z = stepperZ.homing_threshold()); #endif #if ENABLED(PREVENT_COLD_EXTRUSION) diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h index 4a67b4afda76c..7d5263c6b830c 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.h @@ -93,6 +93,7 @@ class DGUSScreenHandler { static void DGUS_RunoutInit(void); static void DGUS_ExtrudeLoadInit(void); static void LCD_BLK_Adjust(DGUS_VP_Variable &var, void *val_ptr); + static void SD_FileBack(DGUS_VP_Variable &var, void *val_ptr); // Hook for manual move. static void HandleManualMove(DGUS_VP_Variable &var, void *val_ptr); @@ -189,12 +190,12 @@ class DGUSScreenHandler { static void PrintReturn(DGUS_VP_Variable &var, void *val_ptr); #endif - // OK Button the Confirm screen. + // OK Button on the Confirm screen. static void ScreenConfirmedOK(DGUS_VP_Variable &var, void *val_ptr); - // Update data after went to new screen (by display or by GotoScreen) - // remember: store the last-displayed screen, so it can get returned to. - // (e.g for pop up messages) + // Update data after going to a new screen (by display or by GotoScreen) + // remember: store the last-displayed screen, so it can be returned to. + // (e.g for popup messages) static void UpdateNewScreen(DGUSLCD_Screens newscreen, bool popup=false); // Recall the remembered screen. diff --git a/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp b/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp index 1c2944bb4f068..af57f3dccc471 100644 --- a/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.cpp @@ -55,11 +55,11 @@ const uint16_t VPList_Main[] PROGMEM = { }; const uint16_t VPList_Temp[] PROGMEM = { - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, + #if HOTENDS >= 2 + VP_T_E1_Is, VP_T_E1_Set, + #endif #endif #if HAS_HEATED_BED VP_T_Bed_Is, VP_T_Bed_Set, @@ -69,11 +69,11 @@ const uint16_t VPList_Temp[] PROGMEM = { const uint16_t VPList_Status[] PROGMEM = { /* VP_M117, for completeness, but it cannot be auto-uploaded */ - #if HOTENDS >= 1 + #if HAS_HOTEND VP_T_E0_Is, VP_T_E0_Set, - #endif - #if HOTENDS >= 2 - VP_T_E1_Is, VP_T_E1_Set, + #if HOTENDS >= 2 + VP_T_E1_Is, VP_T_E1_Set, + #endif #endif #if HAS_HEATED_BED VP_T_Bed_Is, VP_T_Bed_Set, @@ -90,72 +90,40 @@ const uint16_t VPList_Status[] PROGMEM = { const uint16_t VPList_Status2[] PROGMEM = { // VP_M117, for completeness, but it cannot be auto-uploaded - #if HOTENDS >= 1 + #if HAS_HOTEND VP_Flowrate_E0, - #endif - #if HOTENDS >= 2 - VP_Flowrate_E1, + #if HOTENDS >= 2 + VP_Flowrate_E1, + #endif #endif VP_PrintProgress_Percentage, VP_PrintTime, 0x0000 }; - -const uint16_t VPList_ManualMove[] PROGMEM = { - VP_XPos, VP_YPos, VP_ZPos, - 0x0000 -}; - -const uint16_t VPList_ManualExtrude[] PROGMEM = { - VP_EPos, - 0x0000 -}; - -const uint16_t VPList_FanAndFeedrate[] PROGMEM = { - VP_Feedrate_Percentage, VP_Fan0_Percentage, - 0x0000 -}; - -const uint16_t VPList_SD_FlowRates[] PROGMEM = { - VP_Flowrate_E0, VP_Flowrate_E1, - 0x0000 -}; - -const uint16_t VPList_SDFileList[] PROGMEM = { - VP_SD_FileName0, VP_SD_FileName1, VP_SD_FileName2, VP_SD_FileName3, VP_SD_FileName4, - 0x0000 -}; - -const uint16_t VPList_SD_PrintManipulation[] PROGMEM = { - VP_PrintProgress_Percentage, VP_PrintTime, - 0x0000 -}; +const uint16_t VPList_ManualMove[] PROGMEM = { VP_XPos, VP_YPos, VP_ZPos, 0x0000 }; +const uint16_t VPList_ManualExtrude[] PROGMEM = { VP_EPos, 0x0000 }; +const uint16_t VPList_FanAndFeedrate[] PROGMEM = { VP_Feedrate_Percentage, VP_Fan0_Percentage, 0x0000 }; +const uint16_t VPList_SD_FlowRates[] PROGMEM = { VP_Flowrate_E0, VP_Flowrate_E1, 0x0000 }; +const uint16_t VPList_SDFileList[] PROGMEM = { VP_SD_FileName0, VP_SD_FileName1, VP_SD_FileName2, VP_SD_FileName3, VP_SD_FileName4, 0x0000 }; +const uint16_t VPList_SD_PrintManipulation[] PROGMEM = { VP_PrintProgress_Percentage, VP_PrintTime, 0x0000 }; const struct VPMapping VPMap[] PROGMEM = { - { DGUSLCD_SCREEN_BOOT, VPList_Boot }, - { DGUSLCD_SCREEN_MAIN, VPList_Main }, - { DGUSLCD_SCREEN_TEMPERATURE, VPList_Temp }, - { DGUSLCD_SCREEN_STATUS, VPList_Status }, - { DGUSLCD_SCREEN_STATUS2, VPList_Status2 }, - { DGUSLCD_SCREEN_MANUALMOVE, VPList_ManualMove }, - { DGUSLCD_SCREEN_MANUALEXTRUDE, VPList_ManualExtrude }, - { DGUSLCD_SCREEN_FANANDFEEDRATE, VPList_FanAndFeedrate }, - { DGUSLCD_SCREEN_FLOWRATES, VPList_SD_FlowRates }, + { DGUSLCD_SCREEN_BOOT, VPList_Boot }, + { DGUSLCD_SCREEN_MAIN, VPList_Main }, + { DGUSLCD_SCREEN_TEMPERATURE, VPList_Temp }, + { DGUSLCD_SCREEN_STATUS, VPList_Status }, + { DGUSLCD_SCREEN_STATUS2, VPList_Status2 }, + { DGUSLCD_SCREEN_MANUALMOVE, VPList_ManualMove }, + { DGUSLCD_SCREEN_MANUALEXTRUDE, VPList_ManualExtrude }, + { DGUSLCD_SCREEN_FANANDFEEDRATE, VPList_FanAndFeedrate }, + { DGUSLCD_SCREEN_FLOWRATES, VPList_SD_FlowRates }, { DGUSLCD_SCREEN_SDPRINTMANIPULATION, VPList_SD_PrintManipulation }, - { DGUSLCD_SCREEN_SDFILELIST, VPList_SDFileList }, + { DGUSLCD_SCREEN_SDFILELIST, VPList_SDFileList }, { 0 , nullptr } // List is terminated with an nullptr as table entry. }; const char MarlinVersion[] PROGMEM = SHORT_BUILD_VERSION; -// Helper to define a DGUS_VP_Variable for common use cases. -#define VPHELPER(VPADR, VPADRVAR, RXFPTR, TXFPTR ) { .VP=VPADR, .memadr=VPADRVAR, .size=sizeof(VPADRVAR), \ - .set_by_display_handler = RXFPTR, .send_to_display_handler = TXFPTR } - -// Helper to define a DGUS_VP_Variable when the sizeo of the var cannot be determined automaticalyl (eg. a string) -#define VPHELPER_STR(VPADR, VPADRVAR, STRLEN, RXFPTR, TXFPTR ) { .VP=VPADR, .memadr=VPADRVAR, .size=STRLEN, \ - .set_by_display_handler = RXFPTR, .send_to_display_handler = TXFPTR } - const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { // Helper to detect touch events VPHELPER(VP_SCREENCHANGE, nullptr, ScreenHandler.ScreenChangeHook, nullptr), @@ -165,72 +133,71 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { #endif VPHELPER(VP_CONFIRMED, nullptr, ScreenHandler.ScreenConfirmedOK, nullptr), - VPHELPER(VP_TEMP_ALL_OFF, nullptr, &ScreenHandler.HandleAllHeatersOff, nullptr), + VPHELPER(VP_TEMP_ALL_OFF, nullptr, ScreenHandler.HandleAllHeatersOff, nullptr), #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) - VPHELPER(VP_MOVE_OPTION, &distanceToMove, &ScreenHandler.HandleManualMoveOption, nullptr), + VPHELPER(VP_MOVE_OPTION, &distanceToMove, ScreenHandler.HandleManualMoveOption, nullptr), #endif #if ENABLED(DGUS_UI_MOVE_DIS_OPTION) - VPHELPER(VP_MOVE_X, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Y, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Z, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_HOME_ALL, &distanceToMove, &ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_X, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Y, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Z, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_HOME_ALL, &distanceToMove, ScreenHandler.HandleManualMove, nullptr), #else - VPHELPER(VP_MOVE_X, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Y, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_MOVE_Z, nullptr, &ScreenHandler.HandleManualMove, nullptr), - VPHELPER(VP_HOME_ALL, nullptr, &ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_X, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Y, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_MOVE_Z, nullptr, ScreenHandler.HandleManualMove, nullptr), + VPHELPER(VP_HOME_ALL, nullptr, ScreenHandler.HandleManualMove, nullptr), #endif - VPHELPER(VP_MOTOR_LOCK_UNLOK, nullptr, &ScreenHandler.HandleMotorLockUnlock, nullptr), + VPHELPER(VP_MOTOR_LOCK_UNLOK, nullptr, ScreenHandler.HandleMotorLockUnlock, nullptr), #if ENABLED(POWER_LOSS_RECOVERY) - VPHELPER(VP_POWER_LOSS_RECOVERY, nullptr, &ScreenHandler.HandlePowerLossRecovery, nullptr), + VPHELPER(VP_POWER_LOSS_RECOVERY, nullptr, ScreenHandler.HandlePowerLossRecovery, nullptr), #endif - VPHELPER(VP_SETTINGS, nullptr, &ScreenHandler.HandleSettings, nullptr), + VPHELPER(VP_SETTINGS, nullptr, ScreenHandler.HandleSettings, nullptr), - { .VP = VP_MARLIN_VERSION, .memadr = (void*)MarlinVersion, .size = VP_MARLIN_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler =&ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MARLIN_VERSION, .memadr = (void*)MarlinVersion, .size = VP_MARLIN_VERSION_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, // M117 LCD String (We don't need the string in memory but "just" push it to the display on demand, hence the nullptr - { .VP = VP_M117, .memadr = nullptr, .size = VP_M117_LEN, .set_by_display_handler = nullptr, .send_to_display_handler =&ScreenHandler.DGUSLCD_SendStringToDisplay }, + { .VP = VP_M117, .memadr = nullptr, .size = VP_M117_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplay }, // Temperature Data - #if HOTENDS >= 1 + #if HAS_HOTEND VPHELPER(VP_T_E0_Is, nullptr, nullptr, SET_VARIABLE(getActualTemp_celsius, E0, long)), - VPHELPER(VP_T_E0_Set, nullptr, GET_VARIABLE(setTargetTemp_celsius, E0), - SET_VARIABLE(getTargetTemp_celsius, E0)), - VPHELPER(VP_Flowrate_E0, nullptr, ScreenHandler.HandleFlowRateChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_T_E0_Set, nullptr, GET_VARIABLE(setTargetTemp_celsius, E0), SET_VARIABLE(getTargetTemp_celsius, E0)), + VPHELPER(VP_Flowrate_E0, nullptr, ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), VPHELPER(VP_EPos, &destination.e, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), - VPHELPER(VP_MOVE_E0, nullptr, &ScreenHandler.HandleManualExtrude, nullptr), - VPHELPER(VP_E0_CONTROL, &thermalManager.temp_hotend[0].target, &ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_E0_STATUS, &thermalManager.temp_hotend[0].target, nullptr, &ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_MOVE_E0, nullptr, ScreenHandler.HandleManualExtrude, nullptr), + VPHELPER(VP_E0_CONTROL, &thermalManager.temp_hotend[0].target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_E0_STATUS, &thermalManager.temp_hotend[0].target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), #if ENABLED(DGUS_PREHEAT_UI) - VPHELPER(VP_E0_BED_PREHEAT, nullptr, &ScreenHandler.HandlePreheat, nullptr), + VPHELPER(VP_E0_BED_PREHEAT, nullptr, ScreenHandler.HandlePreheat, nullptr), #endif #if ENABLED(PIDTEMP) VPHELPER(VP_E0_PID_P, &thermalManager.temp_hotend[0].pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), VPHELPER(VP_E0_PID_I, &thermalManager.temp_hotend[0].pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), VPHELPER(VP_E0_PID_D, &thermalManager.temp_hotend[0].pid.Kd, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), - VPHELPER(VP_PID_AUTOTUNE_E0, nullptr, &ScreenHandler.HandlePIDAutotune, nullptr), + VPHELPER(VP_PID_AUTOTUNE_E0, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), #endif #if ENABLED(DGUS_FILAMENT_LOADUNLOAD) - VPHELPER(VP_E0_FILAMENT_LOAD_UNLOAD, nullptr, &ScreenHandler.HandleFilamentOption, &ScreenHandler.HandleFilamentLoadUnload), + VPHELPER(VP_E0_FILAMENT_LOAD_UNLOAD, nullptr, ScreenHandler.HandleFilamentOption, ScreenHandler.HandleFilamentLoadUnload), #endif #endif #if HOTENDS >= 2 - VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleTemperatureChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_Flowrate_E1, nullptr, ScreenHandler.HandleFlowRateChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_MOVE_E1, nullptr, &ScreenHandler.HandleManualExtrude, nullptr), - VPHELPER(VP_E1_CONTROL, &thermalManager.temp_hotend[1].target, &ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_E1_STATUS, &thermalManager.temp_hotend[1].target, nullptr, &ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_T_E1_Is, &thermalManager.temp_hotend[1].celsius, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<0>), + VPHELPER(VP_T_E1_Set, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_Flowrate_E1, nullptr, ScreenHandler.HandleFlowRateChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_MOVE_E1, nullptr, ScreenHandler.HandleManualExtrude, nullptr), + VPHELPER(VP_E1_CONTROL, &thermalManager.temp_hotend[1].target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_E1_STATUS, &thermalManager.temp_hotend[1].target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), #if ENABLED(PIDTEMP) - VPHELPER(VP_PID_AUTOTUNE_E1, nullptr, &ScreenHandler.HandlePIDAutotune, nullptr), + VPHELPER(VP_PID_AUTOTUNE_E1, nullptr, ScreenHandler.HandlePIDAutotune, nullptr), #endif #endif #if HAS_HEATED_BED VPHELPER(VP_T_Bed_Is, &thermalManager.temp_bed.celsius, nullptr, ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_T_Bed_Set, &thermalManager.temp_bed.target, ScreenHandler.HandleTemperatureChanged, &ScreenHandler.DGUSLCD_SendWordValueToDisplay), - VPHELPER(VP_BED_CONTROL, &thermalManager.temp_bed.target, &ScreenHandler.HandleHeaterControl, nullptr), - VPHELPER(VP_BED_STATUS, &thermalManager.temp_bed.target, nullptr, &ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), + VPHELPER(VP_T_Bed_Set, &thermalManager.temp_bed.target, ScreenHandler.HandleTemperatureChanged, ScreenHandler.DGUSLCD_SendWordValueToDisplay), + VPHELPER(VP_BED_CONTROL, &thermalManager.temp_bed.target, ScreenHandler.HandleHeaterControl, nullptr), + VPHELPER(VP_BED_STATUS, &thermalManager.temp_bed.target, nullptr, ScreenHandler.DGUSLCD_SendHeaterStatusToDisplay), #if ENABLED(PIDTEMPBED) VPHELPER(VP_BED_PID_P, &thermalManager.temp_bed.pid.Kp, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), VPHELPER(VP_BED_PID_I, &thermalManager.temp_bed.pid.Ki, ScreenHandler.HandleTemperaturePIDChanged, ScreenHandler.DGUSLCD_SendTemperaturePID), @@ -241,14 +208,14 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { // Fan Data #if HAS_FAN #define FAN_VPHELPER(N) \ - VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], ScreenHandler.DGUSLCD_PercentageToUint8, &ScreenHandler.DGUSLCD_SendPercentageToDisplay), \ - VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], &ScreenHandler.HandleFanControl, nullptr), \ - VPHELPER(VP_FAN##N##_STATUS, &thermalManager.fan_speed[N], nullptr, &ScreenHandler.DGUSLCD_SendFanStatusToDisplay), + VPHELPER(VP_Fan##N##_Percentage, &thermalManager.fan_speed[N], ScreenHandler.DGUSLCD_PercentageToUint8, ScreenHandler.DGUSLCD_SendPercentageToDisplay), \ + VPHELPER(VP_FAN##N##_CONTROL, &thermalManager.fan_speed[N], ScreenHandler.HandleFanControl, nullptr), \ + VPHELPER(VP_FAN##N##_STATUS, &thermalManager.fan_speed[N], nullptr, ScreenHandler.DGUSLCD_SendFanStatusToDisplay), REPEAT(FAN_COUNT, FAN_VPHELPER) #endif // Feedrate - VPHELPER(VP_Feedrate_Percentage, &feedrate_percentage, ScreenHandler.DGUSLCD_SetValueDirectly, &ScreenHandler.DGUSLCD_SendWordValueToDisplay ), + VPHELPER(VP_Feedrate_Percentage, &feedrate_percentage, ScreenHandler.DGUSLCD_SetValueDirectly, ScreenHandler.DGUSLCD_SendWordValueToDisplay), // Position Data VPHELPER(VP_XPos, ¤t_position.x, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), @@ -256,23 +223,23 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_ZPos, ¤t_position.z, nullptr, ScreenHandler.DGUSLCD_SendFloatAsLongValueToDisplay<2>), // Print Progress - VPHELPER(VP_PrintProgress_Percentage, nullptr, nullptr, ScreenHandler.DGUSLCD_SendPrintProgressToDisplay ), + VPHELPER(VP_PrintProgress_Percentage, nullptr, nullptr, ScreenHandler.DGUSLCD_SendPrintProgressToDisplay), // Print Time - VPHELPER_STR(VP_PrintTime, nullptr, VP_PrintTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintTimeToDisplay ), + VPHELPER_STR(VP_PrintTime, nullptr, VP_PrintTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintTimeToDisplay), #if ENABLED(PRINTCOUNTER) - VPHELPER_STR(VP_PrintAccTime, nullptr, VP_PrintAccTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintAccTimeToDisplay ), - VPHELPER_STR(VP_PrintsTotal, nullptr, VP_PrintsTotal_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintsTotalToDisplay ), + VPHELPER_STR(VP_PrintAccTime, nullptr, VP_PrintAccTime_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintAccTimeToDisplay), + VPHELPER_STR(VP_PrintsTotal, nullptr, VP_PrintsTotal_LEN, nullptr, ScreenHandler.DGUSLCD_SendPrintsTotalToDisplay), #endif VPHELPER(VP_X_STEP_PER_MM, &planner.settings.axis_steps_per_mm[X_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), VPHELPER(VP_Y_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Y_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), VPHELPER(VP_Z_STEP_PER_MM, &planner.settings.axis_steps_per_mm[Z_AXIS], ScreenHandler.HandleStepPerMMChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), - #if HOTENDS >= 1 + #if HAS_HOTEND VPHELPER(VP_E0_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(0)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), - #endif - #if HOTENDS >= 2 - VPHELPER(VP_E1_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(1)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + #if HOTENDS >= 2 + VPHELPER(VP_E1_STEP_PER_MM, &planner.settings.axis_steps_per_mm[E_AXIS_N(1)], ScreenHandler.HandleStepPerMMExtruderChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<1>), + #endif #endif // SDCard File listing. @@ -289,7 +256,7 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { VPHELPER(VP_SD_AbortPrintConfirmed, nullptr, ScreenHandler.DGUSLCD_SD_ReallyAbort, nullptr), VPHELPER(VP_SD_Print_Setting, nullptr, ScreenHandler.DGUSLCD_SD_PrintTune, nullptr), #if HAS_BED_PROBE - VPHELPER(VP_SD_Print_ProbeOffsetZ, &probe.offset.z, ScreenHandler.HandleProbeOffsetZChanged, &ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<2>), + VPHELPER(VP_SD_Print_ProbeOffsetZ, &probe.offset.z, ScreenHandler.HandleProbeOffsetZChanged, ScreenHandler.DGUSLCD_SendFloatAsIntValueToDisplay<2>), #if ENABLED(BABYSTEPPING) VPHELPER(VP_SD_Print_LiveAdjustZ, nullptr, ScreenHandler.HandleLiveAdjustZ, nullptr), #endif @@ -301,10 +268,10 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = { #endif // Messages for the User, shared by the popup and the kill screen. They cant be autouploaded as we do not buffer content. - { .VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, - { .VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = &ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR1, .memadr = nullptr, .size = VP_MSGSTR1_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR2, .memadr = nullptr, .size = VP_MSGSTR2_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR3, .memadr = nullptr, .size = VP_MSGSTR3_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, + { .VP = VP_MSGSTR4, .memadr = nullptr, .size = VP_MSGSTR4_LEN, .set_by_display_handler = nullptr, .send_to_display_handler = ScreenHandler.DGUSLCD_SendStringToDisplayPGM }, VPHELPER(0, 0, 0, 0) // must be last entry. }; diff --git a/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.h b/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.h index c1890c7c28ff2..7885621d0b1bf 100644 --- a/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.h +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSDisplayDef.h @@ -46,7 +46,7 @@ enum DGUSLCD_Screens : uint8_t { DGUSLCD_SCREEN_KILL = 250, ///< Kill Screen. Must always be 250 (to be able to display "Error wrong LCD Version") DGUSLCD_SCREEN_WAITING = 251, DGUSLCD_SCREEN_POPUP = 252, ///< special target, popup screen will also return this code to say "return to previous screen" - DGUSLDC_SCREEN_UNUSED = 255 + DGUSLCD_SCREEN_UNUSED = 255 }; // Display Memory layout used (T5UID) diff --git a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp index f05dfc6f70c92..70efb355fcda9 100644 --- a/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/origin/DGUSScreenHandler.cpp @@ -251,7 +251,7 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { switch (var.VP) { default: return; - #if HOTENDS >= 1 + #if HAS_HOTEND case VP_E0_PID_P: newvalue = value; break; case VP_E0_PID_I: newvalue = scalePID_i(value); break; case VP_E0_PID_D: newvalue = scalePID_d(value); break; @@ -331,18 +331,18 @@ void DGUSScreenHandler::HandleManualMove(DGUS_VP_Variable &var, void *val_ptr) { } if (filament_data.action == 0) { // Go back to utility screen - #if HOTENDS >= 1 + #if HAS_HOTEND thermalManager.setTargetHotend(e_temp, ExtUI::extruder_t::E0); - #endif - #if HOTENDS >= 2 - thermalManager.setTargetHotend(e_temp, ExtUI::extruder_t::E1); + #if HOTENDS >= 2 + thermalManager.setTargetHotend(e_temp, ExtUI::extruder_t::E1); + #endif #endif GotoScreen(DGUSLCD_SCREEN_UTILITY); } else { // Go to the preheat screen to show the heating progress switch (var.VP) { default: return; - #if HOTENDS >= 1 + #if HAS_HOTEND case VP_E0_FILAMENT_LOAD_UNLOAD: filament_data.extruder = ExtUI::extruder_t::E0; thermalManager.setTargetHotend(e_temp, filament_data.extruder); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/media_file_reader.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/media_file_reader.cpp index ab60579700539..ea8d4037531e5 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/media_file_reader.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/archim2-flash/media_file_reader.cpp @@ -27,9 +27,7 @@ #if ENABLED(SDSUPPORT) bool MediaFileReader::open(const char *filename) { - card.init(SD_SPI_SPEED, SDSS); - volume.init(&card); - root.openRoot(&volume); + root = CardReader::getroot(); return file.open(&root, filename, O_READ); } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/advanced_settings.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/advanced_settings.cpp index 16b2891e27d83..fd478c95a2f5d 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/advanced_settings.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_BIO_ADVANCED_SETTINGS_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_advanced_settings.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/advanced_settings.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_advanced_settings.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/advanced_settings.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_confirm_home_e.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_e.cpp similarity index 98% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_confirm_home_e.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_e.cpp index 3b555513752d5..dedda6d215b76 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_confirm_home_e.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_e.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_BIO_CONFIRM_HOME_E diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_confirm_home_e.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_e.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_confirm_home_e.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_e.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_xyz.cpp similarity index 98% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_xyz.cpp index f1abd2e76a600..bff1808d0dc4d 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_xyz.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_BIO_CONFIRM_HOME_XYZ diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_xyz.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/confirm_home_xyz.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_main_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/main_menu.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_main_menu.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/main_menu.cpp index 6897ceb91436d..ae5e7d8ab131d 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_main_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/main_menu.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_BIO_MAIN_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_main_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/main_menu.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_main_menu.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/main_menu.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_printing_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_printing_dialog_box.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.cpp index 10ed6eb14a184..86c700f235ac7 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_printing_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_BIO_PRINTING_DIALOG_BOX diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_printing_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_printing_dialog_box.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/screens.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/screens.h new file mode 100644 index 0000000000000..7294c4aa0b108 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/screens.h @@ -0,0 +1,105 @@ +/************* + * screens.h * + *************/ + +/**************************************************************************** + * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * + * * + * 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. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +/********************************* DL CACHE SLOTS ******************************/ + +// In order to reduce SPI traffic, we cache display lists (DL) in RAMG. This +// is done using the CLCD::DLCache class, which takes a unique ID for each +// cache location. These IDs are defined here: + +enum { + STATUS_SCREEN_CACHE, + MENU_SCREEN_CACHE, + TUNE_SCREEN_CACHE, + ALERT_BOX_CACHE, + SPINNER_CACHE, + ADVANCED_SETTINGS_SCREEN_CACHE, + TEMPERATURE_SCREEN_CACHE, + STEPS_SCREEN_CACHE, + MAX_FEEDRATE_SCREEN_CACHE, + MAX_VELOCITY_SCREEN_CACHE, + MAX_ACCELERATION_SCREEN_CACHE, + DEFAULT_ACCELERATION_SCREEN_CACHE, + FLOW_PERCENT_SCREEN_CACHE, + ZOFFSET_SCREEN_CACHE, + STEPPER_CURRENT_SCREEN_CACHE, + STEPPER_BUMP_SENSITIVITY_SCREEN_CACHE, + PRINTING_SCREEN_CACHE, + FILES_SCREEN_CACHE, + INTERFACE_SETTINGS_SCREEN_CACHE, + INTERFACE_SOUNDS_SCREEN_CACHE, + LOCK_SCREEN_CACHE, + DISPLAY_TIMINGS_SCREEN_CACHE +}; + +// To save MCU RAM, the status message is "baked" in to the status screen +// cache, so we reserve a large chunk of memory for the DL cache + +#define STATUS_SCREEN_DL_SIZE 4096 +#define ALERT_BOX_DL_SIZE 3072 +#define SPINNER_DL_SIZE 3072 +#define FILE_SCREEN_DL_SIZE 4160 +#define PRINTING_SCREEN_DL_SIZE 2048 + +/************************* MENU SCREEN DECLARATIONS *************************/ + +#include "../generic/base_screen.h" +#include "../generic/base_numeric_adjustment_screen.h" +#include "../generic/dialog_box_base_class.h" +#include "../generic/boot_screen.h" +#include "../generic/about_screen.h" +#include "../generic/kill_screen.h" +#include "../generic/alert_dialog_box.h" +#include "../generic/spinner_dialog_box.h" +#include "../generic/restore_failsafe_dialog_box.h" +#include "../generic/save_settings_dialog_box.h" +#include "../generic/confirm_start_print_dialog_box.h" +#include "../generic/confirm_abort_print_dialog_box.h" +#include "../generic/confirm_user_request_alert_box.h" +#include "../generic/touch_calibration_screen.h" +#include "../generic/move_axis_screen.h" +#include "../generic/steps_screen.h" +#include "../generic/feedrate_percent_screen.h" +#include "../generic/max_velocity_screen.h" +#include "../generic/max_acceleration_screen.h" +#include "../generic/default_acceleration_screen.h" +#include "../generic/temperature_screen.h" +#include "../generic/interface_sounds_screen.h" +#include "../generic/interface_settings_screen.h" +#include "../generic/lock_screen.h" +#include "../generic/endstop_state_screen.h" +#include "../generic/display_tuning_screen.h" +#include "../generic/media_player_screen.h" +#include "../generic/statistics_screen.h" +#include "../generic/stepper_current_screen.h" +#include "../generic/stepper_bump_sensitivity_screen.h" +#include "../generic/leveling_menu.h" +#include "../generic/z_offset_screen.h" +#include "../generic/files_screen.h" + +#include "bio_status_screen.h" +#include "bio_main_menu.h" +#include "bio_tune_menu.h" +#include "bio_advanced_settings.h" +#include "bio_printing_dialog_box.h" +#include "bio_confirm_home_xyz.h" +#include "bio_confirm_home_e.h" diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_status_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/status_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_status_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/status_screen.cpp index c66e4d94d8cd1..6fa4d761f678e 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_status_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/status_screen.cpp @@ -22,14 +22,14 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_BIO_STATUS_SCREEN #if ENABLED(TOUCH_UI_PORTRAIT) - #include "bio_printer_ui_portrait.h" + #include "ui_portrait.h" #else - #include "bio_printer_ui_landscape.h" + #include "ui_landscape.h" #endif #define GRID_COLS 2 diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_status_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/status_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_status_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/status_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_tune_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/tune_menu.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_tune_menu.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/tune_menu.cpp index 806f7bd1afa00..31021c31c03d8 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_tune_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/tune_menu.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_BIO_TUNE_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_tune_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/tune_menu.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_tune_menu.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/tune_menu.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_printer_ui_landscape.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/ui_landscape.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_printer_ui_landscape.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/ui_landscape.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_printer_ui_portrait.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/ui_portrait.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bio_printer_ui_portrait.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/ui_portrait.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_advanced_settings_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/advanced_settings_menu.cpp similarity index 96% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_advanced_settings_menu.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/advanced_settings_menu.cpp index 7bd149bd46130..d984dbe120ccd 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_advanced_settings_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/advanced_settings_menu.cpp @@ -1,5 +1,5 @@ /***************************************** - * cocoa_press_advance_settings_menu.cpp * + * cocoa_press/advance_settings_menu.cpp * *****************************************/ /**************************************************************************** @@ -21,9 +21,9 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" -#ifdef FTDI_COCOA_ADVANCED_SETTINGS_MENU +#ifdef COCOA_ADVANCED_SETTINGS_MENU using namespace FTDI; using namespace ExtUI; @@ -92,4 +92,4 @@ bool AdvancedSettingsMenu::onTouchEnd(uint8_t tag) { } return true; } -#endif // FTDI_COCOA_ADVANCED_SETTINGS_MENU +#endif // COCOA_ADVANCED_SETTINGS_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_advanced_settings_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/advanced_settings_menu.h similarity index 91% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_advanced_settings_menu.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/advanced_settings_menu.h index 08c0745321838..02f65572a29e0 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_advanced_settings_menu.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/advanced_settings_menu.h @@ -1,5 +1,5 @@ /*************************************** - * cocoa_press_advance_settings_menu.h * + * cocoa_press/advance_settings_menu.h * ***************************************/ /**************************************************************************** @@ -22,8 +22,8 @@ #pragma once -#define FTDI_COCOA_ADVANCED_SETTINGS_MENU -#define FTDI_COCOA_ADVANCED_SETTINGS_MENU_CLASS AdvancedSettingsMenu +#define COCOA_ADVANCED_SETTINGS_MENU +#define COCOA_ADVANCED_SETTINGS_MENU_CLASS AdvancedSettingsMenu class AdvancedSettingsMenu : public BaseScreen, public CachedScreen { public: diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_ui.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/cocoa_press_ui.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_ui.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/cocoa_press_ui.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp new file mode 100644 index 0000000000000..57c8a7505c8ae --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.cpp @@ -0,0 +1,91 @@ +/********************************* + * cocoa_press/leveling_menu.cpp * + *********************************/ + +/**************************************************************************** + * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * + * * + * 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. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#include "../config.h" +#include "../screens.h" + +#ifdef COCOA_LEVELING_MENU + +#if BOTH(HAS_BED_PROBE,BLTOUCH) + #include "../../../../feature/bltouch.h" +#endif + +using namespace FTDI; +using namespace ExtUI; +using namespace Theme; + +#define GRID_ROWS 5 +#define GRID_COLS 3 +#define BED_MESH_TITLE_POS BTN_POS(1,1), BTN_SIZE(3,1) +#define PROBE_BED_POS BTN_POS(1,2), BTN_SIZE(1,1) +#define SHOW_MESH_POS BTN_POS(2,2), BTN_SIZE(1,1) +#define EDIT_MESH_POS BTN_POS(3,2), BTN_SIZE(1,1) +#define BLTOUCH_TITLE_POS BTN_POS(1,3), BTN_SIZE(3,1) +#define BLTOUCH_RESET_POS BTN_POS(1,4), BTN_SIZE(1,1) +#define BLTOUCH_TEST_POS BTN_POS(2,4), BTN_SIZE(1,1) +#define BACK_POS BTN_POS(1,5), BTN_SIZE(3,1) + +void LevelingMenu::onRedraw(draw_mode_t what) { + if (what & BACKGROUND) { + CommandProcessor cmd; + cmd.cmd(CLEAR_COLOR_RGB(Theme::bg_color)) + .cmd(CLEAR(true,true,true)) + .tag(0); + } + + if (what & FOREGROUND) { + CommandProcessor cmd; + cmd.font(font_large) + .cmd(COLOR_RGB(bg_text_enabled)) + .text(BED_MESH_TITLE_POS, GET_TEXT_F(MSG_BED_LEVELING)) + .text(BLTOUCH_TITLE_POS, GET_TEXT_F(MSG_BLTOUCH)) + .font(font_medium).colors(normal_btn) + .tag(2).button(PROBE_BED_POS, GET_TEXT_F(MSG_PROBE_BED)) + .enabled(ENABLED(HAS_MESH)) + .tag(3).button(SHOW_MESH_POS, GET_TEXT_F(MSG_SHOW_MESH)) + .enabled(ENABLED(HAS_MESH)) + .tag(4).button(EDIT_MESH_POS, GET_TEXT_F(MSG_EDIT_MESH)) + #undef GRID_COLS + #define GRID_COLS 2 + .tag(5).button(BLTOUCH_RESET_POS, GET_TEXT_F(MSG_BLTOUCH_RESET)) + .tag(6).button(BLTOUCH_TEST_POS, GET_TEXT_F(MSG_BLTOUCH_SELFTEST)) + #undef GRID_COLS + #define GRID_COLS 3 + .colors(action_btn) + .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BACK)); + } +} + +bool LevelingMenu::onTouchEnd(uint8_t tag) { + switch (tag) { + case 1: GOTO_PREVIOUS(); break; + case 2: BedMeshViewScreen::doProbe(); break; + case 3: BedMeshViewScreen::show(); break; + case 4: BedMeshEditScreen::show(); break; + case 5: injectCommands_P(PSTR("M280 P0 S60")); break; + case 6: SpinnerDialogBox::enqueueAndWait_P(F("M280 P0 S90\nG4 P100\nM280 P0 S120")); break; + default: return false; + } + return true; +} + +#endif // COCOA_LEVELING_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.h new file mode 100644 index 0000000000000..8275380249892 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/leveling_menu.h @@ -0,0 +1,32 @@ +/******************************* + * cocoa_press/leveling_menu.h * + ******************************/ + +/**************************************************************************** + * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * + * * + * 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. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#pragma once + +#define COCOA_LEVELING_MENU +#define COCOA_LEVELING_MENU_CLASS LevelingMenu + +class LevelingMenu : public BaseScreen, public CachedScreen { + public: + static void onRedraw(draw_mode_t); + static bool onTouchEnd(uint8_t tag); +}; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_load_chocolate.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/load_chocolate.cpp similarity index 96% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_load_chocolate.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/load_chocolate.cpp index ac49df0916249..8c15cae60f99a 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_load_chocolate.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/load_chocolate.cpp @@ -1,6 +1,6 @@ -/************************************ - * cocoa_press_unload_cartridge.cpp * - ************************************/ +/********************************** + * cocoa_press/load_chocolate.cpp * + **********************************/ /**************************************************************************** * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * @@ -22,10 +22,10 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" -#include "screen_data.h" +#include "../screens.h" +#include "../screen_data.h" -#ifdef FTDI_COCOA_LOAD_CHOCOLATE_SCREEN +#ifdef COCOA_LOAD_CHOCOLATE_SCREEN #include "cocoa_press_ui.h" @@ -215,4 +215,4 @@ void LoadChocolateScreen::onIdle() { } BaseScreen::onIdle(); } -#endif // FTDI_COCOA_LOAD_CHOCOLATE_SCREEN +#endif // COCOA_LOAD_CHOCOLATE_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_load_chocolate.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/load_chocolate.h similarity index 93% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_load_chocolate.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/load_chocolate.h index 819464495b67f..4a582f0212f8e 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_load_chocolate.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/load_chocolate.h @@ -1,5 +1,5 @@ /******************************** - * cocoa_press_load_chocolate.h * + * cocoa_press/load_chocolate.h * ********************************/ /**************************************************************************** @@ -23,8 +23,8 @@ #pragma once -#define FTDI_COCOA_LOAD_CHOCOLATE_SCREEN -#define FTDI_COCOA_LOAD_CHOCOLATE_SCREEN_CLASS LoadChocolateScreen +#define COCOA_LOAD_CHOCOLATE_SCREEN +#define COCOA_LOAD_CHOCOLATE_SCREEN_CLASS LoadChocolateScreen struct LoadChocolateScreenData { uint8_t repeat_tag; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_main_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.cpp similarity index 96% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_main_menu.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.cpp index 7708b38ecaf62..a990717fb31a2 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_main_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.cpp @@ -1,5 +1,5 @@ /***************************** - * cocoa_press_main_menu.cpp * + * cocoa_press/main_menu.cpp * *****************************/ /**************************************************************************** @@ -22,9 +22,9 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" -#ifdef FTDI_COCOA_MAIN_MENU +#ifdef COCOA_MAIN_MENU using namespace FTDI; using namespace Theme; @@ -88,7 +88,7 @@ bool MainMenu::onTouchEnd(uint8_t tag) { case 8: GOTO_SCREEN(AdvancedSettingsMenu); break; case 9: injectCommands_P(PSTR("M84")); break; #if HAS_LEVELING - case 10: GOTO_SCREEN(LevelingMenu); break; + case 10: GOTO_SCREEN(LevelingMenu); break; #endif case 11: GOTO_SCREEN(AboutScreen); break; default: @@ -97,4 +97,4 @@ bool MainMenu::onTouchEnd(uint8_t tag) { return true; } -#endif // FTDI_COCOA_MAIN_MENU +#endif // COCOA_MAIN_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_main_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.h similarity index 94% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_main_menu.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.h index 7c2bb5039af0c..460bb4b81a70b 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_main_menu.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/main_menu.h @@ -1,5 +1,5 @@ /*************************** - * cocoa_press_main_menu.h * + * cocoa_press/main_menu.h * ***************************/ /**************************************************************************** @@ -23,8 +23,8 @@ #pragma once -#define FTDI_COCOA_MAIN_MENU -#define FTDI_COCOA_MAIN_MENU_CLASS MainMenu +#define COCOA_MAIN_MENU +#define COCOA_MAIN_MENU_CLASS MainMenu class MainMenu : public BaseScreen, public CachedScreen { public: diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_move_e_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/move_e_screen.cpp similarity index 94% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_move_e_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/move_e_screen.cpp index 2621ef64fe2ac..f7dbc466c7ded 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_move_e_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/move_e_screen.cpp @@ -1,5 +1,5 @@ /********************************* - * cocoa_press_move_e_screen.cpp * + * cocoa_press/move_e_screen.cpp * *********************************/ /**************************************************************************** @@ -22,10 +22,10 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" -#include "screen_data.h" +#include "../screens.h" +#include "../screen_data.h" -#ifdef FTDI_COCOA_MOVE_E_SCREEN +#ifdef COCOA_MOVE_E_SCREEN using namespace FTDI; using namespace ExtUI; @@ -60,4 +60,4 @@ void MoveEScreen::onIdle() { } BaseScreen::onIdle(); } -#endif // FTDI_COCOA_MOVE_E_SCREEN +#endif // COCOA_MOVE_E_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_move_e_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/move_e_screen.h similarity index 93% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_move_e_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/move_e_screen.h index e86a91a52986d..0cede6f0c5e22 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_move_e_screen.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/move_e_screen.h @@ -1,5 +1,5 @@ /******************************* - * cocoa_press_move_e_screen.h * + * cocoa_press/move_e_screen.h * *******************************/ /**************************************************************************** @@ -23,8 +23,8 @@ #pragma once -#define FTDI_COCOA_MOVE_E_SCREEN -#define FTDI_COCOA_MOVE_E_SCREEN_CLASS MoveEScreen +#define COCOA_MOVE_E_SCREEN +#define COCOA_MOVE_E_SCREEN_CLASS MoveEScreen class MoveEScreen : public BaseMoveAxisScreen, public CachedScreen { public: diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_move_xyz_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/move_xyz_screen.cpp similarity index 93% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_move_xyz_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/move_xyz_screen.cpp index c9442c93223bd..8e80bd53a9e15 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_move_xyz_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/move_xyz_screen.cpp @@ -1,5 +1,5 @@ /*********************************** - * cocoa_press_move_xyz_screen.cpp * + * cocoa_press/move_xyz_screen.cpp * ***********************************/ /**************************************************************************** @@ -22,10 +22,10 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" -#include "screen_data.h" +#include "../screens.h" +#include "../screen_data.h" -#ifdef FTDI_COCOA_MOVE_XYZ_SCREEN +#ifdef COCOA_MOVE_XYZ_SCREEN using namespace FTDI; using namespace ExtUI; @@ -49,4 +49,4 @@ void MoveXYZScreen::onIdle() { } BaseScreen::onIdle(); } -#endif // FTDI_COCOA_MOVE_XYZ_SCREEN +#endif // COCOA_MOVE_XYZ_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_move_xyz_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/move_xyz_screen.h similarity index 93% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_move_xyz_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/move_xyz_screen.h index 9cbec113e60d0..015f5b30e4a5e 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_move_xyz_screen.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/move_xyz_screen.h @@ -1,5 +1,5 @@ /********************************* - * cocoa_press_move_xyz_screen.h * + * cocoa_press/move_xyz_screen.h * *********************************/ /**************************************************************************** @@ -23,8 +23,8 @@ #pragma once -#define FTDI_COCOA_MOVE_XYZ_SCREEN -#define FTDI_COCOA_MOVE_XYZ_SCREEN_CLASS MoveXYZScreen +#define COCOA_MOVE_XYZ_SCREEN +#define COCOA_MOVE_XYZ_SCREEN_CLASS MoveXYZScreen class MoveXYZScreen : public BaseMoveAxisScreen, public CachedScreen { public: diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_preheat_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_menu.cpp similarity index 97% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_preheat_menu.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_menu.cpp index 92d1522360792..56e90ceb4d8df 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_preheat_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_menu.cpp @@ -1,5 +1,5 @@ /******************************** - * cocoa_press_preheat_menu.cpp * + * cocoa_press/preheat_menu.cpp * ********************************/ /**************************************************************************** @@ -20,9 +20,9 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" -#ifdef FTDI_COCOA_PREHEAT_MENU +#ifdef COCOA_PREHEAT_MENU using namespace FTDI; using namespace ExtUI; @@ -113,4 +113,4 @@ bool PreheatMenu::onTouchEnd(uint8_t tag) { return true; } -#endif // FTDI_COCOA_PREHEAT_MENU +#endif // COCOA_PREHEAT_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_preheat_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_menu.h similarity index 92% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_preheat_menu.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_menu.h index a109e42111736..46bded7df4906 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_preheat_menu.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_menu.h @@ -1,5 +1,5 @@ /****************************** - * cocoa_press_preheat_menu.h * + * cocoa_press/preheat_menu.h * ******************************/ /**************************************************************************** @@ -21,8 +21,8 @@ #pragma once -#define FTDI_COCOA_PREHEAT_MENU -#define FTDI_COCOA_PREHEAT_MENU_CLASS PreheatMenu +#define COCOA_PREHEAT_MENU +#define COCOA_PREHEAT_MENU_CLASS PreheatMenu class PreheatMenu : public BaseScreen, public CachedScreen { public: diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_preheat_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.cpp similarity index 88% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_preheat_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.cpp index a8a172b3dabad..75b1fcc9c1e63 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_preheat_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.cpp @@ -1,6 +1,6 @@ -/**************************** - * preheat_timer_screen.cpp * - ****************************/ +/*************************************** + * cocoapress/preheat_timer_screen.cpp * + ***************************************/ /**************************************************************************** * Written By Marcio Teixeira 2019 - Cocoa Press * @@ -20,10 +20,10 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" -#include "screen_data.h" +#include "../screens.h" +#include "../screen_data.h" -#ifdef FTDI_COCOA_PREHEAT_SCREEN +#ifdef COCOA_PREHEAT_SCREEN using namespace FTDI; using namespace ExtUI; @@ -84,16 +84,6 @@ void PreheatTimerScreen::draw_interaction_buttons(draw_mode_t what) { void PreheatTimerScreen::draw_adjuster(draw_mode_t what, uint8_t tag, progmem_str label, float value, int16_t x, int16_t y, int16_t w, int16_t h) { #define SUB_COLS 9 #define SUB_ROWS 2 - #define SUB_GRID_W(W) ((W)*w/SUB_COLS) - #define SUB_GRID_H(H) ((H)*h/SUB_ROWS) - #define SUB_GRID_X(X) (SUB_GRID_W((X)-1) + x) - #define SUB_GRID_Y(Y) (SUB_GRID_H((Y)-1) + y) - #define SUB_X(X) (SUB_GRID_X(X) + MARGIN_L) - #define SUB_Y(Y) (SUB_GRID_Y(Y) + MARGIN_T) - #define SUB_W(W) (SUB_GRID_W(W) - MARGIN_L - MARGIN_R) - #define SUB_H(H) (SUB_GRID_H(H) - MARGIN_T - MARGIN_B) - #define SUB_POS(X,Y) SUB_X(X), SUB_Y(Y) - #define SUB_SIZE(W,H) SUB_W(W), SUB_H(H) CommandProcessor cmd; cmd.tag(0) @@ -168,4 +158,4 @@ void PreheatTimerScreen::onIdle() { BaseScreen::onIdle(); } -#endif // FTDI_COCOA_PREHEAT_SCREEN +#endif // COCOA_PREHEAT_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_preheat_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.h similarity index 94% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_preheat_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.h index e91340a3aa8fd..9b8e2620dc69e 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_preheat_screen.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/preheat_screen.h @@ -1,5 +1,5 @@ /********************************* - * cocoapress_preheat_screen.cpp * + * cocoapress/preheat_screen.cpp * *********************************/ /**************************************************************************** @@ -21,8 +21,8 @@ #pragma once -#define FTDI_COCOA_PREHEAT_SCREEN -#define FTDI_COCOA_PREHEAT_SCREEN_CLASS PreheatTimerScreen +#define COCOA_PREHEAT_SCREEN +#define COCOA_PREHEAT_SCREEN_CLASS PreheatTimerScreen struct PreheatTimerScreenData { uint32_t start_ms; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/screens.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/screens.h new file mode 100644 index 0000000000000..3a47d6bee4833 --- /dev/null +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/screens.h @@ -0,0 +1,135 @@ +/************* + * screens.h * + *************/ + +/**************************************************************************** + * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * + * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * + * * + * 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. * + * * + * To view a copy of the GNU General Public License, go to the following * + * location: . * + ****************************************************************************/ + +#pragma once + + +/********************************* DL CACHE SLOTS ******************************/ + +// In order to reduce SPI traffic, we cache display lists (DL) in RAMG. This +// is done using the CLCD::DLCache class, which takes a unique ID for each +// cache location. These IDs are defined here: + +enum { + STATUS_SCREEN_CACHE, + MENU_SCREEN_CACHE, + TUNE_SCREEN_CACHE, + ALERT_BOX_CACHE, + SPINNER_CACHE, + ADVANCED_SETTINGS_SCREEN_CACHE, + MOVE_AXIS_SCREEN_CACHE, + TEMPERATURE_SCREEN_CACHE, + STEPS_SCREEN_CACHE, + MAX_FEEDRATE_SCREEN_CACHE, + MAX_VELOCITY_SCREEN_CACHE, + MAX_ACCELERATION_SCREEN_CACHE, + DEFAULT_ACCELERATION_SCREEN_CACHE, + FLOW_PERCENT_SCREEN_CACHE, + LEVELING_SCREEN_CACHE, + ZOFFSET_SCREEN_CACHE, + BED_MESH_VIEW_SCREEN_CACHE, + BED_MESH_EDIT_SCREEN_CACHE, + STEPPER_CURRENT_SCREEN_CACHE, + #if HAS_JUNCTION_DEVIATION + JUNC_DEV_SCREEN_CACHE, + #else + JERK_SCREEN_CACHE, + #endif + CASE_LIGHT_SCREEN_CACHE, + FILAMENT_MENU_CACHE, + LINEAR_ADVANCE_SCREEN_CACHE, + PREHEAT_MENU_CACHE, + PREHEAT_TIMER_SCREEN_CACHE, + LOAD_CHOCOLATE_SCREEN_CACHE, + MOVE_XYZ_SCREEN_CACHE, + MOVE_E_SCREEN_CACHE, + FILES_SCREEN_CACHE, + INTERFACE_SETTINGS_SCREEN_CACHE, + INTERFACE_SOUNDS_SCREEN_CACHE, + LOCK_SCREEN_CACHE, + DISPLAY_TIMINGS_SCREEN_CACHE +}; + +// To save MCU RAM, the status message is "baked" in to the status screen +// cache, so we reserve a large chunk of memory for the DL cache + +#define STATUS_SCREEN_DL_SIZE 4096 +#define ALERT_BOX_DL_SIZE 3072 +#define SPINNER_DL_SIZE 3072 +#define FILE_SCREEN_DL_SIZE 4160 +#define PRINTING_SCREEN_DL_SIZE 2048 + +/************************* MENU SCREEN DECLARATIONS *************************/ + +#include "../generic/base_screen.h" +#include "../generic/base_numeric_adjustment_screen.h" +#include "../generic/dialog_box_base_class.h" +#include "../generic/boot_screen.h" +#include "../generic/about_screen.h" +#include "../generic/kill_screen.h" +#include "../generic/alert_dialog_box.h" +#include "../generic/spinner_dialog_box.h" +#include "../generic/restore_failsafe_dialog_box.h" +#include "../generic/save_settings_dialog_box.h" +#include "../generic/confirm_start_print_dialog_box.h" +#include "../generic/confirm_abort_print_dialog_box.h" +#include "../generic/confirm_user_request_alert_box.h" +#include "../generic/touch_calibration_screen.h" +#include "../generic/move_axis_screen.h" +#include "../generic/steps_screen.h" +#include "../generic/feedrate_percent_screen.h" +#include "../generic/max_velocity_screen.h" +#include "../generic/max_acceleration_screen.h" +#include "../generic/default_acceleration_screen.h" +#include "../generic/temperature_screen.h" +#include "../generic/interface_sounds_screen.h" +#include "../generic/interface_settings_screen.h" +#include "../generic/lock_screen.h" +#include "../generic/endstop_state_screen.h" +#include "../generic/display_tuning_screen.h" +#include "../generic/statistics_screen.h" +#include "../generic/stepper_current_screen.h" +#include "../generic/leveling_menu.h" +#include "../generic/z_offset_screen.h" +#include "../generic/bed_mesh_base.h" +#include "../generic/bed_mesh_view_screen.h" +#include "../generic/bed_mesh_edit_screen.h" +#include "../generic/case_light_screen.h" +#include "../generic/linear_advance_screen.h" +#include "../generic/files_screen.h" +#include "../generic/move_axis_screen.h" +#include "../generic/flow_percent_screen.h" +#include "../generic/tune_menu.h" +#if HAS_JUNCTION_DEVIATION + #include "../generic/junction_deviation_screen.h" +#else + #include "../generic/jerk_screen.h" +#endif + +#include "status_screen.h" +#include "main_menu.h" +#include "advanced_settings_menu.h" +#include "preheat_menu.h" +#include "preheat_screen.h" +#include "load_chocolate.h" +#include "move_xyz_screen.h" +#include "move_e_screen.h" diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_status_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.cpp similarity index 98% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_status_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.cpp index a0c8914589d2a..38fdc2bb26f09 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_status_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.cpp @@ -1,5 +1,5 @@ /********************************* - * cocoa_press_status_screen.cpp * + * cocoa_press/status_screen.cpp * *********************************/ /**************************************************************************** @@ -22,9 +22,9 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" -#ifdef FTDI_COCOA_STATUS_SCREEN +#ifdef COCOA_STATUS_SCREEN #include "cocoa_press_ui.h" @@ -294,4 +294,4 @@ void StatusScreen::onIdle() { } } -#endif // FTDI_COCOA_STATUS_SCREEN +#endif // COCOA_STATUS_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_status_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.h similarity index 95% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_status_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.h index b22bceac14a66..1cddfa0896f1c 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_status_screen.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.h @@ -1,5 +1,5 @@ /******************************* - * cocoa_press_status_screen.h * + * cocoa_press/status_screen.h * *******************************/ /**************************************************************************** @@ -23,8 +23,8 @@ #pragma once -#define FTDI_COCOA_STATUS_SCREEN -#define FTDI_COCOA_STATUS_SCREEN_CLASS StatusScreen +#define COCOA_STATUS_SCREEN +#define COCOA_STATUS_SCREEN_CLASS StatusScreen class StatusScreen : public BaseScreen, public CachedScreen { private: diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp index 08faaa3b6ad2b..9faedae711d80 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_extui.cpp @@ -28,7 +28,7 @@ #if ENABLED(TOUCH_UI_FTDI_EVE) -#include "screens/screens.h" +#include "screens.h" namespace ExtUI { using namespace Theme; @@ -45,24 +45,23 @@ namespace ExtUI { } void onMediaInserted() { - if (AT_SCREEN(StatusScreen)) - StatusScreen::setStatusMessage(GET_TEXT_F(MSG_MEDIA_INSERTED)); - sound.play(media_inserted, PLAY_ASYNCHRONOUS); + #if ENABLED(SDSUPPORT) + sound.play(media_inserted, PLAY_ASYNCHRONOUS); + StatusScreen::onMediaInserted(); + #endif } void onMediaRemoved() { - if (isPrintingFromMedia()) { - stopPrint(); - InterfaceSoundsScreen::playEventSound(InterfaceSoundsScreen::PRINTING_FAILED); - } - else - sound.play(media_removed, PLAY_ASYNCHRONOUS); - - if (AT_SCREEN(StatusScreen) || isPrintingFromMedia()) - StatusScreen::setStatusMessage(GET_TEXT_F(MSG_MEDIA_REMOVED)); - #if ENABLED(SDSUPPORT) - if (AT_SCREEN(FilesScreen)) GOTO_SCREEN(StatusScreen); + if (isPrintingFromMedia()) { + stopPrint(); + InterfaceSoundsScreen::playEventSound(InterfaceSoundsScreen::PRINTING_FAILED); + } + else + sound.play(media_removed, PLAY_ASYNCHRONOUS); + + StatusScreen::onMediaRemoved(); + FilesScreen::onMediaRemoved(); #endif } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/constants.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/constants.h index 507e251518467..20b1a3e9752e3 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/constants.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/constants.h @@ -95,6 +95,7 @@ namespace FTDI_FT810 { namespace FTDI { constexpr uint8_t ARGB1555 = 0; constexpr uint8_t L1 = 1; + constexpr uint8_t L2 = 17; constexpr uint8_t L4 = 2; constexpr uint8_t L8 = 3; constexpr uint8_t RGB332 = 4; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/display_list.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/display_list.h index 99a9e0e81089f..d6afe78f7cda5 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/display_list.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/basic/display_list.h @@ -64,14 +64,14 @@ namespace FTDI { inline uint32_t CLEAR_COLOR_A(uint8_t alpha) {return DL::CLEAR_COLOR_A|(alpha&255UL);} inline uint32_t CLEAR_COLOR_RGB(uint8_t red, uint8_t green, uint8_t blue) {return DL::CLEAR_COLOR_RGB|((red&255UL)<<16)|((green&255UL)<<8)|(blue&255UL);} - inline uint32_t CLEAR_COLOR_RGB(uint32_t rgb) {return DL::CLEAR_COLOR_RGB|rgb;} + inline uint32_t CLEAR_COLOR_RGB(uint32_t rgb) {return DL::CLEAR_COLOR_RGB|(rgb&0xFFFFFF);} inline uint32_t CLEAR_STENCIL(uint8_t s) {return DL::CLEAR_STENCIL|(s&255UL);} inline uint32_t CLEAR_TAG(uint8_t s) {return DL::CLEAR_TAG|(s&255UL);} inline uint32_t COLOR_A(uint8_t alpha) {return DL::COLOR_A|(alpha&255UL);} inline uint32_t COLOR_MASK(bool r, bool g, bool b, bool a) {return DL::COLOR_MASK|((r?1UL:0UL)<<3)|((g?1UL:0UL)<<2)|((b?1UL:0UL)<<1)|(a?1UL:0UL);} inline uint32_t COLOR_RGB(uint8_t red,uint8_t green,uint8_t blue) {return DL::COLOR_RGB|((red&255UL)<<16)|((green&255UL)<<8)|(blue&255UL);} - inline uint32_t COLOR_RGB(uint32_t rgb) {return DL::COLOR_RGB|rgb;} + inline uint32_t COLOR_RGB(uint32_t rgb) {return DL::COLOR_RGB|(rgb&0xFFFFFF);} /* inline uint32_t DISPLAY() {return (0UL<<24)) */ inline uint32_t END() {return DL::END;} inline uint32_t JUMP(uint16_t dest) {return DL::JUMP|(dest&65535UL);} diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h index 9be7882a390f2..8ae7a150f8762 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h @@ -195,11 +195,31 @@ #define pgm_read_ptr_far pgm_read_ptr #endif + // Use NUM_ARGS(__VA_ARGS__) to get the number of variadic arguments + #define _NUM_ARGS(_,Z,Y,X,W,V,U,T,S,R,Q,P,O,N,M,L,K,J,I,H,G,F,E,D,C,B,A,OUT,...) OUT + #define NUM_ARGS(V...) _NUM_ARGS(0,V,26,25,24,23,22,21,20,19,18,17,16,15,14,13,12,11,10,9,8,7,6,5,4,3,2,1,0) + + // SERIAL_ECHOPAIR / SERIAL_ECHOPAIR_P is used to output a key value pair. The key must be a string and the value can be anything + // Print up to 12 pairs of values. Odd elements auto-wrapped in PSTR(). + #define __SEP_N(N,V...) _SEP_##N(V) + #define _SEP_N(N,V...) __SEP_N(N,V) + #define _SEP_1(PRE) SERIAL_ECHOPGM(PRE) + #define _SEP_2(PRE,V) do{ Serial.print(F(PRE)); Serial.print(V); }while(0) + #define _SEP_3(a,b,c) do{ _SEP_2(a,b); SERIAL_ECHOPGM(c); }while(0) + #define _SEP_4(a,b,V...) do{ _SEP_2(a,b); _SEP_2(V); }while(0) + + // Print up to 1 pairs of values followed by newline + #define __SELP_N(N,V...) _SELP_##N(V) + #define _SELP_N(N,V...) __SELP_N(N,V) + #define _SELP_1(PRE) SERIAL_ECHOLNPGM(PRE) + #define _SELP_2(PRE,V) do{ Serial.print(F(PRE)); Serial.println(V); }while(0) + #define _SELP_3(a,b,c) do{ _SEP_2(a,b); SERIAL_ECHOLNPGM(c); }while(0) + #define _SELP_4(a,b,V...) do{ _SEP_2(a,b); _SELP_2(V); }while(0) #define SERIAL_ECHO_START() #define SERIAL_ECHOLNPGM(str) Serial.println(F(str)) #define SERIAL_ECHOPGM(str) Serial.print(F(str)) - #define SERIAL_ECHO_MSG(str) Serial.println(str) - #define SERIAL_ECHOLNPAIR(str, val) do{ Serial.print(F(str)); Serial.println(val); }while(0) + #define SERIAL_ECHO_MSG(V...) SERIAL_ECHOLNPAIR(V) + #define SERIAL_ECHOLNPAIR(V...) _SELP_N(NUM_ARGS(V),V) #define SERIAL_ECHOPAIR(str, val) do{ Serial.print(F(str)); Serial.print(val); }while(0) #define safe_delay delay diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.cpp index e324cb978aa01..fd9c70ff3c5f5 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.cpp @@ -26,4 +26,16 @@ CommandProcessor::btn_style_func_t *CommandProcessor::_btn_style_callback = CommandProcessor::default_button_style_func; bool CommandProcessor::is_tracking = false; +uint32_t CommandProcessor::memcrc(uint32_t ptr, uint32_t num) { + const uint16_t x = CLCD::mem_read_16(CLCD::REG::CMD_WRITE); + memcrc(ptr, num, 0); + wait(); + return CLCD::mem_read_32(CLCD::MAP::RAM_CMD + x + 12); +} + +bool CommandProcessor::wait() { + while (is_processing() && !has_fault()) { /* nada */ } + return !has_fault(); +} + #endif // FTDI_EXTENDED diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h index 2258529221c56..8561eb05a2ab4 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/command_processor.h @@ -146,6 +146,9 @@ class CommandProcessor : public CLCD::CommandFifo { return *this; } + bool wait(); + uint32_t memcrc(uint32_t ptr, uint32_t num); + // Wrap all the CommandFifo routines to allow method chaining inline CommandProcessor& cmd (uint32_t cmd32) {CLCD::CommandFifo::cmd(cmd32); return *this;} diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/grid_layout.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/grid_layout.h index 47aec24d83ab1..dd94685c98ed5 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/grid_layout.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/grid_layout.h @@ -47,23 +47,25 @@ #define MARGIN_DEFAULT 3 #endif -// EDGE_R adds some black space on the right edge of the display -// This shifts some of the screens left to visually center them. +// The EDGE variables adds some space on the edges of the display +#define EDGE_T 0 +#define EDGE_B 0 +#define EDGE_L 0 #define EDGE_R 0 // GRID_X and GRID_Y computes the positions of the divisions on // the layout grid. -#define GRID_X(x) ((x)*(FTDI::display_width-EDGE_R)/GRID_COLS) -#define GRID_Y(y) ((y)*FTDI::display_height/GRID_ROWS) +#define GRID_X(x) ((x)*(FTDI::display_width-EDGE_R-EDGE_L)/GRID_COLS+EDGE_L) +#define GRID_Y(y) ((y)*(FTDI::display_height-EDGE_B-EDGE_T)/GRID_ROWS+EDGE_T) // BTN_X, BTN_Y, BTN_W and BTN_X returns the top-left and width // and height of a button, taking into account the button margins. #define BTN_X(x) (GRID_X((x)-1) + MARGIN_L) #define BTN_Y(y) (GRID_Y((y)-1) + MARGIN_T) -#define BTN_W(w) (GRID_X(w) - MARGIN_L - MARGIN_R) -#define BTN_H(h) (GRID_Y(h) - MARGIN_T - MARGIN_B) +#define BTN_W(w) (GRID_X(w) - GRID_X(0) - MARGIN_L - MARGIN_R) +#define BTN_H(h) (GRID_Y(h) - GRID_Y(0) - MARGIN_T - MARGIN_B) // Abbreviations for common phrases, to allow a button to be // defined in one line of source. diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp index b7422a06b1b05..9f73c7dfb8321 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp @@ -82,12 +82,14 @@ namespace FTDI { box_width = w; measure_text_box(fm, str, box_width, box_height); if (box_width <= (uint16_t)w && box_height <= (uint16_t)h) break; - fm.load(--font); if (font == 26) break; + fm.load(--font); } - const uint16_t dx = (options & OPT_RIGHTX) ? w : (options & OPT_CENTERX) ? w/2 : 0; - const uint16_t dy = (options & OPT_CENTERY) ? (h - box_height)/2 : 0; + const uint16_t dx = (options & OPT_RIGHTX) ? w : + (options & OPT_CENTERX) ? w/2 : 0; + const uint16_t dy = (options & OPT_BOTTOMY) ? (h - box_height) : + (options & OPT_CENTERY) ? (h - box_height)/2 : 0; const char *line_start = str; const char *line_end; @@ -105,11 +107,11 @@ namespace FTDI { #if ENABLED(TOUCH_UI_USE_UTF8) if (has_utf8_chars(line)) { - draw_utf8_text(cmd, x + dx, y + dy, line, fm.fs, options & ~OPT_CENTERY); + draw_utf8_text(cmd, x + dx, y + dy, line, fm.fs, options & ~(OPT_CENTERY | OPT_BOTTOMY)); } else #endif { - cmd.CLCD::CommandFifo::text(x + dx, y + dy, font, options & ~OPT_CENTERY); + cmd.CLCD::CommandFifo::text(x + dx, y + dy, font, options & ~(OPT_CENTERY | OPT_BOTTOMY)); cmd.CLCD::CommandFifo::str(line); } } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.h index 9d8cd440615e9..3b14b020c00cf 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.h @@ -25,6 +25,8 @@ * This function draws text inside a bounding box, doing word wrapping and using the largest font that will fit. */ namespace FTDI { + constexpr uint16_t OPT_BOTTOMY = 0x1000; // Non-standard + void draw_text_box(class CommandProcessor& cmd, int x, int y, int w, int h, progmem_str str, uint16_t options = 0, uint8_t font = 31); void draw_text_box(class CommandProcessor& cmd, int x, int y, int w, int h, const char *str, uint16_t options = 0, uint8_t font = 31); } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp index 39b8759204e96..55dd496e1c9c0 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp @@ -138,6 +138,7 @@ */ void FTDI::load_utf8_bitmaps(CommandProcessor &cmd) { + cmd.cmd(SAVE_CONTEXT()); #ifdef TOUCH_UI_UTF8_CYRILLIC_CHARSET CyrillicCharSet::load_bitmaps(cmd); #endif @@ -145,6 +146,7 @@ WesternCharSet::load_bitmaps(cmd); #endif StandardCharSet::load_bitmaps(cmd); + cmd.cmd(RESTORE_CONTEXT()); } /** diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/bitmap2cpp.py b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/bitmap2cpp.py deleted file mode 100644 index 0c4499e9aadfd..0000000000000 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/scripts/bitmap2cpp.py +++ /dev/null @@ -1,108 +0,0 @@ -#!/usr/bin/python - -# Written By Marcio Teixeira 2019 - Aleph Objects, Inc. -# -# 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. -# -# To view a copy of the GNU General Public License, go to the following -# location: . - -from __future__ import print_function -from PIL import Image -import argparse -import textwrap - -def pack_rle(data): - """Use run-length encoding to pack the bytes""" - rle = [] - value = data[0] - count = 0 - for i in data: - if i != value or count == 255: - rle.append(count) - rle.append(value) - value = i - count = 1 - else: - count += 1 - rle.append(count) - rle.append(value) - return rle - -class WriteSource: - def __init__(self, lines_in_blocks): - self.blocks = [] - self.values = [] - self.block_size = lines_in_blocks - self.rows = 0 - - def add_pixel(self, value): - self.values.append(value) - - def convert_to_4bpp(self, data, chunk_size = 0): - # Invert the image - data = list(map(lambda i: 255 - i, data)) - # Quanitize 8-bit values into 4-bits - data = list(map(lambda i: i >> 4, data)) - # Make sure there is an even number of elements - if (len(data) & 1) == 1: - data.append(0) - # Combine each two adjacent values into one - i = iter(data) - data = list(map(lambda a, b: a << 4 | b, i ,i)) - # Pack the data - data = pack_rle(data) - # Convert values into hex strings - return list(map(lambda a: "0x" + format(a, '02x'), data)) - - def end_row(self, y): - # Pad each row into even number of values - if len(self.values) & 1: - self.values.append(0) - - self.rows += 1 - if self.block_size and (self.rows % self.block_size) == 0: - self.blocks.append(self.values) - self.values = [] - - def write(self): - if len(self.values): - self.blocks.append(self.values) - - block_strs = []; - for b in self.blocks: - data = self.convert_to_4bpp(b) - data = ', '.join(data) - data = textwrap.fill(data, 75, initial_indent = ' ', subsequent_indent = ' ') - block_strs.append(data) - - print("const unsigned char font[] PROGMEM = {") - for i, b in enumerate(block_strs): - if i: - print(',') - print('\n /* {} */'.format(i)) - print(b, end='') - print("\n};") - -if __name__ == "__main__": - parser = argparse.ArgumentParser(description='Converts a grayscale bitmap into a 16-level RLE packed C array for use as font data') - parser.add_argument("input") - parser.add_argument('--char_height', help='Adds a separator every so many lines', type=int) - args = parser.parse_args() - - writer = WriteSource(args.char_height) - - img = Image.open(args.input).convert('L') - for y in range(img.height): - for x in range(img.width): - writer.add_pixel(img.getpixel((x,y))) - writer.end_row(y) - writer.write() diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/about_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp similarity index 86% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/about_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp index 1d8db12ef991f..4e90e71e8a51b 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/about_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.cpp @@ -21,12 +21,12 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_ABOUT_SCREEN #define GRID_COLS 4 -#define GRID_ROWS 7 +#define GRID_ROWS 8 using namespace FTDI; using namespace Theme; @@ -47,9 +47,9 @@ void AboutScreen::onRedraw(draw_mode_t) { #define HEADING_POS BTN_POS(1,2), BTN_SIZE(4,1) #define FW_VERS_POS BTN_POS(1,3), BTN_SIZE(4,1) #define FW_INFO_POS BTN_POS(1,4), BTN_SIZE(4,1) - #define LICENSE_POS BTN_POS(1,5), BTN_SIZE(4,2) - #define STATS_POS BTN_POS(1,7), BTN_SIZE(2,1) - #define BACK_POS BTN_POS(3,7), BTN_SIZE(2,1) + #define LICENSE_POS BTN_POS(1,5), BTN_SIZE(4,3) + #define STATS_POS BTN_POS(1,8), BTN_SIZE(2,1) + #define BACK_POS BTN_POS(3,8), BTN_SIZE(2,1) #define _INSET_POS(x,y,w,h) x + w/10, y, w - w/5, h #define INSET_POS(pos) _INSET_POS(pos) @@ -91,20 +91,22 @@ void AboutScreen::onRedraw(draw_mode_t) { draw_text_box(cmd, FW_INFO_POS, about_str, OPT_CENTER, font_medium); draw_text_box(cmd, INSET_POS(LICENSE_POS), GET_TEXT_F(MSG_LICENSE), OPT_CENTER, font_tiny); - cmd.font(font_medium) - .colors(normal_btn) - .tag(2).button(STATS_POS, GET_TEXT_F(MSG_INFO_STATS_MENU)) - .colors(action_btn) + cmd.font(font_medium); + #if ENABLED(PRINTCOUNTER) && defined(FTDI_STATISTICS_SCREEN) + cmd.colors(normal_btn) + .tag(2).button(STATS_POS, GET_TEXT_F(MSG_INFO_STATS_MENU)); + #endif + cmd.colors(action_btn) .tag(1).button(BACK_POS, GET_TEXT_F(MSG_BACK)); } bool AboutScreen::onTouchEnd(uint8_t tag) { switch (tag) { case 1: GOTO_PREVIOUS(); break; - #if ENABLED(PRINTCOUNTER) + #if ENABLED(PRINTCOUNTER) && defined(FTDI_STATISTICS_SCREEN) case 2: GOTO_SCREEN(StatisticsScreen); break; #endif - #if ENABLED(TOUCH_UI_DEVELOPER_MENU) + #if ENABLED(TOUCH_UI_DEVELOPER_MENU) && defined(FTDI_DEVELOPER_MENU) case 3: GOTO_SCREEN(DeveloperMenu); break; #endif default: return false; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/about_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/about_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/about_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/advanced_settings_menu.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/advanced_settings_menu.cpp index b9255c11b9f22..58a7112d010b3 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/advanced_settings_menu.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_ADVANCED_SETTINGS_MENU diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/advanced_settings_menu.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/advanced_settings_menu.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/advanced_settings_menu.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/advanced_settings_menu.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/alert_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/alert_dialog_box.cpp similarity index 97% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/alert_dialog_box.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/alert_dialog_box.cpp index bbe922ad5da12..ccdfa89419d7e 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/alert_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/alert_dialog_box.cpp @@ -21,8 +21,8 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" -#include "screen_data.h" +#include "../screens.h" +#include "../screen_data.h" #ifdef FTDI_ALERT_DIALOG_BOX diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/alert_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/alert_dialog_box.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/alert_dialog_box.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/alert_dialog_box.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/backlash_compensation_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/backlash_compensation_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/backlash_compensation_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/backlash_compensation_screen.cpp index 11fb72b5a8487..c3fcb25f43855 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/backlash_compensation_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/backlash_compensation_screen.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_BACKLASH_COMP_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/backlash_compensation_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/backlash_compensation_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/backlash_compensation_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/backlash_compensation_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_numeric_adjustment_screen.cpp similarity index 98% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_numeric_adjustment_screen.cpp index 3b40e7f14e870..90199783fd4e0 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_numeric_adjustment_screen.cpp @@ -21,8 +21,8 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" -#include "screen_data.h" +#include "../screens.h" +#include "../screen_data.h" #ifdef FTDI_BASE_NUMERIC_ADJ_SCREEN @@ -51,6 +51,8 @@ BaseNumericAdjustmentScreen::widgets_t::widgets_t(draw_mode_t what) : _what(what .cmd(COLOR_RGB(bg_text_enabled)) .tag(0); } + else + cmd.colors(normal_btn); cmd.font(font_medium); _button(cmd, 1, @@ -319,7 +321,7 @@ void BaseNumericAdjustmentScreen::widgets_t::toggle(uint8_t tag, progmem_str lab } if (_what & FOREGROUND) { - _button_style(cmd, BTN_TOGGLE); + _button_style(cmd, is_enabled ? BTN_TOGGLE : BTN_DISABLED); cmd.tag(is_enabled ? tag : 0) .enabled(is_enabled) .font(font_small) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_numeric_adjustment_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/base_numeric_adjustment_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_numeric_adjustment_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/base_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_screen.cpp similarity index 93% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/base_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_screen.cpp index 139a3100cf620..0a8bebea3c9d3 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/base_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_screen.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_BASE_SCREEN @@ -45,7 +45,7 @@ bool BaseScreen::buttonStyleCallback(CommandProcessor &cmd, uint8_t tag, uint8_t return false; } - #if LCD_TIMEOUT_TO_STATUS > 0 + #if SCREENS_CAN_TIME_OUT if (EventLoop::get_pressed_tag() != 0) { reset_menu_timeout(); } @@ -65,7 +65,7 @@ bool BaseScreen::buttonStyleCallback(CommandProcessor &cmd, uint8_t tag, uint8_t } void BaseScreen::onIdle() { - #if LCD_TIMEOUT_TO_STATUS > 0 + #if SCREENS_CAN_TIME_OUT if ((millis() - last_interaction) > LCD_TIMEOUT_TO_STATUS) { reset_menu_timeout(); #if ENABLED(TOUCH_UI_DEBUG) @@ -77,12 +77,10 @@ void BaseScreen::onIdle() { } void BaseScreen::reset_menu_timeout() { - #if LCD_TIMEOUT_TO_STATUS > 0 - last_interaction = millis(); - #endif + TERN_(SCREENS_CAN_TIME_OUT, last_interaction = millis()); } -#if LCD_TIMEOUT_TO_STATUS > 0 +#if SCREENS_CAN_TIME_OUT uint32_t BaseScreen::last_interaction; #endif diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/base_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_screen.h similarity index 98% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/base_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_screen.h index cbeea1f750b37..030fa51a2aaf6 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/base_screen.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/base_screen.h @@ -27,7 +27,7 @@ class BaseScreen : public UIScreen { protected: - #if LCD_TIMEOUT_TO_STATUS > 0 + #if SCREENS_CAN_TIME_OUT static uint32_t last_interaction; #endif diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_base.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_base.cpp similarity index 94% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_base.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_base.cpp index e83f09f045294..14f2196453376 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_base.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_base.cpp @@ -20,7 +20,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_BED_MESH_BASE @@ -141,13 +141,18 @@ void BedMeshBase::_drawMesh(CommandProcessor &cmd, int16_t x, int16_t y, int16_t if (ISVAL(x,y)) { if (opts & USE_COLORS) { const float val_dev = sq(VALUE(x, y) - val_mean); - uint8_t r = 0, b = 0; - //*(VALUE(x, y) < 0 ? &r : &b) = val_dev / sq_min * 0xFF; - if (VALUE(x, y) < 0) - r = val_dev / sq_min * 0xFF; - else - b = val_dev / sq_max * 0xFF; - cmd.cmd(COLOR_RGB(0xFF - b, 0xFF - b - r, 0xFF - r)); + float r = 0, b = 0; + if (sq_min != sq_max) { + if (VALUE(x, y) < 0) + r = val_dev / sq_min; + else + b = val_dev / sq_max; + } + #ifdef BED_MESH_POINTS_GRAY + cmd.cmd(COLOR_RGB((1.0f - b + r) * 0x7F, (1.0f - b - r) * 0x7F, (1.0f - r + b) * 0x7F)); + #else + cmd.cmd(COLOR_RGB((1.0f - b) * 0xFF, (1.0f - b - r) * 0xFF, (1.0f - r) * 0xFF)); + #endif } cmd.cmd(VERTEX2F(TRANSFORM(x, y, HEIGHT(x, y)))); } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_base.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_base.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_base.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_base.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_edit_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp similarity index 95% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_edit_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp index f2c775c9937b7..e06fb52773491 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_edit_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.cpp @@ -20,8 +20,8 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" -#include "screen_data.h" +#include "../screens.h" +#include "../screen_data.h" #ifdef FTDI_BED_MESH_EDIT_SCREEN @@ -69,9 +69,17 @@ void BedMeshEditScreen::onEntry() { mydata.zAdjustment = 0; mydata.savedMeshLevelingState = ExtUI::getLevelingActive(); mydata.savedEndstopState = ExtUI::getSoftEndstopState(); + makeMeshValid(); BaseScreen::onEntry(); } +void BedMeshEditScreen::makeMeshValid() { + bed_mesh_t &mesh = ExtUI::getMeshArray(); + GRID_LOOP(x, y) { + if (isnan(mesh[x][y])) mesh[x][y] = 0; + } +} + void BedMeshEditScreen::onExit() { ExtUI::setLevelingActive(mydata.savedMeshLevelingState); ExtUI::setSoftEndstopState(mydata.savedEndstopState); @@ -121,8 +129,9 @@ bool BedMeshEditScreen::changeHighlightedValue(uint8_t tag) { void BedMeshEditScreen::drawHighlightedPointValue() { CommandProcessor cmd; cmd.font(Theme::font_medium) - .colors(normal_btn) + .cmd(COLOR_RGB(bg_text_enabled)) .text(Z_LABEL_POS, GET_TEXT_F(MSG_MESH_EDIT_Z)) + .colors(normal_btn) .font(font_small); if (mydata.highlight.x != NONE) draw_adjuster(cmd, Z_VALUE_POS, 3, getHighlightedValue(), GET_TEXT_F(MSG_UNITS_MM), 4, 3); @@ -187,7 +196,8 @@ void BedMeshEditScreen::show() { // After the spinner, go to this screen. current_screen.forget(); PUSH_SCREEN(BedMeshEditScreen); - } else { + } + else { injectCommands_P(PSTR("G29 S1")); GOTO_SCREEN(BedMeshEditScreen); } diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_edit_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.h similarity index 98% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_edit_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.h index b856b9b33b3ad..45a53f0f13720 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_edit_screen.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_edit_screen.h @@ -32,6 +32,7 @@ struct BedMeshEditScreenData { class BedMeshEditScreen : public BedMeshBase, public CachedScreen { private: + static void makeMeshValid(); static float getHighlightedValue(); static void setHighlightedValue(float value); static void moveToHighlightedValue(); diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_view_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.cpp similarity index 96% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_view_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.cpp index 1a00e10ca9927..75b15828a20e3 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_view_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.cpp @@ -20,8 +20,8 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" -#include "screen_data.h" +#include "../screens.h" +#include "../screen_data.h" #ifdef FTDI_BED_MESH_VIEW_SCREEN @@ -69,7 +69,7 @@ void BedMeshViewScreen::onEntry() { void BedMeshViewScreen::drawHighlightedPointValue() { CommandProcessor cmd; cmd.font(Theme::font_medium) - .colors(normal_btn) + .cmd(COLOR_RGB(bg_text_enabled)) .text(Z_LABEL_POS, GET_TEXT_F(MSG_MESH_EDIT_Z)) .font(font_small); @@ -161,7 +161,7 @@ void BedMeshViewScreen::doProbe() { void BedMeshViewScreen::doMeshValidation() { mydata.count = 0; GOTO_SCREEN(StatusScreen); - injectCommands_P(PSTR("G28 O\nM117 Heating...\nG26 R X0 Y0")); + injectCommands_P(PSTR("M75\nG28 O\nM117 Heating...\nG26 R X0 Y0\nG27\nM77")); } void BedMeshViewScreen::show() { diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_view_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/bed_mesh_view_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/bed_mesh_view_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/boot_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/boot_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/boot_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/boot_screen.cpp index c8c7cdb5a58ed..d2a22692958b6 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/boot_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/boot_screen.cpp @@ -22,7 +22,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_BOOT_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/boot_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/boot_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/boot_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/boot_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/case_light_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/case_light_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/case_light_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/case_light_screen.cpp index 04327128ab4d4..8fbb400a681be 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/case_light_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/case_light_screen.cpp @@ -20,7 +20,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_CASE_LIGHT_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/case_light_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/case_light_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/case_light_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/case_light_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/change_filament_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.cpp similarity index 98% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/change_filament_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.cpp index e9fa8a66d4733..46d3a4ea1cf90 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/change_filament_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.cpp @@ -21,8 +21,8 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" -#include "screen_data.h" +#include "../screens.h" +#include "../screen_data.h" #ifdef FTDI_CHANGE_FILAMENT_SCREEN @@ -76,7 +76,7 @@ constexpr static ChangeFilamentScreenData &mydata = screen_data.ChangeFilamentSc /****************** COLOR SCALE ***********************/ -uint32_t getWarmColor(uint16_t temp, uint16_t cool, uint16_t low, uint16_t med, uint16_t high) { +uint32_t ChangeFilamentScreen::getWarmColor(uint16_t temp, uint16_t cool, uint16_t low, uint16_t med, uint16_t high) { rgb_t R0, R1, mix; float t; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/change_filament_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.h similarity index 95% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/change_filament_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.h index 43a4bae6e001b..42eaf25f4ae3a 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/change_filament_screen.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/change_filament_screen.h @@ -38,9 +38,9 @@ class ChangeFilamentScreen : public BaseScreen, public CachedScreen 1 #include "language_menu.h" #endif - -#endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/spinner_dialog_box.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp similarity index 97% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/spinner_dialog_box.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp index 7483261e3c048..489beabe6b74c 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/spinner_dialog_box.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.cpp @@ -21,8 +21,8 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" -#include "screen_data.h" +#include "../screens.h" +#include "../screen_data.h" #ifdef FTDI_SPINNER_DIALOG_BOX diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/spinner_dialog_box.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/spinner_dialog_box.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/spinner_dialog_box.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/statistics_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/statistics_screen.cpp similarity index 99% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/statistics_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/statistics_screen.cpp index 2d62d5349b184..2153a1e1adcf4 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/statistics_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/statistics_screen.cpp @@ -21,7 +21,7 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" +#include "../screens.h" #ifdef FTDI_STATISTICS_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/statistics_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/statistics_screen.h similarity index 100% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/statistics_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/statistics_screen.h diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/status_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.cpp similarity index 97% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/status_screen.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.cpp index f61136e396bb7..23ac90107b6d3 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/status_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.cpp @@ -21,8 +21,8 @@ ****************************************************************************/ #include "../config.h" -#include "screens.h" -#include "screen_data.h" +#include "../screens.h" +#include "../screen_data.h" #ifdef FTDI_STATUS_SCREEN @@ -461,4 +461,14 @@ bool StatusScreen::onTouchEnd(uint8_t tag) { return true; } +void StatusScreen::onMediaInserted() { + if (AT_SCREEN(StatusScreen)) + setStatusMessage(GET_TEXT_F(MSG_MEDIA_INSERTED)); +} + +void StatusScreen::onMediaRemoved() { + if (AT_SCREEN(StatusScreen) || ExtUI::isPrintingFromMedia()) + setStatusMessage(GET_TEXT_F(MSG_MEDIA_REMOVED)); +} + #endif // FTDI_STATUS_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/status_screen.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.h similarity index 96% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/status_screen.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.h index 3a2ba1746c346..6033ba1ad99f5 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/status_screen.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.h @@ -42,4 +42,6 @@ class StatusScreen : public BaseScreen, public CachedScreen { private: - static void move(float inc); + static void move(float mm, int16_t steps); static void runWizard(); + static bool wizardRunning(); public: static void onEntry(); + static void onExit(); static void onRedraw(draw_mode_t); static bool onTouchHeld(uint8_t tag); }; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language_en.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language_en.h index 9de9623e198b6..4ac44501d5bae 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language_en.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/language/language_en.h @@ -70,7 +70,7 @@ namespace Language_en { PROGMEM Language_Str MSG_ABOUT_TOUCH_PANEL_2 = WEBSITE_URL; PROGMEM Language_Str MSG_LICENSE = u8"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.\n\nTo view a copy of the GNU General " + "of the License, or (at your option) any later version. To view a copy of the GNU General " "Public License, go to the following location: https://www.gnu.org/licenses."; PROGMEM Language_Str MSG_RUNOUT_1 = u8"Runout 1"; PROGMEM Language_Str MSG_RUNOUT_2 = u8"Runout 2"; @@ -130,7 +130,7 @@ namespace Language_en { PROGMEM Language_Str MSG_EEPROM_RESTORED = u8"Settings restored from backup"; PROGMEM Language_Str MSG_EEPROM_RESET = u8"Settings restored to default"; PROGMEM Language_Str MSG_EEPROM_SAVED = u8"Settings saved!"; - PROGMEM Language_Str MSG_EEPROM_SAVE_PROMPT = u8"Do you wish to save these settings as defaults?"; + PROGMEM Language_Str MSG_EEPROM_SAVE_PROMPT = u8"Do you wish to save these settings for next power-on?"; PROGMEM Language_Str MSG_EEPROM_RESET_WARNING = u8"Are you sure? Customizations will be lost."; PROGMEM Language_Str MSG_PASSCODE_REJECTED = u8"Wrong passcode!"; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/screen_data.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screen_data.h similarity index 94% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/screen_data.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screen_data.h index 17e445fe4d468..057054a6af176 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/screen_data.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screen_data.h @@ -22,7 +22,7 @@ #pragma once -#include "../ftdi_eve_lib/ftdi_eve_lib.h" +#include "ftdi_eve_lib/ftdi_eve_lib.h" // To save RAM, store state information related to a particular screen // in a union. The values should be initialized in the onEntry method. @@ -58,12 +58,12 @@ union screen_data_t { DECL_DATA_IF_INCLUDED(FTDI_BED_MESH_VIEW_SCREEN) DECL_DATA_IF_INCLUDED(FTDI_BED_MESH_EDIT_SCREEN) DECL_DATA_IF_INCLUDED(FTDI_STRESS_TEST_SCREEN) - DECL_DATA_IF_INCLUDED(FTDI_COCOA_PREHEAT_SCREEN) - DECL_DATA_IF_INCLUDED(FTDI_COCOA_LOAD_CHOCOLATE_SCREEN) DECL_DATA_IF_INCLUDED(FTDI_NUDGE_NOZZLE_SCREEN) DECL_DATA_IF_INCLUDED(FTDI_Z_OFFSET_SCREEN) DECL_DATA_IF_INCLUDED(FTDI_BASE_NUMERIC_ADJ_SCREEN) DECL_DATA_IF_INCLUDED(FTDI_ALERT_DIALOG_BOX) + DECL_DATA_IF_INCLUDED(COCOA_PREHEAT_SCREEN) + DECL_DATA_IF_INCLUDED(COCOA_LOAD_CHOCOLATE_SCREEN) }; extern screen_data_t screen_data; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/screens.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.cpp similarity index 90% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/screens.cpp rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.cpp index c3e015d75cf3a..ec627e313b134 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/screens.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.cpp @@ -20,7 +20,7 @@ * location: . * ****************************************************************************/ -#include "../config.h" +#include "config.h" #if ENABLED(TOUCH_UI_FTDI_EVE) #include "screens.h" @@ -100,15 +100,6 @@ SCREEN_TABLE { DECL_SCREEN_IF_INCLUDED(FTDI_BIO_PRINTING_DIALOG_BOX) DECL_SCREEN_IF_INCLUDED(FTDI_BIO_CONFIRMOME_XYZ) DECL_SCREEN_IF_INCLUDED(FTDI_BIO_CONFIRMOME_E) - DECL_SCREEN_IF_INCLUDED(FTDI_COCOA_STATUS_SCREEN) - DECL_SCREEN_IF_INCLUDED(FTDI_COCOA_MAIN_MENU) - DECL_SCREEN_IF_INCLUDED(FTDI_COCOA_ADVANCED_SETTINGS_MENU) - DECL_SCREEN_IF_INCLUDED(FTDI_COCOA_PREHEAT_MENU) - DECL_SCREEN_IF_INCLUDED(FTDI_COCOA_PREHEAT_SCREEN) - DECL_SCREEN_IF_INCLUDED(FTDI_COCOA_UNLOAD_CARTRIDGE_SCREEN) - DECL_SCREEN_IF_INCLUDED(FTDI_COCOA_LOAD_CHOCOLATE_SCREEN) - DECL_SCREEN_IF_INCLUDED(FTDI_COCOA_MOVE_XYZ_SCREEN) - DECL_SCREEN_IF_INCLUDED(FTDI_COCOA_MOVE_E_SCREEN) DECL_SCREEN_IF_INCLUDED(FTDI_DEVELOPER_MENU) DECL_SCREEN_IF_INCLUDED(FTDI_CONFIRM_ERASE_FLASH_DIALOG_BOX) DECL_SCREEN_IF_INCLUDED(FTDI_WIDGET_DEMO_SCREEN) @@ -116,6 +107,15 @@ SCREEN_TABLE { DECL_SCREEN_IF_INCLUDED(FTDI_STRESS_TEST_SCREEN) DECL_SCREEN_IF_INCLUDED(FTDI_MEDIA_PLAYER_SCREEN) DECL_SCREEN_IF_INCLUDED(FTDI_DISPLAY_TUNING_SCREEN) + DECL_SCREEN_IF_INCLUDED(COCOA_STATUS_SCREEN) + DECL_SCREEN_IF_INCLUDED(COCOA_MAIN_MENU) + DECL_SCREEN_IF_INCLUDED(COCOA_ADVANCED_SETTINGS_MENU) + DECL_SCREEN_IF_INCLUDED(COCOA_PREHEAT_MENU) + DECL_SCREEN_IF_INCLUDED(COCOA_PREHEAT_SCREEN) + DECL_SCREEN_IF_INCLUDED(COCOA_LOAD_CHOCOLATE_SCREEN) + DECL_SCREEN_IF_INCLUDED(COCOA_LEVELING_MENU) + DECL_SCREEN_IF_INCLUDED(COCOA_MOVE_XYZ_SCREEN) + DECL_SCREEN_IF_INCLUDED(COCOA_MOVE_E_SCREEN) }; SCREEN_TABLE_POST diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_unload_cartridge.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.h similarity index 68% rename from Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_unload_cartridge.h rename to Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.h index 95a9ee47ec468..f118303d21880 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_unload_cartridge.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens.h @@ -1,11 +1,10 @@ -/********************************** - * cocoa_press_unload_cartridge.h * - **********************************/ +/************* + * screens.h * + *************/ /**************************************************************************** * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * - * Written By Marcio Teixeira 2020 - Cocoa Press * * * * 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 * @@ -18,17 +17,34 @@ * GNU General Public License for more details. * * * * To view a copy of the GNU General Public License, go to the following * - * location: . * + * location: . * ****************************************************************************/ #pragma once -#define FTDI_COCOA_UNLOAD_CARTRIDGE_SCREEN -#define FTDI_COCOA_UNLOAD_CARTRIDGE_SCREEN_CLASS UnloadCartridgeScreen +#include "compat.h" -class UnloadCartridgeScreen : public BaseScreen, public CachedScreen { - public: - static void onRedraw(draw_mode_t); - static bool onTouchEnd(uint8_t tag); - static bool onTouchHeld(uint8_t tag); -}; +#if ENABLED(TOUCH_UI_FTDI_EVE) + +#include "ftdi_eve_lib/ftdi_eve_lib.h" +#include "language/language.h" +#include "theme/theme.h" +#include "generic/string_format.h" + +#ifndef BED_LEVELING_COMMANDS + #define BED_LEVELING_COMMANDS "G29" +#endif + +extern tiny_timer_t refresh_timer; + +#if ENABLED(TOUCH_UI_LULZBOT_BIO) + #include "bioprinter/screens.h" +#elif ENABLED(TOUCH_UI_COCOA_PRESS) + #include "cocoapress/screens.h" +#elif ENABLED(TOUCH_UI_SYNDAVER_LEVEL) + #include "syndaver_level/screens.h" +#else + #include "generic/screens.h" +#endif + +#endif // TOUCH_UI_FTDI_EVE diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_unload_cartridge.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_unload_cartridge.cpp deleted file mode 100644 index 3428c38bb17ab..0000000000000 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/screens/cocoa_press_unload_cartridge.cpp +++ /dev/null @@ -1,100 +0,0 @@ -/************************************ - * cocoa_press_unload_cartridge.cpp * - ************************************/ - -/**************************************************************************** - * Written By Mark Pelletier 2017 - Aleph Objects, Inc. * - * Written By Marcio Teixeira 2018 - Aleph Objects, Inc. * - * Written By Marcio Teixeira 2020 - Cocoa Press * - * * - * 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. * - * * - * To view a copy of the GNU General Public License, go to the following * - * location: . * - ****************************************************************************/ - -#include "../config.h" -#include "screens.h" -#include "screen_data.h" - -#ifdef FTDI_COCOA_UNLOAD_CARTRIDGE_SCREEN - -using namespace ExtUI; -using namespace FTDI; -using namespace Theme; - -#define GRID_COLS 2 -#define GRID_ROWS 6 - -#define TITLE_POS BTN_POS(1,1), BTN_SIZE(2,1) -#define DESCRIPTION_POS BTN_POS(1,2), BTN_SIZE(2,3) -#define CARTRIDGE_OUT_BTN_POS BTN_POS(1,5), BTN_SIZE(1,1) -#define CARTRIDGE_IN_BTN_POS BTN_POS(2,5), BTN_SIZE(1,1) -#define BACK_BTN_POS BTN_POS(1,6), BTN_SIZE(2,1) - -void UnloadCartridgeScreen::onRedraw(draw_mode_t what) { - CommandProcessor cmd; - - if (what & BACKGROUND) { - cmd.cmd(CLEAR_COLOR_RGB(bg_color)) - .cmd(CLEAR(true,true,true)) - .cmd(COLOR_RGB(bg_text_enabled)) - .tag(0) - .font(font_large) - .text(TITLE_POS, GET_TEXT_F(MSG_UNLOAD_CARTRIDGE)); - draw_text_box(cmd, DESCRIPTION_POS, F( - "Press and hold the buttons below to help " - "you unlock the cartridge. After unlocking, " - "press and hold the Cartridge Out button " - "until the cartridge is sticking out of the " - "extruder enough to grip and remove. After " - "removing the cartridge, continue holding the " - "Cartridge Out button until the plunger adapter is " - "visible at the bottom of the extruder." - ), - OPT_CENTERY, font_medium); - } - - if (what & FOREGROUND) { - cmd.font(font_medium) - .colors(normal_btn) - .tag(2).button(CARTRIDGE_OUT_BTN_POS, GET_TEXT_F(MSG_CARTRIDGE_OUT)) - .tag(3).button(CARTRIDGE_IN_BTN_POS, GET_TEXT_F(MSG_CARTRIDGE_IN)) - .colors(action_btn) - .tag(1).button(BACK_BTN_POS, GET_TEXT_F(MSG_BACK)); - } -} - -bool UnloadCartridgeScreen::onTouchEnd(uint8_t tag) { - using namespace ExtUI; - switch (tag) { - case 1: GOTO_PREVIOUS(); break; - } - return true; -} - -bool UnloadCartridgeScreen::onTouchHeld(uint8_t tag) { - if (ExtUI::isMoving()) return false; // Don't allow moves to accumulate - constexpr float increment = 0.25; - MoveAxisScreen::setManualFeedrate(E0, increment); - #define UI_INCREMENT_AXIS(axis) UI_INCREMENT(AxisPosition_mm, axis); - #define UI_DECREMENT_AXIS(axis) UI_DECREMENT(AxisPosition_mm, axis); - switch (tag) { - case 2: UI_DECREMENT_AXIS(E0); break; - case 3: UI_INCREMENT_AXIS(E0); break; - default: return false; - } - #undef UI_DECREMENT_AXIS - #undef UI_INCREMENT_AXIS - return false; -} - -#endif // FTDI_COCOA_UNLOAD_CARTRIDGE_SCREEN diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/colors.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/colors.h index 1649675122e93..995379fcdab72 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/colors.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/theme/colors.h @@ -108,6 +108,7 @@ namespace Theme { constexpr uint32_t bed_mesh_lines_rgb = accent_color_6; constexpr uint32_t bed_mesh_shadow_rgb = 0x444444; + #define BED_MESH_POINTS_GRAY #else constexpr uint32_t theme_darkest = gray_color_1; constexpr uint32_t theme_dark = gray_color_2; diff --git a/Marlin/src/lcd/extui/mks_ui/draw_media_select.cpp b/Marlin/src/lcd/extui/mks_ui/draw_media_select.cpp index 6fa5cefef0a4c..0394ed6009d69 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_media_select.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_media_select.cpp @@ -46,8 +46,8 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { if (event != LV_EVENT_RELEASED) return; lv_clear_media_select(); switch (obj->mks_obj_id) { - case ID_T_USB_DISK: card.changeMedia(&card.media_usbFlashDrive); break; - case ID_T_SD_DISK: card.changeMedia(&card.media_sd_spi); break; + case ID_T_USB_DISK: card.changeMedia(&card.media_driver_usbFlash); break; + case ID_T_SD_DISK: card.changeMedia(&card.media_driver_sdcard); break; case ID_T_RETURN: TERN_(MKS_TEST, curent_disp_ui = 1); lv_draw_ready_print(); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.cpp b/Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.cpp index b0f55a1d45c23..bf1b9c3459aba 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_tmc_step_mode_settings.cpp @@ -68,30 +68,20 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { draw_return_ui(); break; - #if AXIS_HAS_STEALTHCHOP(X) - case ID_TMC_MODE_X: - toggle_chop(stepperX, buttonXState); - break; + #if X_HAS_STEALTHCHOP + case ID_TMC_MODE_X: toggle_chop(stepperX, buttonXState); break; #endif - #if AXIS_HAS_STEALTHCHOP(Y) - case ID_TMC_MODE_Y: - toggle_chop(stepperY, buttonYState); - break; + #if Y_HAS_STEALTHCHOP + case ID_TMC_MODE_Y: toggle_chop(stepperY, buttonYState); break; #endif - #if AXIS_HAS_STEALTHCHOP(Z) - case ID_TMC_MODE_Z: - toggle_chop(stepperZ, buttonZState); - break; + #if Z_HAS_STEALTHCHOP + case ID_TMC_MODE_Z: toggle_chop(stepperZ, buttonZState); break; #endif - #if AXIS_HAS_STEALTHCHOP(E0) - case ID_TMC_MODE_E0: - toggle_chop(stepperE0, buttonE0State); - break; + #if E0_HAS_STEALTHCHOP + case ID_TMC_MODE_E0: toggle_chop(stepperE0, buttonE0State); break; #endif - #if AXIS_HAS_STEALTHCHOP(E1) - case ID_TMC_MODE_E1: - toggle_chop(stepperE1, buttonE1State); - break; + #if E1_HAS_STEALTHCHOP + case ID_TMC_MODE_E1: toggle_chop(stepperE1, buttonE1State); break; #endif case ID_TMC_MODE_UP: @@ -113,21 +103,11 @@ void lv_draw_tmc_step_mode_settings() { scr = lv_screen_create(TMC_MODE_UI, machine_menu.TmcStepModeConfTitle); bool stealth_X = false, stealth_Y = false, stealth_Z = false, stealth_E0 = false, stealth_E1 = false; - #if AXIS_HAS_STEALTHCHOP(X) - stealth_X = stepperX.get_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - stealth_Y = stepperY.get_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - stealth_Z = stepperZ.get_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(E0) - stealth_E0 = stepperE0.get_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(E1) - stealth_E1 = stepperE1.get_stealthChop(); - #endif + TERN_(X_HAS_STEALTHCHOP, stealth_X = stepperX.get_stealthChop()); + TERN_(Y_HAS_STEALTHCHOP, stealth_Y = stepperY.get_stealthChop()); + TERN_(Z_HAS_STEALTHCHOP, stealth_Z = stepperZ.get_stealthChop()); + TERN_(E0_HAS_STEALTHCHOP, stealth_E0 = stepperE0.get_stealthChop()); + TERN_(E1_HAS_STEALTHCHOP, stealth_E1 = stepperE1.get_stealthChop()); if (!uiCfg.para_ui_page) { buttonXState = lv_screen_menu_item_onoff(scr, machine_menu.X_StepMode, PARA_UI_POS_X, PARA_UI_POS_Y, event_handler, ID_TMC_MODE_X, 0, stealth_X); diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index fff31f099bf7a..00b785e6807f4 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -47,6 +47,7 @@ #include "../marlinui.h" #include "../../gcode/queue.h" +#include "../../gcode/gcode.h" #include "../../module/motion.h" #include "../../module/planner.h" #include "../../module/probe.h" @@ -304,7 +305,7 @@ namespace ExtUI { } float getAxisPosition_mm(const axis_t axis) { - return TERN0(JOYSTICK, flags.jogging) ? destination[axis] : current_position[axis]; + return current_position[axis]; } float getAxisPosition_mm(const extruder_t extruder) { @@ -353,14 +354,9 @@ namespace ExtUI { extruder_t getTool(const uint8_t extruder) { switch (extruder) { - case 7: return E7; - case 6: return E6; - case 5: return E5; - case 4: return E4; - case 3: return E3; - case 2: return E2; - case 1: return E1; - default: return E0; + default: + case 0: return E0; case 1: return E1; case 2: return E2; case 3: return E3; + case 4: return E4; case 5: return E5; case 6: return E6; case 7: return E7; } } @@ -372,8 +368,8 @@ namespace ExtUI { switch (axis) { #if IS_KINEMATIC || ENABLED(NO_MOTION_BEFORE_HOMING) case X: return axis_should_home(X_AXIS); - case Y: return axis_should_home(Y_AXIS); - case Z: return axis_should_home(Z_AXIS); + OPTCODE(HAS_Y_AXIS, case Y: return axis_should_home(Y_AXIS)) + OPTCODE(HAS_Z_AXIS, case Z: return axis_should_home(Z_AXIS)) #else case X: case Y: case Z: return true; #endif @@ -385,6 +381,8 @@ namespace ExtUI { return !thermalManager.tooColdToExtrude(extruder - E0); } + GcodeSuite::MarlinBusyState getMachineBusyState() { return TERN0(HOST_KEEPALIVE_FEATURE, GcodeSuite::busy_state); } + #if HAS_SOFTWARE_ENDSTOPS bool getSoftEndstopState() { return soft_endstop._enabled; } void setSoftEndstopState(const bool value) { soft_endstop._enabled = value; } @@ -396,18 +394,27 @@ namespace ExtUI { #if AXIS_IS_TMC(X) case X: return stepperX.getMilliamps(); #endif - #if AXIS_IS_TMC(X2) - case X2: return stepperX2.getMilliamps(); - #endif #if AXIS_IS_TMC(Y) case Y: return stepperY.getMilliamps(); #endif - #if AXIS_IS_TMC(Y2) - case Y2: return stepperY2.getMilliamps(); - #endif #if AXIS_IS_TMC(Z) case Z: return stepperZ.getMilliamps(); #endif + #if AXIS_IS_TMC(I) + case I: return stepperI.getMilliamps(); + #endif + #if AXIS_IS_TMC(J) + case J: return stepperJ.getMilliamps(); + #endif + #if AXIS_IS_TMC(K) + case K: return stepperK.getMilliamps(); + #endif + #if AXIS_IS_TMC(X2) + case X2: return stepperX2.getMilliamps(); + #endif + #if AXIS_IS_TMC(Y2) + case Y2: return stepperY2.getMilliamps(); + #endif #if AXIS_IS_TMC(Z2) case Z2: return stepperZ2.getMilliamps(); #endif @@ -450,18 +457,27 @@ namespace ExtUI { #if AXIS_IS_TMC(X) case X: stepperX.rms_current(constrain(mA, 400, 1500)); break; #endif - #if AXIS_IS_TMC(X2) - case X2: stepperX2.rms_current(constrain(mA, 400, 1500)); break; - #endif #if AXIS_IS_TMC(Y) case Y: stepperY.rms_current(constrain(mA, 400, 1500)); break; #endif - #if AXIS_IS_TMC(Y2) - case Y2: stepperY2.rms_current(constrain(mA, 400, 1500)); break; - #endif #if AXIS_IS_TMC(Z) case Z: stepperZ.rms_current(constrain(mA, 400, 1500)); break; #endif + #if AXIS_IS_TMC(I) + case I: stepperI.rms_current(constrain(mA, 400, 1500)); break; + #endif + #if AXIS_IS_TMC(J) + case J: stepperJ.rms_current(constrain(mA, 400, 1500)); break; + #endif + #if AXIS_IS_TMC(K) + case K: stepperK.rms_current(constrain(mA, 400, 1500)); break; + #endif + #if AXIS_IS_TMC(X2) + case X2: stepperX2.rms_current(constrain(mA, 400, 1500)); break; + #endif + #if AXIS_IS_TMC(Y2) + case Y2: stepperY2.rms_current(constrain(mA, 400, 1500)); break; + #endif #if AXIS_IS_TMC(Z2) case Z2: stepperZ2.rms_current(constrain(mA, 400, 1500)); break; #endif @@ -501,66 +517,59 @@ namespace ExtUI { int getTMCBumpSensitivity(const axis_t axis) { switch (axis) { - #if ENABLED(X_SENSORLESS) - case X: return stepperX.homing_threshold(); + OPTCODE(X_SENSORLESS, case X: return stepperX.homing_threshold()) + OPTCODE(Y_SENSORLESS, case Y: return stepperY.homing_threshold()) + OPTCODE(Z_SENSORLESS, case Z: return stepperZ.homing_threshold()) + OPTCODE(I_SENSORLESS, case I: return stepperI.homing_threshold()) + OPTCODE(J_SENSORLESS, case J: return stepperJ.homing_threshold()) + OPTCODE(K_SENSORLESS, case K: return stepperK.homing_threshold()) + OPTCODE(X2_SENSORLESS, case X2: return stepperX2.homing_threshold()) + OPTCODE(Y2_SENSORLESS, case Y2: return stepperY2.homing_threshold()) + OPTCODE(Z2_SENSORLESS, case Z2: return stepperZ2.homing_threshold()) + OPTCODE(Z3_SENSORLESS, case Z3: return stepperZ3.homing_threshold()) + OPTCODE(Z4_SENSORLESS, case Z4: return stepperZ4.homing_threshold()) + default: return 0; + } + } + + void setTMCBumpSensitivity(const_float_t value, const axis_t axis) { + switch (axis) { + #if X_SENSORLESS + case X: stepperX.homing_threshold(value); break; #endif - #if ENABLED(X2_SENSORLESS) - case X2: return stepperX2.homing_threshold(); + #if Y_SENSORLESS + case Y: stepperY.homing_threshold(value); break; #endif - #if ENABLED(Y_SENSORLESS) - case Y: return stepperY.homing_threshold(); + #if Z_SENSORLESS + case Z: stepperZ.homing_threshold(value); break; #endif - #if ENABLED(Y2_SENSORLESS) - case Y2: return stepperY2.homing_threshold(); + #if I_SENSORLESS + case I: stepperI.homing_threshold(value); break; #endif - #if ENABLED(Z_SENSORLESS) - case Z: return stepperZ.homing_threshold(); + #if J_SENSORLESS + case J: stepperJ.homing_threshold(value); break; #endif - #if ENABLED(Z2_SENSORLESS) - case Z2: return stepperZ2.homing_threshold(); + #if K_SENSORLESS + case K: stepperK.homing_threshold(value); break; #endif - #if ENABLED(Z3_SENSORLESS) - case Z3: return stepperZ3.homing_threshold(); + #if X2_SENSORLESS + case X2: stepperX2.homing_threshold(value); break; #endif - #if ENABLED(Z4_SENSORLESS) - case Z4: return stepperZ4.homing_threshold(); + #if Y2_SENSORLESS + case Y2: stepperY2.homing_threshold(value); break; #endif - default: return 0; - } - } - - void setTMCBumpSensitivity(const_float_t value, const axis_t axis) { - switch (axis) { - #if X_SENSORLESS || Y_SENSORLESS || Z_SENSORLESS - #if X_SENSORLESS - case X: stepperX.homing_threshold(value); break; - #endif - #if X2_SENSORLESS - case X2: stepperX2.homing_threshold(value); break; - #endif - #if Y_SENSORLESS - case Y: stepperY.homing_threshold(value); break; - #endif - #if Y2_SENSORLESS - case Y2: stepperY2.homing_threshold(value); break; - #endif - #if Z_SENSORLESS - case Z: stepperZ.homing_threshold(value); break; - #endif - #if Z2_SENSORLESS - case Z2: stepperZ2.homing_threshold(value); break; - #endif - #if Z3_SENSORLESS - case Z3: stepperZ3.homing_threshold(value); break; - #endif - #if Z4_SENSORLESS - case Z4: stepperZ4.homing_threshold(value); break; - #endif - #else - UNUSED(value); + #if Z2_SENSORLESS + case Z2: stepperZ2.homing_threshold(value); break; + #endif + #if Z3_SENSORLESS + case Z3: stepperZ3.homing_threshold(value); break; + #endif + #if Z4_SENSORLESS + case Z4: stepperZ4.homing_threshold(value); break; #endif default: break; } + UNUSED(value); } #endif @@ -661,9 +670,7 @@ namespace ExtUI { #if HAS_JUNCTION_DEVIATION - float getJunctionDeviation_mm() { - return planner.junction_deviation_mm; - } + float getJunctionDeviation_mm() { return planner.junction_deviation_mm; } void setJunctionDeviation_mm(const_float_t value) { planner.junction_deviation_mm = constrain(value, 0.001, 0.3); @@ -682,7 +689,7 @@ namespace ExtUI { #endif #if PREHEAT_COUNT - uint16_t getMaterial_preset_E(const uint16_t index) { return ui.material_preset[index].hotend_temp; } + uint16_t getMaterial_preset_E(const uint16_t index) { return ui.material_preset[index].hotend_temp; } #if HAS_HEATED_BED uint16_t getMaterial_preset_B(const uint16_t index) { return ui.material_preset[index].bed_temp; } #endif @@ -709,9 +716,13 @@ namespace ExtUI { switch (axis) { #if ENABLED(BABYSTEP_XY) case X: babystep.add_steps(X_AXIS, steps); break; - case Y: babystep.add_steps(Y_AXIS, steps); break; + #if HAS_Y_AXIS + case Y: babystep.add_steps(Y_AXIS, steps); break; + #endif + #endif + #if HAS_Z_AXIS + case Z: babystep.add_steps(Z_AXIS, steps); break; #endif - case Z: babystep.add_steps(Z_AXIS, steps); break; default: return false; }; return true; @@ -750,8 +761,8 @@ namespace ExtUI { hotend_offset[e][axis] += mm; normalizeNozzleOffset(X); - normalizeNozzleOffset(Y); - normalizeNozzleOffset(Z); + TERN_(HAS_Y_AXIS, normalizeNozzleOffset(Y)); + TERN_(HAS_Z_AXIS, normalizeNozzleOffset(Z)); } #else UNUSED(linked_nozzles); @@ -767,6 +778,10 @@ namespace ExtUI { return steps > 0 ? CEIL(steps) : FLOOR(steps); } + float mmFromWholeSteps(int16_t steps, const axis_t axis) { + return steps * planner.steps_to_mm[axis]; + } + #endif // BABYSTEPPING float getZOffset_mm() { @@ -1010,8 +1025,7 @@ namespace ExtUI { TERN_(HAS_FAN, thermalManager.zero_fan_speeds()); } - bool awaitingUserConfirm() { return wait_for_user; } - + bool awaitingUserConfirm() { return TERN0(HAS_RESUME_CONTINUE, wait_for_user); } void setUserConfirmed() { TERN_(HAS_RESUME_CONTINUE, wait_for_user = false); } void printFile(const char *filename) { @@ -1019,10 +1033,10 @@ namespace ExtUI { } bool isPrintingFromMediaPaused() { - return TERN0(SDSUPPORT, isPrintingFromMedia() && printingIsPaused()); + return TERN0(SDSUPPORT, IS_SD_PAUSED()); } - bool isPrintingFromMedia() { return IS_SD_PRINTING(); } + bool isPrintingFromMedia() { return TERN0(SDSUPPORT, IS_SD_PRINTING() || IS_SD_PAUSED()); } bool isPrinting() { return commandsInQueue() || isPrintingFromMedia() || printJobOngoing() || printingIsPaused(); @@ -1034,9 +1048,9 @@ namespace ExtUI { bool isMediaInserted() { return TERN0(SDSUPPORT, IS_SD_INSERTED() && card.isMounted()); } - void pausePrint() { ui.pause_print(); } + void pausePrint() { ui.pause_print(); } void resumePrint() { ui.resume_print(); } - void stopPrint() { ui.abort_print(); } + void stopPrint() { ui.abort_print(); } void onUserConfirmRequired_P(PGM_P const pstr) { char msg[strlen_P(pstr) + 1]; diff --git a/Marlin/src/lcd/extui/ui_api.h b/Marlin/src/lcd/extui/ui_api.h index 56031696260b4..8d8b0e59e415b 100644 --- a/Marlin/src/lcd/extui/ui_api.h +++ b/Marlin/src/lcd/extui/ui_api.h @@ -44,6 +44,7 @@ #include "../../inc/MarlinConfig.h" #include "../marlinui.h" +#include "../../gcode/gcode.h" namespace ExtUI { @@ -53,7 +54,7 @@ namespace ExtUI { static constexpr size_t eeprom_data_size = 48; - enum axis_t : uint8_t { X, Y, Z, X2, Y2, Z2, Z3, Z4 }; + enum axis_t : uint8_t { X, Y, Z, I, J, K, X2, Y2, Z2, Z3, Z4 }; enum extruder_t : uint8_t { E0, E1, E2, E3, E4, E5, E6, E7 }; enum heater_t : uint8_t { H0, H1, H2, H3, H4, H5, BED, CHAMBER, COOLER }; enum fan_t : uint8_t { FAN0, FAN1, FAN2, FAN3, FAN4, FAN5, FAN6, FAN7 }; @@ -78,6 +79,8 @@ namespace ExtUI { void injectCommands(char * const); bool commandsInQueue(); + GcodeSuite::MarlinBusyState getMachineBusyState(); + bool isHeaterIdle(const heater_t); bool isHeaterIdle(const extruder_t); void enableHeater(const heater_t); @@ -125,6 +128,7 @@ namespace ExtUI { float getAxisMaxAcceleration_mm_s2(const extruder_t); feedRate_t getMinFeedrate_mm_s(); feedRate_t getMinTravelFeedrate_mm_s(); + feedRate_t getFeedrate_mm_s(); float getPrintingAcceleration_mm_s2(); float getRetractAcceleration_mm_s2(); float getTravelAcceleration_mm_s2(); @@ -186,6 +190,8 @@ namespace ExtUI { void setHostResponse(const uint8_t); #endif + inline void simulateUserClick() { ui.lcd_clicked = true; } + #if ENABLED(PRINTCOUNTER) char* getFailedPrints_str(char buffer[21]); char* getTotalPrints_str(char buffer[21]); @@ -239,6 +245,7 @@ namespace ExtUI { #if ENABLED(BABYSTEPPING) int16_t mmToWholeSteps(const_float_t mm, const axis_t axis); + float mmFromWholeSteps(int16_t steps, const axis_t axis); bool babystepAxis_steps(const int16_t steps, const axis_t axis); void smartAdjustAxis_steps(const int16_t steps, const axis_t axis, bool linked_nozzles); diff --git a/Marlin/src/lcd/language/language_an.h b/Marlin/src/lcd/language/language_an.h index 0513de7f7d8f5..787096994f7da 100644 --- a/Marlin/src/lcd/language/language_an.h +++ b/Marlin/src/lcd/language/language_an.h @@ -89,6 +89,7 @@ namespace Language_an { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Mover 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mover 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Mover 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Mover 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Velocidat"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Base Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Boquilla"); diff --git a/Marlin/src/lcd/language/language_bg.h b/Marlin/src/lcd/language/language_bg.h index 59646521567a0..0d4291b8355d2 100644 --- a/Marlin/src/lcd/language/language_bg.h +++ b/Marlin/src/lcd/language/language_bg.h @@ -79,6 +79,7 @@ namespace Language_bg { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Премести с 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Премести с 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Премести с 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Премести с 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Скорост"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Bed Z"); PROGMEM Language_Str MSG_NOZZLE = " " LCD_STR_THERMOMETER _UxGT(" Дюза"); diff --git a/Marlin/src/lcd/language/language_ca.h b/Marlin/src/lcd/language/language_ca.h index 6709a0ce5543a..f97a783d01836 100644 --- a/Marlin/src/lcd/language/language_ca.h +++ b/Marlin/src/lcd/language/language_ca.h @@ -89,6 +89,7 @@ namespace Language_ca { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Mou 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mou 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Mou 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Mou 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Velocitat"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Llit Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Nozzle"); diff --git a/Marlin/src/lcd/language/language_cz.h b/Marlin/src/lcd/language/language_cz.h index c434f5493b922..ab2aaa943f8d1 100644 --- a/Marlin/src/lcd/language/language_cz.h +++ b/Marlin/src/lcd/language/language_cz.h @@ -241,6 +241,7 @@ namespace Language_cz { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Posunout o 0,1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Posunout o 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Posunout o 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Posunout o 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Rychlost"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Výška podl."); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Tryska"); diff --git a/Marlin/src/lcd/language/language_da.h b/Marlin/src/lcd/language/language_da.h index 925881284376e..95c2573ae1448 100644 --- a/Marlin/src/lcd/language/language_da.h +++ b/Marlin/src/lcd/language/language_da.h @@ -79,6 +79,7 @@ namespace Language_da { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Flyt 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Flyt 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Flyt 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Flyt 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Hastighed"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Plade Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Dyse"); diff --git a/Marlin/src/lcd/language/language_de.h b/Marlin/src/lcd/language/language_de.h index ebc2445b11e95..7e40d4266562a 100644 --- a/Marlin/src/lcd/language/language_de.h +++ b/Marlin/src/lcd/language/language_de.h @@ -231,9 +231,10 @@ namespace Language_de { PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Bewege Extruder *"); PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Hotend zu kalt"); PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT(" %s mm"); - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT(" 0,1 mm"); - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT(" 1,0 mm"); - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("10,0 mm"); + PROGMEM Language_Str MSG_MOVE_01MM = _UxGT(" 0,1 mm"); + PROGMEM Language_Str MSG_MOVE_1MM = _UxGT(" 1,0 mm"); + PROGMEM Language_Str MSG_MOVE_10MM = _UxGT(" 10,0 mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("100,0 mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Geschw."); PROGMEM Language_Str MSG_BED_Z = _UxGT("Bett Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Düse"); diff --git a/Marlin/src/lcd/language/language_el.h b/Marlin/src/lcd/language/language_el.h index ebe27fecbd9ab..b69b4695d3bee 100644 --- a/Marlin/src/lcd/language/language_el.h +++ b/Marlin/src/lcd/language/language_el.h @@ -87,6 +87,7 @@ namespace Language_el { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Μετακίνηση 0,1 μμ"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Μετακίνηση 1 μμ"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Μετακίνηση 10 μμ"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Μετακίνηση 100 μμ"); PROGMEM Language_Str MSG_SPEED = _UxGT("Ταχύτητα"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Επ. Εκτύπωσης Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Ακροφύσιο"); diff --git a/Marlin/src/lcd/language/language_el_gr.h b/Marlin/src/lcd/language/language_el_gr.h index e6909ad5bfb7d..208d7c2363be5 100644 --- a/Marlin/src/lcd/language/language_el_gr.h +++ b/Marlin/src/lcd/language/language_el_gr.h @@ -88,6 +88,7 @@ namespace Language_el_gr { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Μετακίνηση 0,1 μμ"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Μετακίνηση 1 μμ"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Μετακίνηση 10 μμ"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Μετακίνηση 100 μμ"); PROGMEM Language_Str MSG_SPEED = _UxGT("Ταχύτητα"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Κλίνη Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Ακροφύσιο"); diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 34b2c0bb5b6f0..6920f00d36b54 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -72,6 +72,9 @@ namespace Language_en { PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Home X"); PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Home Y"); PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Home Z"); + PROGMEM Language_Str MSG_AUTO_HOME_I = _UxGT("Home ") LCD_STR_I; + PROGMEM Language_Str MSG_AUTO_HOME_J = _UxGT("Home ") LCD_STR_J; + PROGMEM Language_Str MSG_AUTO_HOME_K = _UxGT("Home ") LCD_STR_K; PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Auto Z-Align"); PROGMEM Language_Str MSG_ITERATION = _UxGT("G34 Iteration: %i"); PROGMEM Language_Str MSG_DECREASING_ACCURACY = _UxGT("Accuracy Decreasing!"); @@ -85,6 +88,9 @@ namespace Language_en { PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("Home Offset X"); PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Home Offset Y"); PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Home Offset Z"); + PROGMEM Language_Str MSG_HOME_OFFSET_I = _UxGT("Home Offset ") LCD_STR_I; + PROGMEM Language_Str MSG_HOME_OFFSET_J = _UxGT("Home Offset ") LCD_STR_J; + PROGMEM Language_Str MSG_HOME_OFFSET_K = _UxGT("Home Offset ") LCD_STR_K; PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Offsets Applied"); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Set Origin"); PROGMEM Language_Str MSG_ASSISTED_TRAMMING = _UxGT("Assisted Tramming"); @@ -265,6 +271,9 @@ namespace Language_en { PROGMEM Language_Str MSG_MOVE_X = _UxGT("Move X"); PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Move Y"); PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Move Z"); + PROGMEM Language_Str MSG_MOVE_I = _UxGT("Move ") LCD_STR_I; + PROGMEM Language_Str MSG_MOVE_J = _UxGT("Move ") LCD_STR_J; + PROGMEM Language_Str MSG_MOVE_K = _UxGT("Move ") LCD_STR_K; PROGMEM Language_Str MSG_MOVE_E = _UxGT("Extruder"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Extruder *"); PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Hotend too cold"); @@ -272,9 +281,11 @@ namespace Language_en { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Move 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Move 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Move 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Move 100mm"); PROGMEM Language_Str MSG_MOVE_0001IN = _UxGT("Move 0.001in"); PROGMEM Language_Str MSG_MOVE_001IN = _UxGT("Move 0.01in"); PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Move 0.1in"); + PROGMEM Language_Str MSG_MOVE_1IN = _UxGT("Move 1.0in"); PROGMEM Language_Str MSG_SPEED = _UxGT("Speed"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Bed Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Nozzle"); @@ -329,12 +340,18 @@ namespace Language_en { PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-Jerk"); PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-Jerk"); PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-Jerk"); + PROGMEM Language_Str MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-Jerk"); + PROGMEM Language_Str MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-Jerk"); + PROGMEM Language_Str MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-Jerk"); PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-Jerk"); PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev"); PROGMEM Language_Str MSG_VELOCITY = _UxGT("Velocity"); PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A; PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; + PROGMEM Language_Str MSG_VMAX_I = _UxGT("Vmax ") LCD_STR_I; + PROGMEM Language_Str MSG_VMAX_J = _UxGT("Vmax ") LCD_STR_J; + PROGMEM Language_Str MSG_VMAX_K = _UxGT("Vmax ") LCD_STR_K; PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vmax *"); PROGMEM Language_Str MSG_VMIN = _UxGT("Vmin"); @@ -343,6 +360,9 @@ namespace Language_en { PROGMEM Language_Str MSG_AMAX_A = _UxGT("Amax ") LCD_STR_A; PROGMEM Language_Str MSG_AMAX_B = _UxGT("Amax ") LCD_STR_B; PROGMEM Language_Str MSG_AMAX_C = _UxGT("Amax ") LCD_STR_C; + PROGMEM Language_Str MSG_AMAX_I = _UxGT("Amax ") LCD_STR_I; + PROGMEM Language_Str MSG_AMAX_J = _UxGT("Amax ") LCD_STR_J; + PROGMEM Language_Str MSG_AMAX_K = _UxGT("Amax ") LCD_STR_K; PROGMEM Language_Str MSG_AMAX_E = _UxGT("Amax ") LCD_STR_E; PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Amax *"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-Retract"); @@ -353,6 +373,9 @@ namespace Language_en { PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" Steps/mm"); PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" Steps/mm"); PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" Steps/mm"); + PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" Steps/mm"); + PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" Steps/mm"); + PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" Steps/mm"); PROGMEM Language_Str MSG_E_STEPS = _UxGT("E steps/mm"); PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* Steps/mm"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperature"); @@ -486,6 +509,9 @@ namespace Language_en { PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Babystep X"); PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Babystep Y"); PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Babystep Z"); + PROGMEM Language_Str MSG_BABYSTEP_I = _UxGT("Babystep ") LCD_STR_I; + PROGMEM Language_Str MSG_BABYSTEP_J = _UxGT("Babystep ") LCD_STR_J; + PROGMEM Language_Str MSG_BABYSTEP_K = _UxGT("Babystep ") LCD_STR_K; PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Total"); PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Endstop Abort"); PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Heating Failed"); @@ -566,6 +592,9 @@ namespace Language_en { PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Driver %"); PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y Driver %"); PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = AXIS4_STR _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = AXIS5_STR _UxGT(" Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = AXIS6_STR _UxGT(" Driver %"); PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Driver %"); PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("TMC CONNECTION ERROR"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM Write"); @@ -683,6 +712,9 @@ namespace Language_en { PROGMEM Language_Str MSG_BACKLASH_A = LCD_STR_A; PROGMEM Language_Str MSG_BACKLASH_B = LCD_STR_B; PROGMEM Language_Str MSG_BACKLASH_C = LCD_STR_C; + PROGMEM Language_Str MSG_BACKLASH_I = LCD_STR_I; + PROGMEM Language_Str MSG_BACKLASH_J = LCD_STR_J; + PROGMEM Language_Str MSG_BACKLASH_K = LCD_STR_K; PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Correction"); PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Smoothing"); @@ -710,6 +742,9 @@ namespace Language_en { PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Calibration Failed"); PROGMEM Language_Str MSG_DRIVER_BACKWARD = _UxGT(" driver backward"); + + PROGMEM Language_Str MSG_SD_CARD = _UxGT("SD Card"); + PROGMEM Language_Str MSG_USB_DISK = _UxGT("USB Disk"); } #if FAN_COUNT == 1 diff --git a/Marlin/src/lcd/language/language_es.h b/Marlin/src/lcd/language/language_es.h index b2d83aa05ba73..f342732161331 100644 --- a/Marlin/src/lcd/language/language_es.h +++ b/Marlin/src/lcd/language/language_es.h @@ -236,6 +236,7 @@ namespace Language_es { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Mover 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mover 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Mover 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Mover 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Velocidad"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Cama Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Boquilla"); diff --git a/Marlin/src/lcd/language/language_eu.h b/Marlin/src/lcd/language/language_eu.h index 1c1c9e423dcdd..2be6f399d8d35 100644 --- a/Marlin/src/lcd/language/language_eu.h +++ b/Marlin/src/lcd/language/language_eu.h @@ -143,6 +143,7 @@ namespace Language_eu { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Mugitu 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mugitu 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Mugitu 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Mugitu 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Abiadura"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Z Ohea"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Pita"); diff --git a/Marlin/src/lcd/language/language_fi.h b/Marlin/src/lcd/language/language_fi.h index 9954f1dd8aaf7..0d3b97cc44afa 100644 --- a/Marlin/src/lcd/language/language_fi.h +++ b/Marlin/src/lcd/language/language_fi.h @@ -76,6 +76,7 @@ namespace Language_fi { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Liikuta 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Liikuta 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Liikuta 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Liikuta 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Nopeus"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Suutin"); PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Suutin ~"); diff --git a/Marlin/src/lcd/language/language_fr.h b/Marlin/src/lcd/language/language_fr.h index bdd91d3b2975f..5dbec298d4955 100644 --- a/Marlin/src/lcd/language/language_fr.h +++ b/Marlin/src/lcd/language/language_fr.h @@ -235,6 +235,7 @@ namespace Language_fr { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Déplacer 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Déplacer 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Déplacer 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Déplacer 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Vitesse"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Lit Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Buse"); diff --git a/Marlin/src/lcd/language/language_gl.h b/Marlin/src/lcd/language/language_gl.h index 5745ce1eb804f..3eec75e138f93 100644 --- a/Marlin/src/lcd/language/language_gl.h +++ b/Marlin/src/lcd/language/language_gl.h @@ -233,6 +233,7 @@ namespace Language_gl { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Mover 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mover 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Mover 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Mover 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Velocidade"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Cama Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Bico"); diff --git a/Marlin/src/lcd/language/language_hr.h b/Marlin/src/lcd/language/language_hr.h index 1684ad0e1bc24..e4cbdaed6c614 100644 --- a/Marlin/src/lcd/language/language_hr.h +++ b/Marlin/src/lcd/language/language_hr.h @@ -83,6 +83,7 @@ namespace Language_hr { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Miči 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Miči 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Miči 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Miči 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Brzina"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Bed Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Dizna"); diff --git a/Marlin/src/lcd/language/language_hu.h b/Marlin/src/lcd/language/language_hu.h index b2c1d30f331f3..0c73d9a85af1e 100644 --- a/Marlin/src/lcd/language/language_hu.h +++ b/Marlin/src/lcd/language/language_hu.h @@ -26,11 +26,11 @@ * * LCD Menu Messages. See also https://marlinfw.org/docs/development/lcd_language.html * Hungarian translation by AntoszHUN. I am constantly improving and updating the translation. - * Translation last updated: 21/03/2021 - 21:00 + * Translation last updated: 23/05/2021 - 20:45 * * LCD Menü Üzenetek. Lásd még https://marlinfw.org/docs/development/lcd_language.html * A Magyar fordítást készítette: AntoszHUN. A fordítást folyamatosan javítom és frissítem. - * A Fordítás utolsó frissítése: 2021.03.21. - 21:00 + * A Fordítás utolsó frissítése: 2021.05.23. - 20:45 */ namespace Language_hu { @@ -76,6 +76,9 @@ namespace Language_hu { PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Szintezés kész!"); PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Szint csökkentés"); PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Kezdöpont eltolás"); + PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("X Kezdö eltol."); + PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Y Kezdö eltol."); + PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Z Kezdö eltol."); PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Eltolás beállítva."); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Eredeti Be"); PROGMEM Language_Str MSG_ASSISTED_TRAMMING = _UxGT("Elektromos segéd"); @@ -108,12 +111,15 @@ namespace Language_hu { PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Lézer telj."); PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Orsó telj."); PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Lézer váltás"); + PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Hütés váltás"); + PROGMEM Language_Str MSG_LASER_ASSIST_TOGGLE = _UxGT("Levegö segéd"); PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Impulzus teszt ms"); PROGMEM Language_Str MSG_LASER_FIRE_PULSE = _UxGT("Tüz impulzus"); + PROGMEM Language_Str MSG_FLOWMETER_FAULT = _UxGT("Áramlási hiba"); PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Orsóváltás"); - PROGMEM Language_Str MSG_SPINDLE_FORWARD = _UxGT("Orsó előre"); + PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Vákuum váltás"); + PROGMEM Language_Str MSG_SPINDLE_FORWARD = _UxGT("Orsó elöre"); PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Orsó hátra"); - PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Bekapcsolás"); PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Kikapcsolás"); PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Adagol"); @@ -134,7 +140,7 @@ namespace Language_hu { PROGMEM Language_Str MSG_MESH_X = _UxGT("Index X"); PROGMEM Language_Str MSG_MESH_Y = _UxGT("Index Y"); PROGMEM Language_Str MSG_MESH_EDIT_Z = _UxGT("Z érték"); - PROGMEM Language_Str MSG_USER_MENU = _UxGT("Egyéni parancs"); + PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("Egyéni parancs"); PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 Szonda teszt"); PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 Pont"); PROGMEM Language_Str MSG_M48_OUT_OF_BOUNDS = _UxGT("Szonda határon kívül"); @@ -154,6 +160,7 @@ namespace Language_hu { PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Egységes ágy szint"); PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Döntési pont"); PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Kézi háló építés"); + PROGMEM Language_Str MSG_UBL_MESH_WIZARD = _UxGT("UBL Háló varázsló"); PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Tégy alátétet és mérj"); PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Mérés"); PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Üres ágyat mérj"); @@ -161,9 +168,9 @@ namespace Language_hu { PROGMEM Language_Str MSG_UBL_ACTIVATE_MESH = _UxGT("UBL aktívál"); PROGMEM Language_Str MSG_UBL_DEACTIVATE_MESH = _UxGT("UBL deaktívál"); PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = _UxGT("Ágy höfok"); - PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Ágy höfok"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = _UxGT("Fej höfok"); - PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Fej höfok"); + PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Egyéni ágy höfok"); + PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = _UxGT("Fejhöfok"); + PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Egyéni fejhöfok"); PROGMEM Language_Str MSG_UBL_MESH_EDIT = _UxGT("Háló szerkesztés"); PROGMEM Language_Str MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Egyéni háló szerkesztés"); PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("Finomított háló"); @@ -239,7 +246,7 @@ namespace Language_hu { PROGMEM Language_Str MSG_LED_CHANNEL_N = _UxGT("Csatorna ="); PROGMEM Language_Str MSG_LEDS2 = _UxGT("LED-ek #2"); PROGMEM Language_Str MSG_NEO2_PRESETS = _UxGT("Fény #2 megadott"); - PROGMEM Language_Str MSG_NEO2_BRIGHTNESS = _UxGT("Fényerő"); + PROGMEM Language_Str MSG_NEO2_BRIGHTNESS = _UxGT("Fényerö"); PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Egyéni szín"); PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Piros intenzitás"); PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("Zöld intenzitás"); @@ -259,6 +266,7 @@ namespace Language_hu { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Mozgás 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mozgás 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Mozgás 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Mozgás 100mm"); PROGMEM Language_Str MSG_MOVE_0001IN = _UxGT("Mozgás 0.001mm"); PROGMEM Language_Str MSG_MOVE_001IN = _UxGT("Mozgás 0.01mm"); PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Mozgás 0.1mm"); @@ -272,6 +280,7 @@ namespace Language_hu { PROGMEM Language_Str MSG_CHAMBER = _UxGT("Burkolat"); PROGMEM Language_Str MSG_COOLER = _UxGT("Lézer hütövíz"); PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Hütö kapcsoló"); + PROGMEM Language_Str MSG_FLOWMETER_SAFETY = _UxGT("Áramlásbiztonság"); PROGMEM Language_Str MSG_LASER = _UxGT("Lézer"); PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Hütés sebesség"); PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Hütés sebesség ="); @@ -298,6 +307,16 @@ namespace Language_hu { PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Hangolási hiba. Rossz adagoló."); PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("Hangolási hiba. Magas hömérséklet."); PROGMEM Language_Str MSG_PID_TIMEOUT = _UxGT("Hangolási hiba! Idötúllépés."); + PROGMEM Language_Str MSG_PID_P = _UxGT("PID-P"); + PROGMEM Language_Str MSG_PID_P_E = _UxGT("PID-P *"); + PROGMEM Language_Str MSG_PID_I = _UxGT("PID-I"); + PROGMEM Language_Str MSG_PID_I_E = _UxGT("PID-I *"); + PROGMEM Language_Str MSG_PID_D = _UxGT("PID-D"); + PROGMEM Language_Str MSG_PID_D_E = _UxGT("PID-D *"); + PROGMEM Language_Str MSG_PID_C = _UxGT("PID-C"); + PROGMEM Language_Str MSG_PID_C_E = _UxGT("PID-C *"); + PROGMEM Language_Str MSG_PID_F = _UxGT("PID-F"); + PROGMEM Language_Str MSG_PID_F_E = _UxGT("PID-F *"); PROGMEM Language_Str MSG_SELECT = _UxGT("Kiválaszt"); PROGMEM Language_Str MSG_SELECT_E = _UxGT("Kiválaszt *"); PROGMEM Language_Str MSG_ACC = _UxGT("Gyorsítás"); @@ -505,6 +524,7 @@ namespace Language_hu { PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("Lineáris szintezés"); PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Bilineáris szintezés"); PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Egységes ágy szintezés"); + PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Mesh probing done"); PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Háló szintezés"); PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Statisztikák"); PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Alaplap infó"); @@ -566,17 +586,17 @@ namespace Language_hu { PROGMEM Language_Str MSG_MMU2_LOAD_FILAMENT = _UxGT("Szál betöltése"); PROGMEM Language_Str MSG_MMU2_LOAD_ALL = _UxGT("Összes betöltése"); PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("Fej betöltése"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("Szál kiadása"); - PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Szál kiadása ~"); + PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("Szál kidobás"); + PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("Szál kidobás ~"); PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("Kiadja a szálat"); PROGMEM Language_Str MSG_MMU2_LOADING_FILAMENT = _UxGT("Szál betölt. %i..."); - PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Szál kiadás...."); + PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Szál kidobás. ..."); PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Szál kiadása...."); PROGMEM Language_Str MSG_MMU2_ALL = _UxGT("Mind"); PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("Nyomtatószál ~"); PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("MMU újraindítás"); PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("MMU újraindul..."); - PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Eltávolít, kattint"); + PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Kidob, kattint"); PROGMEM Language_Str MSG_MIX = _UxGT("Kever"); PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Összetevö ="); @@ -632,7 +652,7 @@ namespace Language_hu { PROGMEM Language_Str MSG_FILAMENT_CHANGE_LOAD = _UxGT(MSG_2_LINE("Várj a", "szál betöltésére")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_PURGE = _UxGT(MSG_2_LINE("Várj a", "szál tisztításra")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_2_LINE("Kattints a készre", "szál tiszta")); - PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Várj a nyomtatóra", "majd foltyat...")); + PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_2_LINE("Várj a nyomtatóra", "majd folytat...")); #else PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_1_LINE("Katt a folytatáshoz")); PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Parkolás...")); @@ -683,6 +703,8 @@ namespace Language_hu { PROGMEM Language_Str MSG_BOTTOM_RIGHT = _UxGT("Jobb alsó"); PROGMEM Language_Str MSG_CALIBRATION_COMPLETED = _UxGT("Kalibrálás befejezve"); PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Kalibrálási hiba"); + + PROGMEM Language_Str MSG_DRIVER_BACKWARD = _UxGT(" meghajtók hátra"); } #if FAN_COUNT == 1 diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index d359354932a5d..85b9d3f399f52 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -67,9 +67,12 @@ namespace Language_it { PROGMEM Language_Str MSG_DEBUG_MENU = _UxGT("Menu di debug"); PROGMEM Language_Str MSG_PROGRESS_BAR_TEST = _UxGT("Test barra avanzam."); PROGMEM Language_Str MSG_AUTO_HOME = _UxGT("Auto Home"); - PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Home asse X"); - PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Home asse Y"); - PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Home asse Z"); + PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Home X"); + PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Home Y"); + PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Home Z"); + PROGMEM Language_Str MSG_AUTO_HOME_I = _UxGT("Home ") LCD_STR_I; + PROGMEM Language_Str MSG_AUTO_HOME_J = _UxGT("Home ") LCD_STR_J; + PROGMEM Language_Str MSG_AUTO_HOME_K = _UxGT("Home ") LCD_STR_K; PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Allineam.automat. Z"); PROGMEM Language_Str MSG_ITERATION = _UxGT("Iterazione G34: %i"); PROGMEM Language_Str MSG_DECREASING_ACCURACY = _UxGT("Precisione in calo!"); @@ -80,6 +83,12 @@ namespace Language_it { PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Livel. terminato!"); PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Fade Height"); PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Imp. offset home"); + PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("Offset home X"); + PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Offset home Y"); + PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Offset home Z"); + PROGMEM Language_Str MSG_HOME_OFFSET_I = _UxGT("Offset home ") LCD_STR_I; + PROGMEM Language_Str MSG_HOME_OFFSET_J = _UxGT("Offset home ") LCD_STR_J; + PROGMEM Language_Str MSG_HOME_OFFSET_K = _UxGT("Offset home ") LCD_STR_K; PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Offset applicato"); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Imposta Origine"); PROGMEM Language_Str MSG_ASSISTED_TRAMMING = _UxGT("Tramming assistito"); @@ -112,10 +121,13 @@ namespace Language_it { PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Potenza laser"); PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Potenza mandrino"); PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Alterna Laser"); + PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Alterna soffiatore"); + PROGMEM Language_Str MSG_LASER_ASSIST_TOGGLE = _UxGT("Alterna aria supp."); PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("ms impulso di test"); PROGMEM Language_Str MSG_LASER_FIRE_PULSE = _UxGT("Spara impulso"); PROGMEM Language_Str MSG_FLOWMETER_FAULT = _UxGT("Err.flusso refrig."); PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Alterna mandrino"); + PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Alterna vuoto"); PROGMEM Language_Str MSG_SPINDLE_FORWARD = _UxGT("Mandrino in avanti"); PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Inverti mandrino"); PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Accendi aliment."); @@ -158,6 +170,7 @@ namespace Language_it { PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Livel.letto unificato"); PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Punto inclinaz."); PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Mesh Manuale"); + PROGMEM Language_Str MSG_UBL_MESH_WIZARD = _UxGT("Creaz.guid.mesh UBL"); PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Metti spes. e misura"); PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Misura"); PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Rimuovi e mis.piatto"); @@ -258,6 +271,9 @@ namespace Language_it { PROGMEM Language_Str MSG_MOVE_X = _UxGT("Muovi X"); PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Muovi Y"); PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Muovi Z"); + PROGMEM Language_Str MSG_MOVE_I = _UxGT("Muovi ") LCD_STR_I; + PROGMEM Language_Str MSG_MOVE_J = _UxGT("Muovi ") LCD_STR_J; + PROGMEM Language_Str MSG_MOVE_K = _UxGT("Muovi ") LCD_STR_K; PROGMEM Language_Str MSG_MOVE_E = _UxGT("Estrusore"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Estrusore *"); PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Ugello freddo"); @@ -265,9 +281,11 @@ namespace Language_it { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Muovi di 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Muovi di 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Muovi di 10mm"); - PROGMEM Language_Str MSG_MOVE_0001IN = _UxGT("Muovi di 0.001in"); - PROGMEM Language_Str MSG_MOVE_001IN = _UxGT("Muovi di 0.01in"); - PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Muovi di 0.1in"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Muovi di 100mm"); + PROGMEM Language_Str MSG_MOVE_0001IN = _UxGT("Muovi di 0.001\""); + PROGMEM Language_Str MSG_MOVE_001IN = _UxGT("Muovi di 0.01\""); + PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Muovi di 0.1\""); + PROGMEM Language_Str MSG_MOVE_1IN = _UxGT("Muovi di 1\""); PROGMEM Language_Str MSG_SPEED = _UxGT("Velocità"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Piatto Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Ugello"); @@ -312,12 +330,18 @@ namespace Language_it { PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-jerk"); PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-jerk"); PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-jerk"); + PROGMEM Language_Str MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-jerk"); + PROGMEM Language_Str MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-jerk"); + PROGMEM Language_Str MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-jerk"); PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-jerk"); PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Deviaz. giunzioni"); PROGMEM Language_Str MSG_VELOCITY = _UxGT("Velocità"); PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A; PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; + PROGMEM Language_Str MSG_VMAX_I = _UxGT("Vmax ") LCD_STR_I; + PROGMEM Language_Str MSG_VMAX_J = _UxGT("Vmax ") LCD_STR_J; + PROGMEM Language_Str MSG_VMAX_K = _UxGT("Vmax ") LCD_STR_K; PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vmax *"); PROGMEM Language_Str MSG_VMIN = _UxGT("Vmin"); @@ -326,6 +350,9 @@ namespace Language_it { PROGMEM Language_Str MSG_AMAX_A = _UxGT("Amax ") LCD_STR_A; PROGMEM Language_Str MSG_AMAX_B = _UxGT("Amax ") LCD_STR_B; PROGMEM Language_Str MSG_AMAX_C = _UxGT("Amax ") LCD_STR_C; + PROGMEM Language_Str MSG_AMAX_I = _UxGT("Amax ") LCD_STR_I; + PROGMEM Language_Str MSG_AMAX_J = _UxGT("Amax ") LCD_STR_J; + PROGMEM Language_Str MSG_AMAX_K = _UxGT("Amax ") LCD_STR_K; PROGMEM Language_Str MSG_AMAX_E = _UxGT("Amax ") LCD_STR_E; PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Amax *"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-Ritrazione"); @@ -333,11 +360,14 @@ namespace Language_it { PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("Frequenza max"); PROGMEM Language_Str MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Feed min"); PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("Passi/mm"); - PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT("passi/mm"); - PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT("passi/mm"); - PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT("passi/mm"); - PROGMEM Language_Str MSG_E_STEPS = _UxGT("Epassi/mm"); - PROGMEM Language_Str MSG_EN_STEPS = _UxGT("*passi/mm"); + PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" passi/mm"); + PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" passi/mm"); + PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" passi/mm"); + PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" passi/mm"); + PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" passi/mm"); + PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" passi/mm"); + PROGMEM Language_Str MSG_E_STEPS = _UxGT("E passi/mm"); + PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* passi/mm"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatura"); PROGMEM Language_Str MSG_MOTION = _UxGT("Movimento"); PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filamento"); @@ -469,6 +499,9 @@ namespace Language_it { PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Babystep X"); PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Babystep Y"); PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Babystep Z"); + PROGMEM Language_Str MSG_BABYSTEP_I = _UxGT("Babystep ") LCD_STR_I; + PROGMEM Language_Str MSG_BABYSTEP_J = _UxGT("Babystep ") LCD_STR_J; + PROGMEM Language_Str MSG_BABYSTEP_K = _UxGT("Babystep ") LCD_STR_K; PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Totali"); PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Finecorsa annullati"); PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Risc.Fallito"); // Max 12 caratteri @@ -545,10 +578,13 @@ namespace Language_it { PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Temp max"); PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Alimentatore"); PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Potenza Drive"); - PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z Driver %"); - PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Driver %"); + PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("Driver X %"); + PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Driver Y %"); + PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Driver Z %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = _UxGT("Driver ") AXIS4_STR _UxGT(" %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = _UxGT("Driver ") AXIS5_STR _UxGT(" %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = _UxGT("Driver ") AXIS6_STR _UxGT(" %"); + PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("Driver E %"); PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("ERR.CONNESSIONE TMC"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Scrivi DAC EEPROM"); PROGMEM Language_Str MSG_FILAMENT_CHANGE_HEADER = _UxGT("CAMBIO FILAMENTO"); @@ -681,10 +717,15 @@ namespace Language_it { PROGMEM Language_Str MSG_SOUND = _UxGT("Suoni"); - PROGMEM Language_Str MSG_TOP_LEFT = _UxGT("Alto sinistra"); + PROGMEM Language_Str MSG_TOP_LEFT = _UxGT("Alto sinistra"); PROGMEM Language_Str MSG_BOTTOM_LEFT = _UxGT("Basso sinistra"); PROGMEM Language_Str MSG_TOP_RIGHT = _UxGT("Alto destra"); PROGMEM Language_Str MSG_BOTTOM_RIGHT = _UxGT("Basso destra"); PROGMEM Language_Str MSG_CALIBRATION_COMPLETED = _UxGT("Calibrazione completata"); PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Calibrazione fallita"); + + PROGMEM Language_Str MSG_DRIVER_BACKWARD = _UxGT(" driver invertito"); + + PROGMEM Language_Str MSG_SD_CARD = _UxGT("Scheda SD"); + PROGMEM Language_Str MSG_USB_DISK = _UxGT("Disco USB"); } diff --git a/Marlin/src/lcd/language/language_jp_kana.h b/Marlin/src/lcd/language/language_jp_kana.h index e0028e22a2c89..61740e3b40eb0 100644 --- a/Marlin/src/lcd/language/language_jp_kana.h +++ b/Marlin/src/lcd/language/language_jp_kana.h @@ -98,6 +98,7 @@ namespace Language_jp_kana { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("0.1mm イドウ"); // "Move 0.1mm" PROGMEM Language_Str MSG_MOVE_1MM = _UxGT(" 1mm イドウ"); // "Move 1mm" PROGMEM Language_Str MSG_MOVE_10MM = _UxGT(" 10mm イドウ"); // "Move 10mm" + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT(" 100mm イドウ"); // "Move 100mm" PROGMEM Language_Str MSG_SPEED = _UxGT("ソクド"); // "Speed" PROGMEM Language_Str MSG_BED_Z = _UxGT("Zオフセット"); // "Bed Z" PROGMEM Language_Str MSG_NOZZLE = _UxGT("ノズル"); // "Nozzle" diff --git a/Marlin/src/lcd/language/language_nl.h b/Marlin/src/lcd/language/language_nl.h index 82e5c292c68b4..1eef4ca424726 100644 --- a/Marlin/src/lcd/language/language_nl.h +++ b/Marlin/src/lcd/language/language_nl.h @@ -91,6 +91,7 @@ namespace Language_nl { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Verplaats 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Verplaats 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Verplaats 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Verplaats 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Snelheid"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Bed Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Nozzle"); diff --git a/Marlin/src/lcd/language/language_pl.h b/Marlin/src/lcd/language/language_pl.h index 9004722cfcdff..fee627b2fee00 100644 --- a/Marlin/src/lcd/language/language_pl.h +++ b/Marlin/src/lcd/language/language_pl.h @@ -26,6 +26,13 @@ * * LCD Menu Messages * See also https://marlinfw.org/docs/development/lcd_language.html + * + * Substitutions are applied for the following characters when used + * in menu items that call lcd_put_u8str_ind_P with an index: + * + * = displays '0'....'10' for indexes 0 - 10 + * ~ displays '1'....'11' for indexes 0 - 10 + * * displays 'E1'...'E11' for indexes 0 - 10 (By default. Uses LCD_FIRST_TOOL) */ #define DISPLAY_CHARSET_ISO10646_PL @@ -34,9 +41,10 @@ namespace Language_pl { using namespace Language_en; // Inherit undefined strings from English constexpr uint8_t CHARSIZE = 2; - PROGMEM Language_Str LANGUAGE = _UxGT("Polish"); + PROGMEM Language_Str LANGUAGE = _UxGT("Polski"); PROGMEM Language_Str WELCOME_MSG = MACHINE_NAME _UxGT(" gotowy."); + //PROGMEM Language_Str MSG_MARLIN = _UxGT("Marlin"); PROGMEM Language_Str MSG_YES = _UxGT("TAK"); PROGMEM Language_Str MSG_NO = _UxGT("NIE"); PROGMEM Language_Str MSG_BACK = _UxGT("Wstecz"); @@ -44,9 +52,11 @@ namespace Language_pl { PROGMEM Language_Str MSG_MEDIA_INSERTED = _UxGT("Karta włożona"); PROGMEM Language_Str MSG_MEDIA_REMOVED = _UxGT("Karta usunięta"); PROGMEM Language_Str MSG_MEDIA_WAITING = _UxGT("Oczekiwanie na kartę"); + PROGMEM Language_Str MSG_SD_INIT_FAIL = _UxGT("Błąd inicializacji karty"); PROGMEM Language_Str MSG_MEDIA_READ_ERROR = _UxGT("Bład odczytu karty"); PROGMEM Language_Str MSG_MEDIA_USB_REMOVED = _UxGT("Urządzenie USB usunięte"); PROGMEM Language_Str MSG_MEDIA_USB_FAILED = _UxGT("Błąd uruchomienia USB"); + //PROGMEM Language_Str MSG_KILL_SUBCALL_OVERFLOW = _UxGT("Subcall Overflow"); PROGMEM Language_Str MSG_LCD_ENDSTOPS = _UxGT("Krańców."); // Max length 8 characters PROGMEM Language_Str MSG_LCD_SOFT_ENDSTOPS = _UxGT("Progr. Krańcówki"); PROGMEM Language_Str MSG_MAIN = _UxGT("Menu główne"); @@ -61,14 +71,24 @@ namespace Language_pl { PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Zeruj Y"); PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Zeruj Z"); PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Autowyrównanie Z"); + //PROGMEM Language_Str MSG_ITERATION = _UxGT("G34 Iteration: %i"); + PROGMEM Language_Str MSG_DECREASING_ACCURACY = _UxGT("Spadek dokładności!"); + PROGMEM Language_Str MSG_ACCURACY_ACHIEVED = _UxGT("Osiągnięto dokładność"); PROGMEM Language_Str MSG_LEVEL_BED_HOMING = _UxGT("Pozycja zerowa"); PROGMEM Language_Str MSG_LEVEL_BED_WAITING = _UxGT("Kliknij by rozp."); PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Następny punkt"); PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Wypoziomowano!"); PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Wys. zanikania"); PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Ust. poz. zer."); + //PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("Home Offset X"); + //PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Home Offset Y"); + //PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Home Offset Z"); PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Poz. zerowa ust."); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Ustaw punkt zero"); + //PROGMEM Language_Str MSG_ASSISTED_TRAMMING = _UxGT("Assisted Tramming"); + //PROGMEM Language_Str MSG_TRAMMING_WIZARD = _UxGT("Tramming Wizard"); + PROGMEM Language_Str MSG_SELECT_ORIGIN = _UxGT("Wybierz punkt zero"); + PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Poprzednia wartość "); #if PREHEAT_COUNT PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Rozgrzej ") PREHEAT_1_LABEL; PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Rozgrzej ") PREHEAT_1_LABEL " ~"; @@ -88,10 +108,21 @@ namespace Language_pl { #endif PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Rozgrzej własne ust."); PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Chłodzenie"); + + PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Częstotliwość"); PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Sterowanie Lasera"); - PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Zasilanie Lasera"); PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Sterowanie wrzeciona"); + PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Zasilanie Lasera"); PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Zasilanie wrzeciona"); + //PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Toggle Laser"); + //PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Toggle Blower"); + //PROGMEM Language_Str MSG_LASER_ASSIST_TOGGLE = _UxGT("Air Assist"); + //PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Test Pulse ms"); + //PROGMEM Language_Str MSG_LASER_FIRE_PULSE = _UxGT("Fire Pulse"); + //PROGMEM Language_Str MSG_FLOWMETER_FAULT = _UxGT("Coolant Flow Fault"); + //PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Toggle Spindle"); + //PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Toggle Vacuum"); + //PROGMEM Language_Str MSG_SPINDLE_FORWARD = _UxGT("Spindle Forward"); PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Rewers wrzeciona"); PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Włącz zasilacz"); PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Wyłącz zasilacz"); @@ -101,6 +132,10 @@ namespace Language_pl { PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Poziomowanie stołu"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Wypoziomuj stół"); PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Narożniki poziomowania"); + //PROGMEM Language_Str MSG_LEVEL_CORNERS_RAISE = _UxGT("Raise Bed Until Probe Triggered"); + //PROGMEM Language_Str MSG_LEVEL_CORNERS_IN_RANGE = _UxGT("All Corners Within Tolerance. Level Bed"); + //PROGMEM Language_Str MSG_LEVEL_CORNERS_GOOD_POINTS = _UxGT("Good Points: "); + //PROGMEM Language_Str MSG_LEVEL_CORNERS_LAST_Z = _UxGT("Last Z: "); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Nastepny narożnik"); PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Edytor siatki"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Edycja siatki"); @@ -112,6 +147,7 @@ namespace Language_pl { PROGMEM Language_Str MSG_CUSTOM_COMMANDS = _UxGT("Własne Polecenia"); PROGMEM Language_Str MSG_M48_TEST = _UxGT("M48 Test sondy"); PROGMEM Language_Str MSG_M48_POINT = _UxGT("M48 Punky"); + //PROGMEM Language_Str MSG_M48_OUT_OF_BOUNDS = _UxGT("Probe out of bounds"); PROGMEM Language_Str MSG_M48_DEVIATION = _UxGT("Odchylenie"); PROGMEM Language_Str MSG_IDEX_MENU = _UxGT("Tryb IDEX"); PROGMEM Language_Str MSG_OFFSETS_MENU = _UxGT("Przesunięcie narzędzia"); @@ -119,14 +155,16 @@ namespace Language_pl { PROGMEM Language_Str MSG_IDEX_MODE_DUPLICATE = _UxGT("Duplikowanie"); PROGMEM Language_Str MSG_IDEX_MODE_MIRRORED_COPY = _UxGT("Kopia lustrzana"); PROGMEM Language_Str MSG_IDEX_MODE_FULL_CTRL = _UxGT("Pełne sterowanie"); + //PROGMEM Language_Str MSG_IDEX_DUPE_GAP = _UxGT("Duplicate X-Gap"); PROGMEM Language_Str MSG_HOTEND_OFFSET_X = _UxGT("2ga dysza X"); PROGMEM Language_Str MSG_HOTEND_OFFSET_Y = _UxGT("2ga dysza Y"); PROGMEM Language_Str MSG_HOTEND_OFFSET_Z = _UxGT("2ga dysza Z"); PROGMEM Language_Str MSG_UBL_DOING_G29 = _UxGT("Wykonywanie G29"); PROGMEM Language_Str MSG_UBL_TOOLS = _UxGT("Narzędzia UBL"); - PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Unified Bed Leveling"); + //PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("Unified Bed Leveling"); PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Punkt pochylenia"); PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Ręczne Budowanie Siatki"); + //PROGMEM Language_Str MSG_UBL_MESH_WIZARD = _UxGT("UBL Mesh Wizard"); PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Umieść podkładkę i zmierz"); PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Zmierz"); PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Usuń & Zmierz Stół"); @@ -143,14 +181,12 @@ namespace Language_pl { PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Koniec edycji siati"); PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Buduj własna siatkę"); PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("Buduj siatkę"); - #if PREHEAT_COUNT - PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Buduj siatkę ($)"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Sprawdzenie siatki ($)"); - #endif + PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Buduj siatkę ($)"); PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("Buduj siatkę na zimno"); PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Dostrojenie wysokości siatki"); PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Wartość wysokości"); PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Sprawdzenie siatki"); + PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Sprawdzenie siatki ($)"); PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Sprawdzenie własnej siatki"); PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26 Nagrzewanie stołu"); PROGMEM Language_Str MSG_G26_HEATING_NOZZLE = _UxGT("G26 Nagrzewanie dyszy"); @@ -211,6 +247,10 @@ namespace Language_pl { PROGMEM Language_Str MSG_SET_LEDS_VIOLET = _UxGT("Fioletowy"); PROGMEM Language_Str MSG_SET_LEDS_WHITE = _UxGT("Biały"); PROGMEM Language_Str MSG_SET_LEDS_DEFAULT = _UxGT("Domyślny"); + PROGMEM Language_Str MSG_LED_CHANNEL_N = _UxGT("Kanał ="); + //PROGMEM Language_Str MSG_LEDS2 = _UxGT("Lights #2"); + //PROGMEM Language_Str MSG_NEO2_PRESETS = _UxGT("Light #2 Presets"); + PROGMEM Language_Str MSG_NEO2_BRIGHTNESS = _UxGT("Jasność"); PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Własne światła"); PROGMEM Language_Str MSG_INTENSITY_R = _UxGT("Czerwony"); PROGMEM Language_Str MSG_INTENSITY_G = _UxGT("Zielony"); @@ -226,31 +266,61 @@ namespace Language_pl { PROGMEM Language_Str MSG_MOVE_E = _UxGT("Ekstruzja (os E)"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Ekstruzja (os E) *"); PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Dysza za zimna"); - PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Przesuń co %smm"); - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Przesuń co .1mm"); - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Przesuń co 1mm"); - PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Przesuń co 10mm"); + PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("Przesuń co %s mm"); + PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Przesuń co .1 mm"); + PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Przesuń co 1 mm"); + PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Przesuń co 10 mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Przesuń co 100 mm"); + PROGMEM Language_Str MSG_MOVE_0001IN = _UxGT("Przesuń co 0.001 cala"); + PROGMEM Language_Str MSG_MOVE_001IN = _UxGT("Przesuń co 0.01 cala"); + PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Przesuń co 0.1 cala"); PROGMEM Language_Str MSG_SPEED = _UxGT("Predkość"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Stół Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Dysza"); PROGMEM Language_Str MSG_NOZZLE_N = _UxGT("Dysza ~"); + //PROGMEM Language_Str MSG_NOZZLE_PARKED = _UxGT("Nozzle Parked"); + PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Dysza w oczekiwaniu"); PROGMEM Language_Str MSG_BED = _UxGT("Stół"); PROGMEM Language_Str MSG_CHAMBER = _UxGT("Obudowa"); - PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Obroty wiatraka"); - PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Obroty wiatraka ~"); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Obroty dodatkowego wiatraka"); - PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Obroty dodatkowego wiatraka ~"); + //PROGMEM Language_Str MSG_COOLER = _UxGT("Laser Coolant"); + //PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Toggle Cooler"); + //PROGMEM Language_Str MSG_FLOWMETER_SAFETY = _UxGT("Flow Safety"); + //PROGMEM Language_Str MSG_LASER = _UxGT("Laser"); + PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Obroty wentylatora"); + PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Obroty wentylatora ~"); + //PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Stored Fan ~"); + PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Obroty dodatkowego wentylatora"); + PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Obroty dodatkowego wentylatora ~"); + PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Wentylator kontrolera"); + //PROGMEM Language_Str MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Idle Speed"); + //PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Auto Mode"); + //PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("Active Speed"); + //PROGMEM Language_Str MSG_CONTROLLER_FAN_DURATION = _UxGT("Idle Period"); PROGMEM Language_Str MSG_FLOW = _UxGT("Przepływ"); PROGMEM Language_Str MSG_FLOW_N = _UxGT("Przepływ ~"); PROGMEM Language_Str MSG_CONTROL = _UxGT("Ustawienia"); - PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); - PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); + //PROGMEM Language_Str MSG_MIN = " " LCD_STR_THERMOMETER _UxGT(" Min"); + //PROGMEM Language_Str MSG_MAX = " " LCD_STR_THERMOMETER _UxGT(" Max"); PROGMEM Language_Str MSG_FACTOR = " " LCD_STR_THERMOMETER _UxGT(" Mnożnik"); PROGMEM Language_Str MSG_AUTOTEMP = _UxGT("Auto. temperatura"); PROGMEM Language_Str MSG_LCD_ON = _UxGT("Wł."); PROGMEM Language_Str MSG_LCD_OFF = _UxGT("Wył."); PROGMEM Language_Str MSG_PID_AUTOTUNE = _UxGT("PID Autostrojenie"); PROGMEM Language_Str MSG_PID_AUTOTUNE_E = _UxGT("PID Autostrojenie *"); + PROGMEM Language_Str MSG_PID_AUTOTUNE_DONE = _UxGT("Strojenie PID zakończone"); + //PROGMEM Language_Str MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Autotune failed. Bad extruder."); + //PROGMEM Language_Str MSG_PID_TEMP_TOO_HIGH = _UxGT("Autotune failed. Temperature too high."); + //PROGMEM Language_Str MSG_PID_TIMEOUT = _UxGT("Autotune failed! Timeout."); + //PROGMEM Language_Str MSG_PID_P = _UxGT("PID-P"); + //PROGMEM Language_Str MSG_PID_P_E = _UxGT("PID-P *"); + //PROGMEM Language_Str MSG_PID_I = _UxGT("PID-I"); + //PROGMEM Language_Str MSG_PID_I_E = _UxGT("PID-I *"); + //PROGMEM Language_Str MSG_PID_D = _UxGT("PID-D"); + //PROGMEM Language_Str MSG_PID_D_E = _UxGT("PID-D *"); + //PROGMEM Language_Str MSG_PID_C = _UxGT("PID-C"); + //PROGMEM Language_Str MSG_PID_C_E = _UxGT("PID-C *"); + //PROGMEM Language_Str MSG_PID_F = _UxGT("PID-F"); + //PROGMEM Language_Str MSG_PID_F_E = _UxGT("PID-F *"); PROGMEM Language_Str MSG_SELECT = _UxGT("Wybierz"); PROGMEM Language_Str MSG_SELECT_E = _UxGT("Wybierz *"); PROGMEM Language_Str MSG_ACC = _UxGT("Przyspieszenie"); @@ -259,61 +329,83 @@ namespace Language_pl { PROGMEM Language_Str MSG_VB_JERK = _UxGT("Zryw V") LCD_STR_B; PROGMEM Language_Str MSG_VC_JERK = _UxGT("Zryw V") LCD_STR_C; PROGMEM Language_Str MSG_VE_JERK = _UxGT("Zryw Ve"); - PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev"); + //PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev"); PROGMEM Language_Str MSG_VELOCITY = _UxGT("Prędkość (V)"); - PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A; - PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; - PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; - PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; - PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vmax *"); - PROGMEM Language_Str MSG_VMIN = _UxGT("Vmin"); + //PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A; + //PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B; + //PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C; + //PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E; + //PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vmax *"); + //PROGMEM Language_Str MSG_VMIN = _UxGT("Vmin"); PROGMEM Language_Str MSG_VTRAV_MIN = _UxGT("Vskok min"); PROGMEM Language_Str MSG_ACCELERATION = _UxGT("Przyspieszenie (A)"); - PROGMEM Language_Str MSG_AMAX_A = _UxGT("Amax ") LCD_STR_A; - PROGMEM Language_Str MSG_AMAX_B = _UxGT("Amax ") LCD_STR_B; - PROGMEM Language_Str MSG_AMAX_C = _UxGT("Amax ") LCD_STR_C; - PROGMEM Language_Str MSG_AMAX_E = _UxGT("Amax ") LCD_STR_E; - PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Amax *"); + //PROGMEM Language_Str MSG_AMAX_A = _UxGT("Amax ") LCD_STR_A; + //PROGMEM Language_Str MSG_AMAX_B = _UxGT("Amax ") LCD_STR_B; + //PROGMEM Language_Str MSG_AMAX_C = _UxGT("Amax ") LCD_STR_C; + //PROGMEM Language_Str MSG_AMAX_E = _UxGT("Amax ") LCD_STR_E; + //PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Amax *"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-wycofanie"); PROGMEM Language_Str MSG_A_TRAVEL = _UxGT("A-przesuń."); + PROGMEM Language_Str MSG_XY_FREQUENCY_LIMIT = _UxGT("Częstotliwość max"); + //PROGMEM Language_Str MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Feed min"); PROGMEM Language_Str MSG_STEPS_PER_MM = _UxGT("kroki/mm"); - PROGMEM Language_Str MSG_A_STEPS = _UxGT("kroki") LCD_STR_A _UxGT("/mm"); - PROGMEM Language_Str MSG_B_STEPS = _UxGT("kroki") LCD_STR_B _UxGT("/mm"); - PROGMEM Language_Str MSG_C_STEPS = _UxGT("kroki") LCD_STR_C _UxGT("/mm"); - PROGMEM Language_Str MSG_E_STEPS = _UxGT("krokiE/mm"); - PROGMEM Language_Str MSG_EN_STEPS = _UxGT("kroki */mm"); + PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" kroki/mm"); + PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" kroki/mm"); + PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" kroki/mm"); + PROGMEM Language_Str MSG_E_STEPS = _UxGT("E kroki/mm"); + PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* kroki/mm"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperatura"); PROGMEM Language_Str MSG_MOTION = _UxGT("Ruch"); - PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filament"); + //PROGMEM Language_Str MSG_FILAMENT = _UxGT("Filament"); PROGMEM Language_Str MSG_VOLUMETRIC_ENABLED = _UxGT("E w mm") SUPERSCRIPT_THREE; + //PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT = _UxGT("E Limit in mm") SUPERSCRIPT_THREE; + //PROGMEM Language_Str MSG_VOLUMETRIC_LIMIT_E = _UxGT("E Limit *"); PROGMEM Language_Str MSG_FILAMENT_DIAM = _UxGT("Śr. fil."); PROGMEM Language_Str MSG_FILAMENT_DIAM_E = _UxGT("Śr. fil. *"); PROGMEM Language_Str MSG_FILAMENT_UNLOAD = _UxGT("Wysuń mm"); PROGMEM Language_Str MSG_FILAMENT_LOAD = _UxGT("Wsuń mm"); - PROGMEM Language_Str MSG_ADVANCE_K = _UxGT("Advance K"); - PROGMEM Language_Str MSG_ADVANCE_K_E = _UxGT("Advance K *"); + //PROGMEM Language_Str MSG_ADVANCE_K = _UxGT("Advance K"); + //PROGMEM Language_Str MSG_ADVANCE_K_E = _UxGT("Advance K *"); PROGMEM Language_Str MSG_CONTRAST = _UxGT("Kontrast LCD"); PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Zapisz w pamięci"); PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Wczytaj z pamięci"); PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("Ustaw. fabryczne"); PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Initializuj EEPROM"); + //PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("EEPROM CRC Error"); + //PROGMEM Language_Str MSG_ERR_EEPROM_INDEX = _UxGT("EEPROM Index Error"); + //PROGMEM Language_Str MSG_ERR_EEPROM_VERSION = _UxGT("EEPROM Version Error"); + //PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Settings Stored"); PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Uaktualnij kartę"); PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Resetuj drukarkę"); PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT("Odswież"); PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Ekran główny"); PROGMEM Language_Str MSG_PREPARE = _UxGT("Przygotuj"); PROGMEM Language_Str MSG_TUNE = _UxGT("Strojenie"); + //PROGMEM Language_Str MSG_POWER_MONITOR = _UxGT("Power monitor"); + PROGMEM Language_Str MSG_CURRENT = _UxGT("Natężenie"); + PROGMEM Language_Str MSG_VOLTAGE = _UxGT("Napięcie"); + PROGMEM Language_Str MSG_POWER = _UxGT("Moc"); PROGMEM Language_Str MSG_START_PRINT = _UxGT("Start wydruku"); PROGMEM Language_Str MSG_BUTTON_NEXT = _UxGT("Następny"); PROGMEM Language_Str MSG_BUTTON_INIT = _UxGT("Inic."); - PROGMEM Language_Str MSG_BUTTON_STOP = _UxGT("Stop"); + //PROGMEM Language_Str MSG_BUTTON_STOP = _UxGT("Stop"); PROGMEM Language_Str MSG_BUTTON_PRINT = _UxGT("Drukuj"); PROGMEM Language_Str MSG_BUTTON_RESET = _UxGT("Resetuj"); + PROGMEM Language_Str MSG_BUTTON_IGNORE = _UxGT("Ignoruj"); PROGMEM Language_Str MSG_BUTTON_CANCEL = _UxGT("Przerwij"); PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Gotowe"); + PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Wstecz"); + PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Kontynuuj"); + PROGMEM Language_Str MSG_BUTTON_SKIP = _UxGT("Pomiń"); + PROGMEM Language_Str MSG_PAUSING = _UxGT("Wstrzymywanie..."); PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Wstrzymaj druk"); PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Wznowienie"); + //PROGMEM Language_Str MSG_HOST_START_PRINT = _UxGT("Host Start"); PROGMEM Language_Str MSG_STOP_PRINT = _UxGT("Stop"); + //PROGMEM Language_Str MSG_END_LOOPS = _UxGT("End Repeat Loops"); + PROGMEM Language_Str MSG_PRINTING_OBJECT = _UxGT("Drukowanie obiektu"); + PROGMEM Language_Str MSG_CANCEL_OBJECT = _UxGT("Anunuj obiekt"); + PROGMEM Language_Str MSG_CANCEL_OBJECT_N = _UxGT("Anunuj obiekt ="); PROGMEM Language_Str MSG_OUTAGE_RECOVERY = _UxGT("Odzyskiwanie po awarii"); PROGMEM Language_Str MSG_MEDIA_MENU = _UxGT("Karta SD"); PROGMEM Language_Str MSG_NO_MEDIA = _UxGT("Brak karty"); @@ -322,6 +414,7 @@ namespace Language_pl { PROGMEM Language_Str MSG_PRINT_PAUSED = _UxGT("Druk wstrzymany"); PROGMEM Language_Str MSG_PRINTING = _UxGT("Drukowanie..."); PROGMEM Language_Str MSG_PRINT_ABORTED = _UxGT("Druk przerwany"); + PROGMEM Language_Str MSG_PRINT_DONE = _UxGT("Druk zakończony"); PROGMEM Language_Str MSG_NO_MOVE = _UxGT("Brak ruchu"); PROGMEM Language_Str MSG_KILLED = _UxGT("Ubity. "); PROGMEM Language_Str MSG_STOPPED = _UxGT("Zatrzymany. "); @@ -331,15 +424,26 @@ namespace Language_pl { PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Skok Z mm"); PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("Cof. wycof. mm"); PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Z Cof. wyc. mm"); + //PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Unretract V"); PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVERF = _UxGT("Cof. wycof. V"); PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Auto. wycofanie"); PROGMEM Language_Str MSG_FILAMENT_SWAP_LENGTH = _UxGT("Długość zmiany"); + //PROGMEM Language_Str MSG_FILAMENT_SWAP_EXTRA = _UxGT("Swap Extra"); PROGMEM Language_Str MSG_FILAMENT_PURGE_LENGTH = _UxGT("Długość oczyszczania"); PROGMEM Language_Str MSG_TOOL_CHANGE = _UxGT("Zmiana narzędzia"); PROGMEM Language_Str MSG_TOOL_CHANGE_ZLIFT = _UxGT("Podniesienie Z"); PROGMEM Language_Str MSG_SINGLENOZZLE_PRIME_SPEED = _UxGT("Prędkość napełniania"); PROGMEM Language_Str MSG_SINGLENOZZLE_RETRACT_SPEED = _UxGT("Prędkość wycofania"); - PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Dysza w oczekiwaniu"); + //PROGMEM Language_Str MSG_FILAMENT_PARK_ENABLED = _UxGT("Park Head"); + //PROGMEM Language_Str MSG_SINGLENOZZLE_UNRETRACT_SPEED = _UxGT("Recover Speed"); + //PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_SPEED = _UxGT("Fan Speed"); + //PROGMEM Language_Str MSG_SINGLENOZZLE_FAN_TIME = _UxGT("Fan Time"); + //PROGMEM Language_Str MSG_TOOL_MIGRATION_ON = _UxGT("Auto ON"); + //PROGMEM Language_Str MSG_TOOL_MIGRATION_OFF = _UxGT("Auto OFF"); + //PROGMEM Language_Str MSG_TOOL_MIGRATION = _UxGT("Tool Migration"); + //PROGMEM Language_Str MSG_TOOL_MIGRATION_AUTO = _UxGT("Auto-migration"); + //PROGMEM Language_Str MSG_TOOL_MIGRATION_END = _UxGT("Last Extruder"); + //PROGMEM Language_Str MSG_TOOL_MIGRATION_SWAP = _UxGT("Migrate to *"); PROGMEM Language_Str MSG_FILAMENTCHANGE = _UxGT("Zmień filament"); PROGMEM Language_Str MSG_FILAMENTCHANGE_E = _UxGT("Zmień filament *"); PROGMEM Language_Str MSG_FILAMENTLOAD = _UxGT("Wsuń Filament"); @@ -352,31 +456,35 @@ namespace Language_pl { PROGMEM Language_Str MSG_RELEASE_MEDIA = _UxGT("Zwolnienie karty"); PROGMEM Language_Str MSG_ZPROBE_OUT = _UxGT("Sonda Z za stołem"); PROGMEM Language_Str MSG_SKEW_FACTOR = _UxGT("Współczynik skrzywienia"); - PROGMEM Language_Str MSG_BLTOUCH = _UxGT("BLTouch"); + //PROGMEM Language_Str MSG_BLTOUCH = _UxGT("BLTouch"); PROGMEM Language_Str MSG_BLTOUCH_SELFTEST = _UxGT("BLTouch Self-Test"); PROGMEM Language_Str MSG_BLTOUCH_RESET = _UxGT("Reset BLTouch"); - PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("Stow"); - PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("Deploy"); - PROGMEM Language_Str MSG_BLTOUCH_SW_MODE = _UxGT("SW-Mode"); - PROGMEM Language_Str MSG_BLTOUCH_5V_MODE = _UxGT("5V-Mode"); - PROGMEM Language_Str MSG_BLTOUCH_OD_MODE = _UxGT("OD-Mode"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE = _UxGT("Mode-Store"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Set BLTouch to 5V"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Set BLTouch to OD"); - PROGMEM Language_Str MSG_BLTOUCH_MODE_ECHO = _UxGT("Report Drain"); + //PROGMEM Language_Str MSG_BLTOUCH_STOW = _UxGT("Stow"); + //PROGMEM Language_Str MSG_BLTOUCH_DEPLOY = _UxGT("Deploy"); + //PROGMEM Language_Str MSG_BLTOUCH_SW_MODE = _UxGT("SW-Mode"); + //PROGMEM Language_Str MSG_BLTOUCH_5V_MODE = _UxGT("5V-Mode"); + //PROGMEM Language_Str MSG_BLTOUCH_OD_MODE = _UxGT("OD-Mode"); + //PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE = _UxGT("Mode-Store"); + //PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_5V = _UxGT("Set BLTouch to 5V"); + //PROGMEM Language_Str MSG_BLTOUCH_MODE_STORE_OD = _UxGT("Set BLTouch to OD"); + //PROGMEM Language_Str MSG_BLTOUCH_MODE_ECHO = _UxGT("Report Drain"); PROGMEM Language_Str MSG_BLTOUCH_MODE_CHANGE = _UxGT("UWAGA: Złe ustawienia mogą uszkodzić drukarkę. Kontynuować?"); - PROGMEM Language_Str MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); - PROGMEM Language_Str MSG_TOUCHMI_INIT = _UxGT("Init TouchMI"); - PROGMEM Language_Str MSG_TOUCHMI_ZTEST = _UxGT("Z Offset Test"); - PROGMEM Language_Str MSG_TOUCHMI_SAVE = _UxGT("Save"); - PROGMEM Language_Str MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("Deploy TouchMI"); - PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("Deploy Z-Probe"); - PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("Stow Z-Probe"); + //PROGMEM Language_Str MSG_TOUCHMI_PROBE = _UxGT("TouchMI"); + //PROGMEM Language_Str MSG_TOUCHMI_INIT = _UxGT("Init TouchMI"); + //PROGMEM Language_Str MSG_TOUCHMI_ZTEST = _UxGT("Z Offset Test"); + //PROGMEM Language_Str MSG_TOUCHMI_SAVE = _UxGT("Save"); + //PROGMEM Language_Str MSG_MANUAL_DEPLOY_TOUCHMI = _UxGT("Deploy TouchMI"); + //PROGMEM Language_Str MSG_MANUAL_DEPLOY = _UxGT("Deploy Z-Probe"); + //PROGMEM Language_Str MSG_MANUAL_STOW = _UxGT("Stow Z-Probe"); PROGMEM Language_Str MSG_HOME_FIRST = _UxGT("Najpierw Home %s%s%s"); + //PROGMEM Language_Str MSG_ZPROBE_OFFSETS = _UxGT("Probe Offsets"); + //PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("Probe X Offset"); + //PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Probe Y Offset"); PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Offset Z"); - PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Babystep X"); - PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Babystep Y"); - PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Babystep Z"); + PROGMEM Language_Str MSG_MOVE_NOZZLE_TO_BED = _UxGT("Przesuń dyszę do stołu"); + //PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Babystep X"); + //PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Babystep Y"); + //PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Babystep Z"); PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Łącznie"); PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Błąd krańcówki"); PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Rozgrz. nieudane"); @@ -384,19 +492,24 @@ namespace Language_pl { PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("ZANIK TEMPERATURY"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("ZANIK TEMP. STOŁU"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("ZANIK TEMP.KOMORY"); + //PROGMEM Language_Str MSG_THERMAL_RUNAWAY_COOLER = _UxGT("Cooler Runaway"); + //PROGMEM Language_Str MSG_COOLING_FAILED = _UxGT("Cooling Failed"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Błąd: MAXTEMP"); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Błąd: MINTEMP"); PROGMEM Language_Str MSG_HALTED = _UxGT("Drukarka zatrzym."); PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Proszę zresetować"); - PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); // One character only + //PROGMEM Language_Str MSG_SHORT_DAY = _UxGT("d"); // One character only PROGMEM Language_Str MSG_SHORT_HOUR = _UxGT("g"); // One character only - PROGMEM Language_Str MSG_SHORT_MINUTE = _UxGT("m"); // One character only + //PROGMEM Language_Str MSG_SHORT_MINUTE = _UxGT("m"); // One character only PROGMEM Language_Str MSG_HEATING = _UxGT("Rozgrzewanie..."); PROGMEM Language_Str MSG_COOLING = _UxGT("Chłodzenie..."); PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Rozgrzewanie stołu..."); PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Chłodzenie stołu..."); + //PROGMEM Language_Str MSG_PROBE_HEATING = _UxGT("Probe Heating..."); + //PROGMEM Language_Str MSG_PROBE_COOLING = _UxGT("Probe Cooling..."); PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Rozgrzewanie komory..."); PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Chłodzenie komory..."); + //PROGMEM Language_Str MSG_LASER_COOLING = _UxGT("Laser Cooling..."); PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Kalibrowanie Delty"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Kalibruj X"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Kalibruj Y"); @@ -414,8 +527,9 @@ namespace Language_pl { PROGMEM Language_Str MSG_3POINT_LEVELING = _UxGT("Poziomowanie 3-punktowe"); PROGMEM Language_Str MSG_LINEAR_LEVELING = _UxGT("Poziomowanie liniowe"); PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Poziomowanie biliniowe"); - PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Unified Bed Leveling"); + //PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Unified Bed Leveling"); PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Poziomowanie siatką"); + //PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Mesh probing done"); PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Statystyki"); PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Info płyty"); PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Termistory"); @@ -424,6 +538,7 @@ namespace Language_pl { PROGMEM Language_Str MSG_INFO_PROTOCOL = _UxGT("Protokół"); PROGMEM Language_Str MSG_INFO_RUNAWAY_OFF = _UxGT("Zegar pracy: OFF"); PROGMEM Language_Str MSG_INFO_RUNAWAY_ON = _UxGT("Zegar pracy: ON"); + //PROGMEM Language_Str MSG_HOTEND_IDLE_TIMEOUT = _UxGT("Hotend Idle Timeout"); PROGMEM Language_Str MSG_CASE_LIGHT = _UxGT("Oświetlenie obudowy"); PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Jasność oświetlenia"); @@ -443,8 +558,8 @@ namespace Language_pl { PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Użyty fil."); #endif - PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Min Temp"); - PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Max Temp"); + //PROGMEM Language_Str MSG_INFO_MIN_TEMP = _UxGT("Min Temp"); + //PROGMEM Language_Str MSG_INFO_MAX_TEMP = _UxGT("Max Temp"); PROGMEM Language_Str MSG_INFO_PSU = _UxGT("Zasilacz"); PROGMEM Language_Str MSG_DRIVE_STRENGTH = _UxGT("Siła silnika"); PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Siła %"); @@ -467,7 +582,7 @@ namespace Language_pl { PROGMEM Language_Str MSG_LCD_PROBING_FAILED = _UxGT("Sondowanie nieudane"); PROGMEM Language_Str MSG_MMU2_CHOOSE_FILAMENT_HEADER = _UxGT("WYBIERZ FILAMENT"); - PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); + //PROGMEM Language_Str MSG_MMU2_MENU = _UxGT("MMU"); PROGMEM Language_Str MSG_KILL_MMU2_FIRMWARE = _UxGT("Uaktualnij firmware MMU!"); PROGMEM Language_Str MSG_MMU2_NOT_RESPONDING = _UxGT("MMU wymaga uwagi."); PROGMEM Language_Str MSG_MMU2_RESUME = _UxGT("Wznów wydruk"); @@ -482,7 +597,7 @@ namespace Language_pl { PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Wysuwanie fil. ..."); PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Wysuwanie fil...."); PROGMEM Language_Str MSG_MMU2_ALL = _UxGT("Wszystko"); - PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("Filament ~"); + //PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("Filament ~"); PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("Resetuj MMU"); PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("Resetowanie MMU..."); PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Usuń, kliknij"); @@ -490,12 +605,41 @@ namespace Language_pl { PROGMEM Language_Str MSG_MIX = _UxGT("Miks"); PROGMEM Language_Str MSG_MIX_COMPONENT_N = _UxGT("Komponent ="); PROGMEM Language_Str MSG_MIXER = _UxGT("Mikser"); - PROGMEM Language_Str MSG_GRADIENT = _UxGT("Gradient"); + //PROGMEM Language_Str MSG_GRADIENT = _UxGT("Gradient"); PROGMEM Language_Str MSG_FULL_GRADIENT = _UxGT("Pełny gradient"); PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("Przełacz miks"); - PROGMEM Language_Str MSG_CYCLE_MIX = _UxGT("Cycle Mix"); - PROGMEM Language_Str MSG_GRADIENT_MIX = _UxGT("Gradient Mix"); + //PROGMEM Language_Str MSG_CYCLE_MIX = _UxGT("Cycle Mix"); + //PROGMEM Language_Str MSG_GRADIENT_MIX = _UxGT("Gradient Mix"); PROGMEM Language_Str MSG_REVERSE_GRADIENT = _UxGT("Odwrotny gradient"); + //PROGMEM Language_Str MSG_ACTIVE_VTOOL = _UxGT("Active V-tool"); + //PROGMEM Language_Str MSG_START_VTOOL = _UxGT("Start V-tool"); + //PROGMEM Language_Str MSG_END_VTOOL = _UxGT(" End V-tool"); + //PROGMEM Language_Str MSG_GRADIENT_ALIAS = _UxGT("Alias V-tool"); + //PROGMEM Language_Str MSG_RESET_VTOOLS = _UxGT("Reset V-tools"); + //PROGMEM Language_Str MSG_COMMIT_VTOOL = _UxGT("Commit V-tool Mix"); + //PROGMEM Language_Str MSG_VTOOLS_RESET = _UxGT("V-tools Were Reset"); + //PROGMEM Language_Str MSG_START_Z = _UxGT("Start Z:"); + //PROGMEM Language_Str MSG_END_Z = _UxGT(" End Z:"); + + PROGMEM Language_Str MSG_GAMES = _UxGT("Gry"); + //PROGMEM Language_Str MSG_BRICKOUT = _UxGT("Brickout"); + //PROGMEM Language_Str MSG_INVADERS = _UxGT("Invaders"); + //PROGMEM Language_Str MSG_SNAKE = _UxGT("Sn4k3"); + //PROGMEM Language_Str MSG_MAZE = _UxGT("Maze"); + + //PROGMEM Language_Str MSG_BAD_PAGE = _UxGT("Bad page index"); + //PROGMEM Language_Str MSG_BAD_PAGE_SPEED = _UxGT("Bad page speed"); + + PROGMEM Language_Str MSG_EDIT_PASSWORD = _UxGT("Zmień hasło"); + PROGMEM Language_Str MSG_LOGIN_REQUIRED = _UxGT("Wymagane zalogowanie"); + PROGMEM Language_Str MSG_PASSWORD_SETTINGS = _UxGT("Ustawienia hasła"); + PROGMEM Language_Str MSG_ENTER_DIGIT = _UxGT("Wprowadź cyfrę"); + PROGMEM Language_Str MSG_CHANGE_PASSWORD = _UxGT("Ustaw/zmień hasło"); + PROGMEM Language_Str MSG_REMOVE_PASSWORD = _UxGT("Usuń hasło"); + PROGMEM Language_Str MSG_PASSWORD_SET = _UxGT("Hasło to "); + PROGMEM Language_Str MSG_START_OVER = _UxGT("Od nowa"); + PROGMEM Language_Str MSG_REMINDER_SAVE_SETTINGS = _UxGT("Pamiętaj by zapisać!"); + PROGMEM Language_Str MSG_PASSWORD_REMOVED = _UxGT("Hasło usunięte"); // // Filament Change screens show up to 3 lines on a 4-line display @@ -526,4 +670,51 @@ namespace Language_pl { PROGMEM Language_Str MSG_FILAMENT_CHANGE_CONT_PURGE = _UxGT(MSG_1_LINE("Kliknij by zakończyć")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_RESUME = _UxGT(MSG_1_LINE("Wznawianie...")); #endif + PROGMEM Language_Str MSG_TMC_DRIVERS = _UxGT("Sterowniki TMC"); + PROGMEM Language_Str MSG_TMC_CURRENT = _UxGT("Prąd sterownika"); + //PROGMEM Language_Str MSG_TMC_HYBRID_THRS = _UxGT("Hybrid Threshold"); + PROGMEM Language_Str MSG_TMC_HOMING_THRS = _UxGT("Zerowanie bezczujnikowe"); + //PROGMEM Language_Str MSG_TMC_STEPPING_MODE = _UxGT("Stepping Mode"); + //PROGMEM Language_Str MSG_TMC_STEALTH_ENABLED = _UxGT("StealthChop Enabled"); + //PROGMEM Language_Str MSG_SERVICE_RESET = _UxGT("Reset"); + //PROGMEM Language_Str MSG_SERVICE_IN = _UxGT(" in:"); + //PROGMEM Language_Str MSG_BACKLASH = _UxGT("Backlash"); + //PROGMEM Language_Str MSG_BACKLASH_A = LCD_STR_A; + //PROGMEM Language_Str MSG_BACKLASH_B = LCD_STR_B; + //PROGMEM Language_Str MSG_BACKLASH_C = LCD_STR_C; + PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Korekcja"); + PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Wygładzanie"); + + PROGMEM Language_Str MSG_LEVEL_X_AXIS = _UxGT("Wypoziomuj oś X"); + PROGMEM Language_Str MSG_AUTO_CALIBRATE = _UxGT("Autokalibracja"); + #if ENABLED(TOUCH_UI_FTDI_EVE) + //PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Idle timeout, temperature decreased. Press Okay to reheat and again to resume."); + #else + //PROGMEM Language_Str MSG_HEATER_TIMEOUT = _UxGT("Heater Timeout"); + #endif + //PROGMEM Language_Str MSG_REHEAT = _UxGT("Reheat"); + //PROGMEM Language_Str MSG_REHEATING = _UxGT("Reheating..."); + + //PROGMEM Language_Str MSG_PROBE_WIZARD = _UxGT("Z Probe Wizard"); + //PROGMEM Language_Str MSG_PROBE_WIZARD_PROBING = _UxGT("Probing Z Reference"); + //PROGMEM Language_Str MSG_PROBE_WIZARD_MOVING = _UxGT("Moving to Probing Pos"); + + PROGMEM Language_Str MSG_SOUND = _UxGT("Dźwięk"); + + //PROGMEM Language_Str MSG_TOP_LEFT = _UxGT("Top Left"); + //PROGMEM Language_Str MSG_BOTTOM_LEFT = _UxGT("Bottom Left"); + //PROGMEM Language_Str MSG_TOP_RIGHT = _UxGT("Top Right"); + //PROGMEM Language_Str MSG_BOTTOM_RIGHT = _UxGT("Bottom Right"); + PROGMEM Language_Str MSG_CALIBRATION_COMPLETED = _UxGT("Kalibracja zakończona"); + PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Kalibracja nie powiodła się"); + + //PROGMEM Language_Str MSG_DRIVER_BACKWARD = _UxGT(" driver backward"); } + +#if FAN_COUNT == 1 + #define MSG_FIRST_FAN_SPEED MSG_FAN_SPEED + #define MSG_EXTRA_FIRST_FAN_SPEED MSG_EXTRA_FAN_SPEED +#else + #define MSG_FIRST_FAN_SPEED MSG_FAN_SPEED_N + #define MSG_EXTRA_FIRST_FAN_SPEED MSG_EXTRA_FAN_SPEED_N +#endif diff --git a/Marlin/src/lcd/language/language_pt.h b/Marlin/src/lcd/language/language_pt.h index 60b0c550564f6..4bec74558e807 100644 --- a/Marlin/src/lcd/language/language_pt.h +++ b/Marlin/src/lcd/language/language_pt.h @@ -85,6 +85,7 @@ namespace Language_pt { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Mover 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mover 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Mover 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Mover 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Velocidade"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Base Z"); PROGMEM Language_Str MSG_NOZZLE = " " LCD_STR_THERMOMETER _UxGT(" Bico"); diff --git a/Marlin/src/lcd/language/language_pt_br.h b/Marlin/src/lcd/language/language_pt_br.h index 642a7d92031f3..88135f5e28452 100644 --- a/Marlin/src/lcd/language/language_pt_br.h +++ b/Marlin/src/lcd/language/language_pt_br.h @@ -218,6 +218,7 @@ namespace Language_pt_br { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Mover 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Mover 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Mover 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Mover 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Velocidade"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Base Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Bocal"); diff --git a/Marlin/src/lcd/language/language_ro.h b/Marlin/src/lcd/language/language_ro.h index a34717acb5175..9313adf3f6e9e 100644 --- a/Marlin/src/lcd/language/language_ro.h +++ b/Marlin/src/lcd/language/language_ro.h @@ -232,6 +232,7 @@ namespace Language_ro { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Move 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Move 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Move 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Move 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Speed"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Bed Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Nozzle"); diff --git a/Marlin/src/lcd/language/language_ru.h b/Marlin/src/lcd/language/language_ru.h index a10f47ef8ebff..4240ecbec3b24 100644 --- a/Marlin/src/lcd/language/language_ru.h +++ b/Marlin/src/lcd/language/language_ru.h @@ -69,6 +69,9 @@ namespace Language_ru { PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Парковка X"); PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Парковка Y"); PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Парковка Z"); + PROGMEM Language_Str MSG_AUTO_HOME_I = _UxGT("Парковка ") LCD_STR_I; + PROGMEM Language_Str MSG_AUTO_HOME_J = _UxGT("Парковка ") LCD_STR_J; + PROGMEM Language_Str MSG_AUTO_HOME_K = _UxGT("Парковка ") LCD_STR_K; PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Авто Z-выравнивание"); PROGMEM Language_Str MSG_ITERATION = _UxGT("G34 Итерация: %i"); PROGMEM Language_Str MSG_DECREASING_ACCURACY = _UxGT("Уменьшение точности!"); @@ -80,11 +83,29 @@ namespace Language_ru { PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Высота спада"); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Установ. смещения дома"); + PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("Смещение дома X"); + PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Смещение дома Y"); + PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Смещение дома Z"); + PROGMEM Language_Str MSG_HOME_OFFSET_I = _UxGT("Смещение дома ") LCD_STR_I; + PROGMEM Language_Str MSG_HOME_OFFSET_J = _UxGT("Смещение дома ") LCD_STR_J; + PROGMEM Language_Str MSG_HOME_OFFSET_K = _UxGT("Смещение дома ") LCD_STR_K; #else PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Установ.смещ.дома"); + PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("Смещ. дома X"); + PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Смещ. дома Y"); + PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Смещ. дома Z"); + PROGMEM Language_Str MSG_HOME_OFFSET_I = _UxGT("Смещ. дома ") LCD_STR_I; + PROGMEM Language_Str MSG_HOME_OFFSET_J = _UxGT("Смещ. дома ") LCD_STR_J; + PROGMEM Language_Str MSG_HOME_OFFSET_K = _UxGT("Смещ. дома ") LCD_STR_K; #endif PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Смещения применены"); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Установить ноль"); + PROGMEM Language_Str MSG_SELECT_ORIGIN = _UxGT("Выберите ноль"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Последнее знач. "); + #else + PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Послед. знач. "); + #endif #if PREHEAT_COUNT PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Преднагрев ") PREHEAT_1_LABEL; PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Нагрев ") PREHEAT_1_LABEL " ~"; @@ -107,14 +128,22 @@ namespace Language_ru { PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Частота"); PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Управление лазером"); PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Переключить лазер"); - PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Мощность лазера"); PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Управление шпинделем"); PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Переключить шпиндель"); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Мощность шпинделя"); + PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Мощность лазера"); + PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Тестовый импульс мс"); #else PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Мощн.шпинделя"); - #endif + PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Мощн. лазера"); + PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Тест. имп. мс"); + #endif + PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Переключить обдув"); + PROGMEM Language_Str MSG_LASER_ASSIST_TOGGLE = _UxGT("Управление обдувом"); + PROGMEM Language_Str MSG_FLOWMETER_FAULT = _UxGT("Ошибка обдува"); + PROGMEM Language_Str MSG_LASER_FIRE_PULSE = _UxGT("Импульс лазера"); + PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Переключить вакуум"); PROGMEM Language_Str MSG_SPINDLE_FORWARD = _UxGT("Шпиндель вперёд"); PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Инверсия шпинделя"); @@ -127,6 +156,15 @@ namespace Language_ru { PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Выровнять стол"); PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Выровнять углы"); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Следующий угол"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_LEVEL_CORNERS_RAISE = _UxGT("Вверх до срабатыв. зонда"); + PROGMEM Language_Str MSG_LEVEL_CORNERS_IN_RANGE = _UxGT("Углы в норме. Вырав.стола"); + #else + PROGMEM Language_Str MSG_LEVEL_CORNERS_RAISE = _UxGT("Вверх до сраб. зонда"); + PROGMEM Language_Str MSG_LEVEL_CORNERS_IN_RANGE = _UxGT("Углы в норме. Вырав."); + #endif + PROGMEM Language_Str MSG_LEVEL_CORNERS_GOOD_POINTS = _UxGT("Хорошие точки: "); + PROGMEM Language_Str MSG_LEVEL_CORNERS_LAST_Z = _UxGT("Последняя Z: "); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Смещение по Z"); PROGMEM Language_Str MSG_EDITING_STOPPED = _UxGT("Правка сетки окончена"); @@ -164,12 +202,13 @@ namespace Language_ru { PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Точка разворота"); PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Ручной ввод сетки"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Разместить шайбу и измерить"); + PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Разместить шайбу,измерить"); PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Убрать и замерить стол"); #else - PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Разм.шайбу,измерить"); + PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Разм.шайбу, измерить"); PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Убрать, измер. стол"); #endif + PROGMEM Language_Str MSG_UBL_MESH_WIZARD = _UxGT("Мастер сеток UBL"); PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Измерение"); PROGMEM Language_Str MSG_UBL_MOVING_TO_NEXT = _UxGT("Двигаемся дальше"); PROGMEM Language_Str MSG_UBL_ACTIVATE_MESH = _UxGT("Активировать UBL"); @@ -185,17 +224,15 @@ namespace Language_ru { PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Правка сетки завершена"); #else PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = LCD_STR_THERMOMETER _UxGT(" стола, ") LCD_STR_DEGREE "C"; - PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = LCD_STR_THERMOMETER _UxGT(" стола, ") LCD_STR_DEGREE "C"; + PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Своя ") LCD_STR_THERMOMETER _UxGT(" стола,") LCD_STR_DEGREE "C"; PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = LCD_STR_THERMOMETER _UxGT(" сопла, ") LCD_STR_DEGREE "C"; - PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = LCD_STR_THERMOMETER _UxGT(" сопла, ") LCD_STR_DEGREE "C"; + PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Своя ") LCD_STR_THERMOMETER _UxGT(" сопла,") LCD_STR_DEGREE "C"; PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Построить свою"); PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Правка завершена"); #endif PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("Точная правка сетки"); PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("Построить сетку"); - #if PREHEAT_COUNT - PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Построить сетку $"); - #endif + PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Построить сетку $"); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("Построить холодную сетку"); #else @@ -205,14 +242,10 @@ namespace Language_ru { PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Высота"); PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_MENU = _UxGT("Проверить сетку"); #if LCD_WIDTH > 21 - #if PREHEAT_COUNT - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Проверить сетку $"); - #endif + PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Проверить сетку $"); PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Проверить свою сетку"); #else - #if PREHEAT_COUNT - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Провер. сетку $"); - #endif + PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Провер. сетку $"); PROGMEM Language_Str MSG_UBL_VALIDATE_CUSTOM_MESH = _UxGT("Провер. свою сетку"); #endif PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26 нагрев стола"); @@ -239,11 +272,12 @@ namespace Language_ru { #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Сохранить сетку снаружи"); PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("Вывод информации UBL"); + PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Кол-во заполнителя"); #else PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Сохранить снаружи"); PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("Информация UBL"); + PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Кол-во заполн."); #endif - PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Кол-во заполнителя"); PROGMEM Language_Str MSG_UBL_MANUAL_FILLIN = _UxGT("Ручное заполнение"); PROGMEM Language_Str MSG_UBL_SMART_FILLIN = _UxGT("Умное заполнение"); PROGMEM Language_Str MSG_UBL_FILLIN_MESH = _UxGT("Заполнить сетку"); @@ -303,6 +337,9 @@ namespace Language_ru { PROGMEM Language_Str MSG_MOVE_X = _UxGT("Движение по X"); PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Движение по Y"); PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Движение по Z"); + PROGMEM Language_Str MSG_MOVE_I = _UxGT("Движение по ") LCD_STR_I; + PROGMEM Language_Str MSG_MOVE_J = _UxGT("Движение по ") LCD_STR_J; + PROGMEM Language_Str MSG_MOVE_K = _UxGT("Движение по ") LCD_STR_K; PROGMEM Language_Str MSG_MOVE_E = _UxGT("Экструдер"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Экструдер *"); PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Сопло не нагрето"); @@ -310,6 +347,7 @@ namespace Language_ru { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Движение 0.1мм"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Движение 1мм"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Движение 10мм"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Движение 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Скорость"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Z стола"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Сопло, ") LCD_STR_DEGREE "C"; @@ -318,6 +356,15 @@ namespace Language_ru { PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Сопло ожидает"); PROGMEM Language_Str MSG_BED = _UxGT("Стол, ") LCD_STR_DEGREE "C"; PROGMEM Language_Str MSG_CHAMBER = _UxGT("Камера,") LCD_STR_DEGREE "C"; + PROGMEM Language_Str MSG_COOLER = _UxGT("Охлаждение лазера"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Переключить охлаждение"); + PROGMEM Language_Str MSG_FLOWMETER_SAFETY = _UxGT("Безопасность потока"); + #else + PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Переключить охлажд."); + PROGMEM Language_Str MSG_FLOWMETER_SAFETY = _UxGT("Безопасн. потока"); + #endif + PROGMEM Language_Str MSG_LASER = _UxGT("Лазер"); PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Кулер"); PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Кулер ~"); PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Сохранённый кулер ~"); @@ -352,6 +399,9 @@ namespace Language_ru { PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-рывок"); PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-рывок"); PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-рывок"); + PROGMEM Language_Str MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-рывок"); + PROGMEM Language_Str MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-рывок"); + PROGMEM Language_Str MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-рывок"); PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-рывок"); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Отклонение узла"); @@ -362,6 +412,9 @@ namespace Language_ru { PROGMEM Language_Str MSG_VMAX_A = _UxGT("Скор.макс ") LCD_STR_A; PROGMEM Language_Str MSG_VMAX_B = _UxGT("Скор.макс ") LCD_STR_B; PROGMEM Language_Str MSG_VMAX_C = _UxGT("Скор.макс ") LCD_STR_C; + PROGMEM Language_Str MSG_VMAX_I = _UxGT("Скор.макс ") LCD_STR_I; + PROGMEM Language_Str MSG_VMAX_J = _UxGT("Скор.макс ") LCD_STR_J; + PROGMEM Language_Str MSG_VMAX_K = _UxGT("Скор.макс ") LCD_STR_K; PROGMEM Language_Str MSG_VMAX_E = _UxGT("Скор.макс ") LCD_STR_E; PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Скор.макс *"); PROGMEM Language_Str MSG_VMIN = _UxGT("Скор.мин"); @@ -370,6 +423,9 @@ namespace Language_ru { PROGMEM Language_Str MSG_AMAX_A = _UxGT("Ускор.макс ") LCD_STR_A; PROGMEM Language_Str MSG_AMAX_B = _UxGT("Ускор.макс ") LCD_STR_B; PROGMEM Language_Str MSG_AMAX_C = _UxGT("Ускор.макс ") LCD_STR_C; + PROGMEM Language_Str MSG_AMAX_I = _UxGT("Ускор.макс ") LCD_STR_I; + PROGMEM Language_Str MSG_AMAX_J = _UxGT("Ускор.макс ") LCD_STR_J; + PROGMEM Language_Str MSG_AMAX_K = _UxGT("Ускор.макс ") LCD_STR_K; PROGMEM Language_Str MSG_AMAX_E = _UxGT("Ускор.макс ") LCD_STR_E; PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Ускор.макс *"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Ускор.втягив."); @@ -380,6 +436,9 @@ namespace Language_ru { PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" шаг/мм"); PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" шаг/мм"); PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" шаг/мм"); + PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" шаг/мм"); + PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" шаг/мм"); + PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" шаг/мм"); PROGMEM Language_Str MSG_E_STEPS = _UxGT("E шаг/мм"); PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* шаг/мм"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Температура"); @@ -402,10 +461,11 @@ namespace Language_ru { PROGMEM Language_Str MSG_CONTRAST = _UxGT("Контраст экрана"); PROGMEM Language_Str MSG_STORE_EEPROM = _UxGT("Сохранить настройки"); PROGMEM Language_Str MSG_LOAD_EEPROM = _UxGT("Загрузить настройки"); - PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("На базовые параметры"); #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("На базовые параметры"); PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Инициализация EEPROM"); #else + PROGMEM Language_Str MSG_RESTORE_DEFAULTS = _UxGT("На базовые парам."); PROGMEM Language_Str MSG_INIT_EEPROM = _UxGT("Инициализ. EEPROM"); #endif PROGMEM Language_Str MSG_ERR_EEPROM_CRC = _UxGT("Сбой EEPROM: CRC"); @@ -414,7 +474,7 @@ namespace Language_ru { PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Параметры сохранены"); PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Обновление прошивки"); PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Сброс принтера"); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT(" Обновить"); + PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT(" Обновить"); PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Главный экран"); PROGMEM Language_Str MSG_PREPARE = _UxGT("Подготовить"); PROGMEM Language_Str MSG_TUNE = _UxGT("Настроить"); @@ -541,10 +601,17 @@ namespace Language_ru { PROGMEM Language_Str MSG_ZPROBE_XOFFSET = _UxGT("Смещение X"); PROGMEM Language_Str MSG_ZPROBE_YOFFSET = _UxGT("Смещение Y"); PROGMEM Language_Str MSG_ZPROBE_ZOFFSET = _UxGT("Смещение Z"); - PROGMEM Language_Str MSG_MOVE_NOZZLE_TO_BED = _UxGT("Двигать сопло к столу"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_MOVE_NOZZLE_TO_BED = _UxGT("Двигать сопло к столу"); + #else + PROGMEM Language_Str MSG_MOVE_NOZZLE_TO_BED = _UxGT("Двиг. сопло к столу"); + #endif PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Микрошаг X"); PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Микрошаг Y"); PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Микрошаг Z"); + PROGMEM Language_Str MSG_BABYSTEP_I = _UxGT("Микрошаг ") LCD_STR_I; + PROGMEM Language_Str MSG_BABYSTEP_J = _UxGT("Микрошаг ") LCD_STR_J; + PROGMEM Language_Str MSG_BABYSTEP_K = _UxGT("Микрошаг ") LCD_STR_K; PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Сумарно"); PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Сработал концевик"); PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Разогрев не удался"); @@ -552,6 +619,8 @@ namespace Language_ru { PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("УТЕЧКА ТЕПЛА"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("УТЕЧКА ТЕПЛА СТОЛА"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("УТЕЧКА ТЕПЛА КАМЕРЫ"); + PROGMEM Language_Str MSG_THERMAL_RUNAWAY_COOLER = _UxGT("УТЕЧКА ОХЛАЖДЕНИЯ"); + PROGMEM Language_Str MSG_COOLING_FAILED = _UxGT("ОХЛАДИТЬ НЕ УДАЛОСЬ"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Ошибка: Т макс."); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Ошибка: Т мин."); PROGMEM Language_Str MSG_HALTED = _UxGT("ПРИНТЕР ОСТАНОВЛЕН"); @@ -567,6 +636,7 @@ namespace Language_ru { PROGMEM Language_Str MSG_PROBE_COOLING = _UxGT("Охлаждение зонда..."); PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Нагрев камеры..."); PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Охладжение камеры..."); + PROGMEM Language_Str MSG_LASER_COOLING = _UxGT("Охлаждение лазера..."); PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Калибровка Delta"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Калибровать X"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Калибровать Y"); @@ -575,13 +645,12 @@ namespace Language_ru { PROGMEM Language_Str MSG_DELTA_SETTINGS = _UxGT("Настройки Delta"); PROGMEM Language_Str MSG_DELTA_AUTO_CALIBRATE = _UxGT("Авто калибровка"); PROGMEM Language_Str MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Высота Delta"); - #if LCD_WIDTH >= 20 - PROGMEM Language_Str MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Зондировать Z-смещение"); - PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Стержень диагонали"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Зондировать Z-смещения"); #else PROGMEM Language_Str MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Зондир. Z-смещения"); - PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Стержень диаг."); #endif + PROGMEM Language_Str MSG_DELTA_DIAG_ROD = _UxGT("Стержень диаг."); PROGMEM Language_Str MSG_DELTA_HEIGHT = _UxGT("Высота"); PROGMEM Language_Str MSG_DELTA_RADIUS = _UxGT("Радиус"); PROGMEM Language_Str MSG_INFO_MENU = _UxGT("О принтере"); @@ -597,6 +666,11 @@ namespace Language_ru { #endif PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("Управление UBL"); PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Выравнивание сетки"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Зондирование выполнено"); + #else + PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Зондиров. выполнено"); + #endif PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Статистика принтера"); PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Данные платы"); @@ -617,14 +691,14 @@ namespace Language_ru { PROGMEM Language_Str MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Яркость подсветки"); PROGMEM Language_Str MSG_KILL_EXPECTED_PRINTER = _UxGT("Неверный принтер"); - #if LCD_WIDTH >= 20 + #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Счётчик печати"); PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Общее время печати"); PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Наидольшее задание"); PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Длина филамента"); #else - PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Отпечатков"); - PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Всего"); + PROGMEM Language_Str MSG_INFO_PRINT_COUNT = _UxGT("Напечатано"); + PROGMEM Language_Str MSG_INFO_PRINT_TIME = _UxGT("Общее время"); PROGMEM Language_Str MSG_INFO_PRINT_LONGEST = _UxGT("Наидольшее"); PROGMEM Language_Str MSG_INFO_PRINT_FILAMENT = _UxGT("Выдавлено"); #endif @@ -637,6 +711,9 @@ namespace Language_ru { PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Привод, %"); PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y Привод, %"); PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z Привод, %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = LCD_STR_I _UxGT(" Привод, %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = LCD_STR_J _UxGT(" Привод, %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = LCD_STR_K _UxGT(" Привод, %"); PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Привод, %"); PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("СБОЙ СВЯЗИ С TMC"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Запись DAC в EEPROM"); @@ -749,11 +826,11 @@ namespace Language_ru { #endif PROGMEM Language_Str MSG_PASSWORD_REMOVED = _UxGT("Пароль удалён"); - PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Парковка...")); // // Filament Change screens show up to 3 lines on a 4-line display // ...or up to 2 lines on a 3-line display // + PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Парковка...")); #if LCD_HEIGHT >= 4 PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_3_LINE("Нажмите кнопку", "для продолжения", "печати")); PROGMEM Language_Str MSG_FILAMENT_CHANGE_INIT = _UxGT(MSG_2_LINE("Ожидайте начала", "смены филамента")); @@ -803,8 +880,8 @@ namespace Language_ru { PROGMEM Language_Str MSG_PROBE_WIZARD = _UxGT("Мастер Z-зонда"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_PROBE_WIZARD_PROBING = _UxGT("Зондиров. контрольной точки Z"); - PROGMEM Language_Str MSG_PROBE_WIZARD_MOVING = _UxGT("Движение к точке зондирования"); + PROGMEM Language_Str MSG_PROBE_WIZARD_PROBING = _UxGT("Зондиров. контр. точки Z"); + PROGMEM Language_Str MSG_PROBE_WIZARD_MOVING = _UxGT("Движение к точке зондиров."); #else PROGMEM Language_Str MSG_PROBE_WIZARD_PROBING = _UxGT("Зондир.контр.точки Z"); PROGMEM Language_Str MSG_PROBE_WIZARD_MOVING = _UxGT("Движ. к точке зондир."); @@ -818,6 +895,11 @@ namespace Language_ru { PROGMEM Language_Str MSG_BOTTOM_RIGHT = _UxGT("Нижний правый"); PROGMEM Language_Str MSG_CALIBRATION_COMPLETED = _UxGT("Калибровка успешна"); PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Ошибка калибровки"); + + PROGMEM Language_Str MSG_DRIVER_BACKWARD = _UxGT(" драйвер назад"); + + PROGMEM Language_Str MSG_SD_CARD = _UxGT("SD Карта"); + PROGMEM Language_Str MSG_USB_DISK = _UxGT("USB Диск"); } #if FAN_COUNT == 1 diff --git a/Marlin/src/lcd/language/language_sk.h b/Marlin/src/lcd/language/language_sk.h index 2e851842e4ef0..96f1bc7ee5dee 100644 --- a/Marlin/src/lcd/language/language_sk.h +++ b/Marlin/src/lcd/language/language_sk.h @@ -81,7 +81,10 @@ namespace Language_sk { PROGMEM Language_Str MSG_LEVEL_BED_NEXT_POINT = _UxGT("Ďalší bod"); PROGMEM Language_Str MSG_LEVEL_BED_DONE = _UxGT("Vyrovnanie hotové!"); PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Výška rovnania"); - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Nastaviť ofsety"); + PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Nastav. dom. ofsety"); + PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("X Ofset"); + PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Y Ofset"); + PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Z Ofset"); PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Ofsety nastavené"); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Nastaviť začiatok"); PROGMEM Language_Str MSG_ASSISTED_TRAMMING = _UxGT("Asist. vyrovnanie"); @@ -114,12 +117,15 @@ namespace Language_sk { PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Výkon lasera"); PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Výkon vretena"); PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Prepnúť laser"); + PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Prepnúť odsávanie"); + PROGMEM Language_Str MSG_LASER_ASSIST_TOGGLE = _UxGT("Prepnúť ofuk"); PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Test. impulz ms"); PROGMEM Language_Str MSG_LASER_FIRE_PULSE = _UxGT("Vystreliť impulz"); + PROGMEM Language_Str MSG_FLOWMETER_FAULT = _UxGT("Chyba chladenia"); PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Prepnúť vreteno"); + PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Prepnúť odsávanie"); PROGMEM Language_Str MSG_SPINDLE_FORWARD = _UxGT("Dopredný chod"); PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Spätný chod"); - PROGMEM Language_Str MSG_SWITCH_PS_ON = _UxGT("Zapnúť napájanie"); PROGMEM Language_Str MSG_SWITCH_PS_OFF = _UxGT("Vypnúť napájanie"); PROGMEM Language_Str MSG_EXTRUDE = _UxGT("Vytlačiť (extr.)"); @@ -160,6 +166,7 @@ namespace Language_sk { PROGMEM Language_Str MSG_UBL_LEVEL_BED = _UxGT("UBL rovnanie"); PROGMEM Language_Str MSG_LCD_TILTING_MESH = _UxGT("Vyrovnávam bod"); PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Manuálna sieť bodov"); + PROGMEM Language_Str MSG_UBL_MESH_WIZARD = _UxGT("Spriev. UBL rovnan."); PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Položte a zmerajte"); PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Zmerajte"); PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Odstráňte a zmerajte"); @@ -265,6 +272,7 @@ namespace Language_sk { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Posunúť o 0,1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Posunúť o 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Posunúť o 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Posunúť o 100mm"); PROGMEM Language_Str MSG_MOVE_0001IN = _UxGT("Posunúť o 0,001in"); PROGMEM Language_Str MSG_MOVE_001IN = _UxGT("Posunúť o 0,01in"); PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Posunúť o 0,1in"); @@ -276,6 +284,10 @@ namespace Language_sk { PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Záložná tryska"); PROGMEM Language_Str MSG_BED = _UxGT("Podložka"); PROGMEM Language_Str MSG_CHAMBER = _UxGT("Komora"); + PROGMEM Language_Str MSG_COOLER = _UxGT("Chladen. lasera"); + PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Prepnúť chladenie"); + PROGMEM Language_Str MSG_FLOWMETER_SAFETY = _UxGT("Bezpeč. prietok"); + PROGMEM Language_Str MSG_LASER = _UxGT("Laser"); PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Rýchlosť vent."); PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Rýchlosť vent. ~"); PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Ulož. vent. ~"); @@ -472,6 +484,8 @@ namespace Language_sk { PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("TEPLOTNÝ SKOK"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("TEPLOTNÝ SKOK PODL."); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("TEPLOTNÝ SKOK KOMO."); + PROGMEM Language_Str MSG_THERMAL_RUNAWAY_COOLER = _UxGT("TEPLOTNÝ SKOK CHLAD."); + PROGMEM Language_Str MSG_COOLING_FAILED = _UxGT("Ochladz. zlyhalo"); PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("Chyba: MAXTEMP"); PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("Chyba: MINTEMP"); PROGMEM Language_Str MSG_HALTED = _UxGT("TLAČIAREŇ ZASTAVENÁ"); @@ -487,6 +501,7 @@ namespace Language_sk { PROGMEM Language_Str MSG_PROBE_COOLING = _UxGT("Ochladz. sondy..."); PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Ohrev komory..."); PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Ochladz. komory..."); + PROGMEM Language_Str MSG_LASER_COOLING = _UxGT("Ochladz. lasera..."); PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Delta kalibrácia"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Kalibrovať X"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Kalibrovať Y"); @@ -506,6 +521,7 @@ namespace Language_sk { PROGMEM Language_Str MSG_BILINEAR_LEVELING = _UxGT("Bilineárne rovnanie"); PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("UBL rovnanie"); PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Mriežkové rovnanie"); + PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Mriežka dokončená"); PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Štatistika"); PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Info. o doske"); PROGMEM Language_Str MSG_INFO_THERMISTOR_MENU = _UxGT("Termistory"); @@ -683,4 +699,6 @@ namespace Language_sk { PROGMEM Language_Str MSG_BOTTOM_RIGHT = _UxGT("Pravý dolný"); PROGMEM Language_Str MSG_CALIBRATION_COMPLETED = _UxGT("Kalibrácia dokončená"); PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Kalibrácia zlyhala"); + + PROGMEM Language_Str MSG_DRIVER_BACKWARD = _UxGT(" spätný chod ovl."); } diff --git a/Marlin/src/lcd/language/language_sv.h b/Marlin/src/lcd/language/language_sv.h index 722443fb21c17..f7b0f06769104 100644 --- a/Marlin/src/lcd/language/language_sv.h +++ b/Marlin/src/lcd/language/language_sv.h @@ -260,6 +260,7 @@ namespace Language_sv { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Flytta 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Flytta 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Flytta 10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Flytta 100mm"); PROGMEM Language_Str MSG_MOVE_0001IN = _UxGT("Flytta 0.001tum"); PROGMEM Language_Str MSG_MOVE_001IN = _UxGT("Flytta 0.01tum"); PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Flytta 0.1tum"); diff --git a/Marlin/src/lcd/language/language_tr.h b/Marlin/src/lcd/language/language_tr.h index 9d711ff376550..6858616b4d5e5 100644 --- a/Marlin/src/lcd/language/language_tr.h +++ b/Marlin/src/lcd/language/language_tr.h @@ -235,6 +235,7 @@ namespace Language_tr { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("10mm"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Hız"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Z Mesafesi"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Nozul"); diff --git a/Marlin/src/lcd/language/language_uk.h b/Marlin/src/lcd/language/language_uk.h index be0e420a42f96..86d0e01fe61b4 100644 --- a/Marlin/src/lcd/language/language_uk.h +++ b/Marlin/src/lcd/language/language_uk.h @@ -71,6 +71,9 @@ namespace Language_uk { PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Паркування X"); PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Паркування Y"); PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Паркування Z"); + PROGMEM Language_Str MSG_AUTO_HOME_I = _UxGT("Паркування ") LCD_STR_I; + PROGMEM Language_Str MSG_AUTO_HOME_J = _UxGT("Паркування ") LCD_STR_J; + PROGMEM Language_Str MSG_AUTO_HOME_K = _UxGT("Паркування ") LCD_STR_K; PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Авто Z-вирівнювання"); PROGMEM Language_Str MSG_ITERATION = _UxGT("G34 Ітерація: %i"); PROGMEM Language_Str MSG_DECREASING_ACCURACY = _UxGT("Зменьшення точності!"); @@ -82,11 +85,29 @@ namespace Language_uk { PROGMEM Language_Str MSG_Z_FADE_HEIGHT = _UxGT("Висота спаду"); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Встанов. зміщення дому"); - #else - PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Встанов. зміщ. дому"); + PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("Зміщення дому X"); + PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Зміщення дому Y"); + PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Зміщення дому Z"); + PROGMEM Language_Str MSG_HOME_OFFSET_I = _UxGT("Зміщення дому ") LCD_STR_I; + PROGMEM Language_Str MSG_HOME_OFFSET_J = _UxGT("Зміщення дому ") LCD_STR_J; + PROGMEM Language_Str MSG_HOME_OFFSET_K = _UxGT("Зміщення дому ") LCD_STR_K; + #else + PROGMEM Language_Str MSG_SET_HOME_OFFSETS = _UxGT("Встан. зміщ. дому"); + PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("Зміщ. дому X"); + PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Зміщ. дому Y"); + PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Зміщ. дому Z"); + PROGMEM Language_Str MSG_HOME_OFFSET_I = _UxGT("Зміщ. дому ") LCD_STR_I; + PROGMEM Language_Str MSG_HOME_OFFSET_J = _UxGT("Зміщ. дому ") LCD_STR_J; + PROGMEM Language_Str MSG_HOME_OFFSET_K = _UxGT("Зміщ. дому ") LCD_STR_K; #endif PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Зміщення прийняті"); PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Встановити нуль"); + PROGMEM Language_Str MSG_SELECT_ORIGIN = _UxGT("Оберіть нуль"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Останнє значення "); + #else + PROGMEM Language_Str MSG_LAST_VALUE_SP = _UxGT("Останнє знач. "); + #endif #if PREHEAT_COUNT PROGMEM Language_Str MSG_PREHEAT_1 = _UxGT("Нагрів ") PREHEAT_1_LABEL; PROGMEM Language_Str MSG_PREHEAT_1_H = _UxGT("Нагрів ") PREHEAT_1_LABEL " ~"; @@ -106,22 +127,29 @@ namespace Language_uk { #endif PROGMEM Language_Str MSG_PREHEAT_CUSTOM = _UxGT("Нагрів свого"); PROGMEM Language_Str MSG_COOLDOWN = _UxGT("Вимкнути нагрів"); + PROGMEM Language_Str MSG_CUTTER_FREQUENCY = _UxGT("Частота"); PROGMEM Language_Str MSG_LASER_MENU = _UxGT("Керування лазером"); + PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Керування шпінделем"); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Потужність лазера"); - PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Керування шпінделем"); #else PROGMEM Language_Str MSG_LASER_POWER = _UxGT("Потуж.лазера"); - PROGMEM Language_Str MSG_SPINDLE_MENU = _UxGT("Керув. шпінделем"); #endif PROGMEM Language_Str MSG_SPINDLE_TOGGLE = _UxGT("Перемкнути шпіндель"); PROGMEM Language_Str MSG_LASER_TOGGLE = _UxGT("Перемкнути лазер"); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Потуж. шпінделя"); + PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Тестовий імпульс мс"); #else PROGMEM Language_Str MSG_SPINDLE_POWER = _UxGT("Потуж. шпінд."); + PROGMEM Language_Str MSG_LASER_PULSE_MS = _UxGT("Тест. імп. мс"); #endif + PROGMEM Language_Str MSG_LASER_EVAC_TOGGLE = _UxGT("Перемкнути обдув"); + PROGMEM Language_Str MSG_LASER_ASSIST_TOGGLE = _UxGT("Керування обдувом"); + PROGMEM Language_Str MSG_FLOWMETER_FAULT = _UxGT("Помилка обдуву"); + PROGMEM Language_Str MSG_LASER_FIRE_PULSE = _UxGT("Імпульс лазеру"); + PROGMEM Language_Str MSG_SPINDLE_EVAC_TOGGLE = _UxGT("Перемкнути вакуум"); PROGMEM Language_Str MSG_SPINDLE_FORWARD = _UxGT("Шпіндель вперед"); PROGMEM Language_Str MSG_SPINDLE_REVERSE = _UxGT("Шпіндель назад"); @@ -134,11 +162,14 @@ namespace Language_uk { PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Вирівняти стіл"); PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Вирівняти кути"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_LEVEL_CORNERS_RAISE = _UxGT("Вгору до спрацювання зонду"); // not sure about this one - #else PROGMEM Language_Str MSG_LEVEL_CORNERS_RAISE = _UxGT("Вгору до спрацюв. зонду"); + PROGMEM Language_Str MSG_LEVEL_CORNERS_IN_RANGE = _UxGT("Кути в межах. Вирів.столу"); + #else + PROGMEM Language_Str MSG_LEVEL_CORNERS_RAISE = _UxGT("Вгору до спрац.зонду"); + PROGMEM Language_Str MSG_LEVEL_CORNERS_IN_RANGE = _UxGT("Кути в межах. Вирівн"); #endif - PROGMEM Language_Str MSG_LEVEL_CORNERS_IN_RANGE = _UxGT("Кути в межах. Вирівнювання столу"); // Too long? + PROGMEM Language_Str MSG_LEVEL_CORNERS_GOOD_POINTS = _UxGT("Хороші точки: "); + PROGMEM Language_Str MSG_LEVEL_CORNERS_LAST_Z = _UxGT("Остання Z: "); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Наступний кут"); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Зміщення по Z"); @@ -181,24 +212,25 @@ namespace Language_uk { PROGMEM Language_Str MSG_UBL_MANUAL_MESH = _UxGT("Ручне введ. сітки"); PROGMEM Language_Str MSG_UBL_BC_INSERT = _UxGT("Розм. шайбу і вимір."); #endif + PROGMEM Language_Str MSG_UBL_MESH_WIZARD = _UxGT("Майстер сіток UBL"); PROGMEM Language_Str MSG_UBL_BC_INSERT2 = _UxGT("Вимірювання"); - PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Видалити і виміряти стіл"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Видалити і виміряти стіл"); + #else + PROGMEM Language_Str MSG_UBL_BC_REMOVE = _UxGT("Видали і вимір. стіл"); + #endif PROGMEM Language_Str MSG_UBL_MOVING_TO_NEXT = _UxGT("Рух до наступної"); PROGMEM Language_Str MSG_UBL_ACTIVATE_MESH = _UxGT("Активувати UBL"); PROGMEM Language_Str MSG_UBL_DEACTIVATE_MESH = _UxGT("Деактивувати UBL"); + PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = LCD_STR_THERMOMETER _UxGT(" столу, ") LCD_STR_DEGREE "C"; + PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Своя ") LCD_STR_THERMOMETER _UxGT(" столу,") LCD_STR_DEGREE "C"; + PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = LCD_STR_THERMOMETER _UxGT(" сопла, ") LCD_STR_DEGREE "C"; + PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Своя ") LCD_STR_THERMOMETER _UxGT(" сопла,") LCD_STR_DEGREE "C"; #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = _UxGT("Температура столу"); - PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = _UxGT("Температура свого столу"); - PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = _UxGT("Температура сопла"); - PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = _UxGT("Температура свого сопла"); PROGMEM Language_Str MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Редагувати свою сітку"); PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("Точне редагування сітки"); PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Будувати свою сітку"); #else - PROGMEM Language_Str MSG_UBL_SET_TEMP_BED = LCD_STR_THERMOMETER _UxGT(" столу, ") LCD_STR_DEGREE "C"; - PROGMEM Language_Str MSG_UBL_BED_TEMP_CUSTOM = LCD_STR_THERMOMETER _UxGT(" столу, ") LCD_STR_DEGREE "C"; - PROGMEM Language_Str MSG_UBL_SET_TEMP_HOTEND = LCD_STR_THERMOMETER _UxGT(" сопла, ") LCD_STR_DEGREE "C"; - PROGMEM Language_Str MSG_UBL_HOTEND_TEMP_CUSTOM = LCD_STR_THERMOMETER _UxGT(" сопла, ") LCD_STR_DEGREE "C"; PROGMEM Language_Str MSG_UBL_EDIT_CUSTOM_MESH = _UxGT("Редагувати свою"); PROGMEM Language_Str MSG_UBL_FINE_TUNE_MESH = _UxGT("Точне редаг. сітки"); PROGMEM Language_Str MSG_UBL_BUILD_CUSTOM_MESH = _UxGT("Будувати свою"); @@ -206,10 +238,8 @@ namespace Language_uk { PROGMEM Language_Str MSG_UBL_MESH_EDIT = _UxGT("Редагування сітки"); PROGMEM Language_Str MSG_UBL_DONE_EDITING_MESH = _UxGT("Сітка побудована"); PROGMEM Language_Str MSG_UBL_BUILD_MESH_MENU = _UxGT("Будувати сітку"); - #if PREHEAT_COUNT - PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Будувати сітку ($)"); - PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Підтвердити ($)"); - #endif + PROGMEM Language_Str MSG_UBL_BUILD_MESH_M = _UxGT("Будувати сітку ($)"); + PROGMEM Language_Str MSG_UBL_VALIDATE_MESH_M = _UxGT("Підтвердити ($)"); PROGMEM Language_Str MSG_UBL_BUILD_COLD_MESH = _UxGT("Буд. холодну сітку"); PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_ADJUST = _UxGT("Встан.висоту сітки"); PROGMEM Language_Str MSG_UBL_MESH_HEIGHT_AMOUNT = _UxGT("Висота"); @@ -219,7 +249,7 @@ namespace Language_uk { PROGMEM Language_Str MSG_G26_HEATING_BED = _UxGT("G26 нагрів столу"); PROGMEM Language_Str MSG_G26_HEATING_NOZZLE = _UxGT("G26 нагрів сопла"); PROGMEM Language_Str MSG_G26_MANUAL_PRIME = _UxGT("Ручне грунтування"); - PROGMEM Language_Str MSG_G26_FIXED_LENGTH = _UxGT("Фікс. довж. грунт."); // ґ is not supported + PROGMEM Language_Str MSG_G26_FIXED_LENGTH = _UxGT("Фікс. довж. грунт."); PROGMEM Language_Str MSG_G26_PRIME_DONE = _UxGT("Грунтув. виконане"); PROGMEM Language_Str MSG_G26_CANCELED = _UxGT("G26 скасовано"); PROGMEM Language_Str MSG_G26_LEAVING = _UxGT("Вийти з G26"); @@ -240,7 +270,7 @@ namespace Language_uk { PROGMEM Language_Str MSG_UBL_OUTPUT_MAP_BACKUP = _UxGT("Зберегти зовні"); PROGMEM Language_Str MSG_UBL_INFO_UBL = _UxGT("Інформація по UBL"); #if LCD_WIDTH > 21 - PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Обсяг заповнювача"); + PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Обсяг заповнюв."); #else PROGMEM Language_Str MSG_UBL_FILLIN_AMOUNT = _UxGT("Обсяг заповн."); #endif @@ -251,12 +281,9 @@ namespace Language_uk { PROGMEM Language_Str MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Анулювати найближчу"); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("Точно налаштувати все"); - #else - PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("Точно налашт. все"); - #endif - #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Точно налашт.найближчу"); #else + PROGMEM Language_Str MSG_UBL_FINE_TUNE_ALL = _UxGT("Точно налашт. все"); PROGMEM Language_Str MSG_UBL_FINE_TUNE_CLOSEST = _UxGT("Точно найближчу"); #endif PROGMEM Language_Str MSG_UBL_STORAGE_MESH_MENU = _UxGT("Збереження сітки"); @@ -300,7 +327,7 @@ namespace Language_uk { #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_NEO2_PRESETS = _UxGT("Передустановка світла #2"); #else - PROGMEM Language_Str MSG_NEO2_PRESETS = _UxGT("Передустан. світла #2"); + PROGMEM Language_Str MSG_NEO2_PRESETS = _UxGT("Передуст. світла #2"); #endif PROGMEM Language_Str MSG_NEO2_BRIGHTNESS = _UxGT("Яскравість"); PROGMEM Language_Str MSG_CUSTOM_LEDS = _UxGT("Своє світло"); @@ -315,6 +342,9 @@ namespace Language_uk { PROGMEM Language_Str MSG_MOVE_X = _UxGT("Рух по X"); PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Рух по Y"); PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Рух по Z"); + PROGMEM Language_Str MSG_MOVE_I = _UxGT("Рух по ") LCD_STR_I; + PROGMEM Language_Str MSG_MOVE_J = _UxGT("Рух по ") LCD_STR_J; + PROGMEM Language_Str MSG_MOVE_K = _UxGT("Рух по ") LCD_STR_K; PROGMEM Language_Str MSG_MOVE_E = _UxGT("Екструдер"); PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Екструдер *"); PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Сопло дуже холодне"); @@ -322,6 +352,7 @@ namespace Language_uk { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Рух 0.1мм"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Рух 1мм"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Рух 10мм"); + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Рух 100mm"); PROGMEM Language_Str MSG_SPEED = _UxGT("Швидкість"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Z Столу"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Сопло, ") LCD_STR_DEGREE "C"; @@ -330,6 +361,14 @@ namespace Language_uk { PROGMEM Language_Str MSG_NOZZLE_STANDBY = _UxGT("Сопло очікує"); PROGMEM Language_Str MSG_BED = _UxGT("Стіл, ") LCD_STR_DEGREE "C"; PROGMEM Language_Str MSG_CHAMBER = _UxGT("Камера,") LCD_STR_DEGREE "C"; + PROGMEM Language_Str MSG_COOLER = _UxGT("Охолодження лазеру"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Перемкнути охолодження"); + #else + PROGMEM Language_Str MSG_COOLER_TOGGLE = _UxGT("Перемкнути охолодж."); + #endif + PROGMEM Language_Str MSG_FLOWMETER_SAFETY = _UxGT("Безпека потоку"); + PROGMEM Language_Str MSG_LASER = _UxGT("Лазер"); PROGMEM Language_Str MSG_FAN_SPEED = _UxGT("Швидк. вент."); PROGMEM Language_Str MSG_FAN_SPEED_N = _UxGT("Швидк. вент. ~"); #if LCD_WIDTH > 21 @@ -339,8 +378,8 @@ namespace Language_uk { PROGMEM Language_Str MSG_STORED_FAN_N = _UxGT("Збереж. вент. ~"); PROGMEM Language_Str MSG_EXTRA_FAN_SPEED_N = _UxGT("Додат.вент. ~"); #endif - PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Вент. контролера"); PROGMEM Language_Str MSG_EXTRA_FAN_SPEED = _UxGT("Дод. швидк. вент."); + PROGMEM Language_Str MSG_CONTROLLER_FAN = _UxGT("Вент. контролера"); PROGMEM Language_Str MSG_CONTROLLER_FAN_IDLE_SPEED = _UxGT("Холості оберти"); PROGMEM Language_Str MSG_CONTROLLER_FAN_AUTO_ON = _UxGT("Авто-режим"); PROGMEM Language_Str MSG_CONTROLLER_FAN_SPEED = _UxGT("Робочі оберти"); @@ -369,6 +408,9 @@ namespace Language_uk { PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-ривок"); PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-ривок"); PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-ривок"); + PROGMEM Language_Str MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-ривок"); + PROGMEM Language_Str MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-ривок"); + PROGMEM Language_Str MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-ривок"); PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-ривок"); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Відхилення вузла"); @@ -379,6 +421,9 @@ namespace Language_uk { PROGMEM Language_Str MSG_VMAX_A = _UxGT("Швидк.макс ") LCD_STR_A; PROGMEM Language_Str MSG_VMAX_B = _UxGT("Швидк.макс ") LCD_STR_B; PROGMEM Language_Str MSG_VMAX_C = _UxGT("Швидк.макс ") LCD_STR_C; + PROGMEM Language_Str MSG_VMAX_I = _UxGT("Швидк.макс ") LCD_STR_I; + PROGMEM Language_Str MSG_VMAX_J = _UxGT("Швидк.макс ") LCD_STR_J; + PROGMEM Language_Str MSG_VMAX_K = _UxGT("Швидк.макс ") LCD_STR_K; PROGMEM Language_Str MSG_VMAX_E = _UxGT("Швидк.макс ") LCD_STR_E; PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Швидк.макс *"); PROGMEM Language_Str MSG_VMIN = _UxGT("Швидк.мін"); @@ -387,6 +432,9 @@ namespace Language_uk { PROGMEM Language_Str MSG_AMAX_A = _UxGT("Приск.макс ") LCD_STR_A; PROGMEM Language_Str MSG_AMAX_B = _UxGT("Приск.макс ") LCD_STR_B; PROGMEM Language_Str MSG_AMAX_C = _UxGT("Приск.макс ") LCD_STR_C; + PROGMEM Language_Str MSG_AMAX_I = _UxGT("Приск.макс ") LCD_STR_I; + PROGMEM Language_Str MSG_AMAX_J = _UxGT("Приск.макс ") LCD_STR_J; + PROGMEM Language_Str MSG_AMAX_K = _UxGT("Приск.макс ") LCD_STR_K; PROGMEM Language_Str MSG_AMAX_E = _UxGT("Приск.макс ") LCD_STR_E; PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Приск.макс *"); PROGMEM Language_Str MSG_A_RETRACT = _UxGT("Приск.втягув."); @@ -397,6 +445,9 @@ namespace Language_uk { PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" кроків/мм"); PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" кроків/мм"); PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" кроків/мм"); + PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" кроків/мм"); + PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" кроків/мм"); + PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" кроків/мм"); PROGMEM Language_Str MSG_E_STEPS = _UxGT("E кроків/мм"); PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* кроків/мм"); PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Температура"); @@ -426,7 +477,7 @@ namespace Language_uk { PROGMEM Language_Str MSG_SETTINGS_STORED = _UxGT("Параметри збережені"); PROGMEM Language_Str MSG_MEDIA_UPDATE = _UxGT("Оновити SD-картку"); PROGMEM Language_Str MSG_RESET_PRINTER = _UxGT("Зкинути принтер"); - PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT(" Поновити"); + PROGMEM Language_Str MSG_REFRESH = LCD_STR_REFRESH _UxGT(" Поновити"); PROGMEM Language_Str MSG_INFO_SCREEN = _UxGT("Головний екран"); PROGMEM Language_Str MSG_PREPARE = _UxGT("Підготувати"); PROGMEM Language_Str MSG_TUNE = _UxGT("Підлаштування"); @@ -472,8 +523,6 @@ namespace Language_uk { #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_CONTROL_RETRACT = _UxGT("Втягування, мм"); PROGMEM Language_Str MSG_CONTROL_RETRACT_SWAP = _UxGT("Зміна втягув.,мм"); - PROGMEM Language_Str MSG_CONTROL_RETRACTF = _UxGT("Ретракт V"); - PROGMEM Language_Str MSG_CONTROL_RETRACT_ZHOP = _UxGT("Стрибок, мм"); PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER = _UxGT("Повернення, мм"); PROGMEM Language_Str MSG_CONTROL_RETRACT_RECOVER_SWAP = _UxGT("Поверн.зміни, мм"); PROGMEM Language_Str MSG_AUTORETRACT = _UxGT("Автовтягування"); @@ -556,6 +605,9 @@ namespace Language_uk { PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Мікрокрок X"); PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Мікрокрок Y"); PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Мікрокрок Z"); + PROGMEM Language_Str MSG_BABYSTEP_I = _UxGT("Мікрокрок ") LCD_STR_I; + PROGMEM Language_Str MSG_BABYSTEP_J = _UxGT("Мікрокрок ") LCD_STR_J; + PROGMEM Language_Str MSG_BABYSTEP_K = _UxGT("Мікрокрок ") LCD_STR_K; PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Сумарно"); PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Кінцевик спрацював"); PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Збій нагріву"); @@ -563,7 +615,13 @@ namespace Language_uk { PROGMEM Language_Str MSG_THERMAL_RUNAWAY = _UxGT("ВИТІК ТЕПЛА"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_BED = _UxGT("ВИТІК ТЕПЛА СТОЛУ"); PROGMEM Language_Str MSG_THERMAL_RUNAWAY_CHAMBER = _UxGT("ВИТІК ТЕПЛА КАМЕРИ"); - PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("МАКСИМАЛЬНА Т"); + PROGMEM Language_Str MSG_THERMAL_RUNAWAY_COOLER = _UxGT("ВИТІК ОХОЛОДЖЕННЯ"); + #if LCD_WIDTH >= 20 + PROGMEM Language_Str MSG_COOLING_FAILED = _UxGT("ОХОЛОДЖЕННЯ НЕ ВДАЛОСЬ"); + #else + PROGMEM Language_Str MSG_COOLING_FAILED = _UxGT("ОХОЛОДЖ. НЕ ВДАЛОСЬ"); + #endif + PROGMEM Language_Str MSG_ERR_MAXTEMP = _UxGT("МАКСИМАЛЬНА Т") LCD_STR_DEGREE; PROGMEM Language_Str MSG_ERR_MINTEMP = _UxGT("МІНІМАЛЬНА Т") LCD_STR_DEGREE; PROGMEM Language_Str MSG_HALTED = _UxGT("ПРИНТЕР ЗУПИНЕНО"); PROGMEM Language_Str MSG_PLEASE_RESET = _UxGT("Перезавантажте"); @@ -573,18 +631,20 @@ namespace Language_uk { PROGMEM Language_Str MSG_HEATING = _UxGT("Нагрівання..."); PROGMEM Language_Str MSG_COOLING = _UxGT("Охолодження..."); PROGMEM Language_Str MSG_BED_HEATING = _UxGT("Нагрів столу..."); - PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Нагрів камери..."); PROGMEM Language_Str MSG_PROBE_HEATING = _UxGT("Нагрів зонду..."); - PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Калібрування Delta"); + PROGMEM Language_Str MSG_CHAMBER_HEATING = _UxGT("Нагрів камери..."); #if LCD_WIDTH >= 20 PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Охолодження столу..."); - PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Охолодження камери..."); PROGMEM Language_Str MSG_PROBE_COOLING = _UxGT("Охолодження зонду..."); + PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Охолодження камери..."); + PROGMEM Language_Str MSG_LASER_COOLING = _UxGT("Охолодження лазеру..."); #else - PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Охол. столу..."); - PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Охол. камери..."); - PROGMEM Language_Str MSG_PROBE_COOLING = _UxGT("Охол. зонду..."); + PROGMEM Language_Str MSG_BED_COOLING = _UxGT("Охолодж. столу..."); + PROGMEM Language_Str MSG_PROBE_COOLING = _UxGT("Охолодж. зонду..."); + PROGMEM Language_Str MSG_CHAMBER_COOLING = _UxGT("Охолодж. камери..."); + PROGMEM Language_Str MSG_LASER_COOLING = _UxGT("Охолодж. лазеру..."); #endif + PROGMEM Language_Str MSG_DELTA_CALIBRATE = _UxGT("Калібрування Delta"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_X = _UxGT("Калібрувати X"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_Y = _UxGT("Калібрувати Y"); PROGMEM Language_Str MSG_DELTA_CALIBRATE_Z = _UxGT("Калібрувати Z"); @@ -611,6 +671,11 @@ namespace Language_uk { #endif PROGMEM Language_Str MSG_UBL_LEVELING = _UxGT("UBL"); PROGMEM Language_Str MSG_MESH_LEVELING = _UxGT("Вирівнювання сітки"); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Зондування сітки виконано"); + #else + PROGMEM Language_Str MSG_MESH_DONE = _UxGT("Зондування виконано"); + #endif PROGMEM Language_Str MSG_INFO_STATS_MENU = _UxGT("Статистика принтера"); PROGMEM Language_Str MSG_INFO_BOARD_MENU = _UxGT("Про плату"); @@ -651,6 +716,9 @@ namespace Language_uk { PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("Драйвер X, %"); PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Драйвер Y, %"); PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Драйвер Z, %"); + PROGMEM Language_Str MSG_DAC_PERCENT_I = _UxGT("Драйвер ") AXIS4_STR _UxGT(", %"); + PROGMEM Language_Str MSG_DAC_PERCENT_J = _UxGT("Драйвер ") AXIS5_STR _UxGT(", %"); + PROGMEM Language_Str MSG_DAC_PERCENT_K = _UxGT("Драйвер ") AXIS6_STR _UxGT(", %"); PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("Драйвер E, %"); PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("ЗБІЙ ЗВ'ЯЗКУ З TMC"); PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("Запис ЦАП у EEPROM"); @@ -687,19 +755,19 @@ namespace Language_uk { #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("MMU Завантажити в сопло"); #else - PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("MMU Завантаж. в сопло"); + PROGMEM Language_Str MSG_MMU2_LOAD_TO_NOZZLE = _UxGT("MMU Завант. в сопло"); #endif PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT = _UxGT("MMU Звільнити"); PROGMEM Language_Str MSG_MMU2_EJECT_FILAMENT_N = _UxGT("MMU Звільнити ~"); PROGMEM Language_Str MSG_MMU2_UNLOAD_FILAMENT = _UxGT("MMU Вивантажити"); - PROGMEM Language_Str MSG_MMU2_LOADING_FILAMENT = _UxGT("MMU Завантаж. %i..."); - PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("MMU Звільнення..."); - PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("MMU Вивантаження..."); - PROGMEM Language_Str MSG_MMU2_ALL = _UxGT("MMU Все"); - PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("MMU Пруток ~"); - PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("MMU Перезапуск"); + PROGMEM Language_Str MSG_MMU2_LOADING_FILAMENT = _UxGT("Завантаж. %i..."); + PROGMEM Language_Str MSG_MMU2_EJECTING_FILAMENT = _UxGT("Викидання прутка..."); + PROGMEM Language_Str MSG_MMU2_UNLOADING_FILAMENT = _UxGT("Вивантаження..."); + PROGMEM Language_Str MSG_MMU2_ALL = _UxGT("Все"); + PROGMEM Language_Str MSG_MMU2_FILAMENT_N = _UxGT("Пруток ~"); + PROGMEM Language_Str MSG_MMU2_RESET = _UxGT("Перезапуск MMU"); PROGMEM Language_Str MSG_MMU2_RESETTING = _UxGT("MMU Перезапуск..."); - PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("MMU Видаліть, натисніть"); + PROGMEM Language_Str MSG_MMU2_EJECT_RECOVER = _UxGT("Видаліть, натисніть"); #if LCD_WIDTH > 21 PROGMEM Language_Str MSG_MIX = _UxGT("Змішування"); @@ -710,7 +778,11 @@ namespace Language_uk { PROGMEM Language_Str MSG_MIXER = _UxGT("Змішувач"); PROGMEM Language_Str MSG_GRADIENT = _UxGT("Градієнт"); PROGMEM Language_Str MSG_FULL_GRADIENT = _UxGT("Повний градієнт"); - PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("Змішування переключ."); + #if LCD_WIDTH > 21 + PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("Переключити змішування"); + #else + PROGMEM Language_Str MSG_TOGGLE_MIX = _UxGT("Переключ.змішування"); + #endif PROGMEM Language_Str MSG_CYCLE_MIX = _UxGT("Циклічне змішування"); PROGMEM Language_Str MSG_GRADIENT_MIX = _UxGT("Градієнт змішування"); PROGMEM Language_Str MSG_REVERSE_GRADIENT = _UxGT("Змінити градієнт"); @@ -721,14 +793,13 @@ namespace Language_uk { PROGMEM Language_Str MSG_RESET_VTOOLS = _UxGT("Зкидання В-інструментів"); #else PROGMEM Language_Str MSG_ACTIVE_VTOOL = _UxGT("Актив. В-інструм."); - PROGMEM Language_Str MSG_GRADIENT_ALIAS = _UxGT("Псевдонім В-інструм."); + PROGMEM Language_Str MSG_GRADIENT_ALIAS = _UxGT("Псевдонім В-інструм"); PROGMEM Language_Str MSG_RESET_VTOOLS = _UxGT("Зкидання В-інструм."); #endif PROGMEM Language_Str MSG_START_VTOOL = _UxGT("Початок В-інструменту"); PROGMEM Language_Str MSG_END_VTOOL = _UxGT("Кінець В-інструменту"); PROGMEM Language_Str MSG_COMMIT_VTOOL = _UxGT("Змішати В-інструменти"); PROGMEM Language_Str MSG_VTOOLS_RESET = _UxGT("В-інструменти зкинуті"); - PROGMEM Language_Str MSG_START_Z = _UxGT("Початок Z:"); PROGMEM Language_Str MSG_END_Z = _UxGT(" Кінець Z:"); @@ -756,12 +827,12 @@ namespace Language_uk { PROGMEM Language_Str MSG_REMINDER_SAVE_SETTINGS = _UxGT("Не забудь зберегти!"); PROGMEM Language_Str MSG_PASSWORD_REMOVED = _UxGT("Пароль видалений"); - PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Паркування...")); // // Filament Change screens show up to 3 lines on a 4-line display // ...or up to 2 lines on a 3-line display // + PROGMEM Language_Str MSG_PAUSE_PRINT_PARKING = _UxGT(MSG_1_LINE("Паркування...")); #if LCD_HEIGHT >= 4 // Up to 3 lines allowed PROGMEM Language_Str MSG_ADVANCED_PAUSE_WAITING = _UxGT(MSG_3_LINE("Натисніть кнопку", "для продовження", "друку")); @@ -828,6 +899,11 @@ namespace Language_uk { PROGMEM Language_Str MSG_BOTTOM_RIGHT = _UxGT("Нижній правий"); PROGMEM Language_Str MSG_CALIBRATION_COMPLETED = _UxGT("Калібрування успішне"); PROGMEM Language_Str MSG_CALIBRATION_FAILED = _UxGT("Збій калібрування"); + + PROGMEM Language_Str MSG_DRIVER_BACKWARD = _UxGT(" драйвер назад"); + + PROGMEM Language_Str MSG_SD_CARD = _UxGT("SD Картка"); + PROGMEM Language_Str MSG_USB_DISK = _UxGT("USB Диск"); } #if FAN_COUNT == 1 diff --git a/Marlin/src/lcd/language/language_vi.h b/Marlin/src/lcd/language/language_vi.h index f0b7f732ed8d8..825666d1e1d79 100644 --- a/Marlin/src/lcd/language/language_vi.h +++ b/Marlin/src/lcd/language/language_vi.h @@ -205,6 +205,7 @@ namespace Language_vi { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Di chuyển 0.1mm"); // Move 0.1mm PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Di chuyển 1mm"); // Move 1mm PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Di chuyển 10mm"); // Move 10mm + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("Di chuyển 100mm"); // Move 100mm PROGMEM Language_Str MSG_SPEED = _UxGT("Tốc độ"); // Speed PROGMEM Language_Str MSG_BED_Z = _UxGT("Z Bàn"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Đầu phun"); // Nozzle diff --git a/Marlin/src/lcd/language/language_zh_CN.h b/Marlin/src/lcd/language/language_zh_CN.h index 98f7704efc79e..39093a7c6c51d 100644 --- a/Marlin/src/lcd/language/language_zh_CN.h +++ b/Marlin/src/lcd/language/language_zh_CN.h @@ -230,6 +230,7 @@ namespace Language_zh_CN { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("移动 0.1 mm"); //"Move 0.1mm" PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("移动 1 mm"); //"Move 1mm" PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("移动 10 mm"); //"Move 10mm" + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("移动 100 mm"); //"Move 100mm" PROGMEM Language_Str MSG_SPEED = _UxGT("速率"); //"Speed" PROGMEM Language_Str MSG_BED_Z = _UxGT("热床Z"); //"Bed Z" PROGMEM Language_Str MSG_NOZZLE = _UxGT("喷嘴"); //"Nozzle" 噴嘴 diff --git a/Marlin/src/lcd/language/language_zh_TW.h b/Marlin/src/lcd/language/language_zh_TW.h index 0ada34a47693c..2061a66ad8bdd 100644 --- a/Marlin/src/lcd/language/language_zh_TW.h +++ b/Marlin/src/lcd/language/language_zh_TW.h @@ -223,11 +223,12 @@ namespace Language_zh_TW { PROGMEM Language_Str MSG_MOVE_Z = _UxGT("移動Z"); //"Move Z" PROGMEM Language_Str MSG_MOVE_E = _UxGT("擠出機"); //"Extruder" PROGMEM Language_Str MSG_MOVE_EN = _UxGT("擠出機 *"); //"Extruder *" - PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("噴嘴溫度不夠"); //"Hotend too cold" + PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("噴嘴溫度不夠"); //"Hotend too cold" PROGMEM Language_Str MSG_MOVE_N_MM = _UxGT("移動 %s mm"); //"Move 0.025mm" - PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("移動 0.1 mm"); //"Move 0.1mm" - PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("移動 1 mm"); //"Move 1mm" + PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("移動 0.1 mm"); //"Move 0.1mm" + PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("移動 1 mm"); //"Move 1mm" PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("移動 10 mm"); //"Move 10mm" + PROGMEM Language_Str MSG_MOVE_100MM = _UxGT("移動 100 mm"); //"Move 100mm" PROGMEM Language_Str MSG_SPEED = _UxGT("速率"); //"Speed" PROGMEM Language_Str MSG_BED_Z = _UxGT("熱床Z"); //"Bed Z" PROGMEM Language_Str MSG_NOZZLE = " " LCD_STR_THERMOMETER _UxGT(" 噴嘴"); //"Nozzle" 噴嘴 diff --git a/Marlin/src/lcd/lcdprint.cpp b/Marlin/src/lcd/lcdprint.cpp index 32f425168f8d0..c421ef1a03300 100644 --- a/Marlin/src/lcd/lcdprint.cpp +++ b/Marlin/src/lcd/lcdprint.cpp @@ -41,6 +41,7 @@ * * displays 'E1'...'E11' for indexes 0 - 10 (By default. Uses LCD_FIRST_TOOL) */ lcd_uint_t lcd_put_u8str_ind_P(PGM_P const pstr, const int8_t ind, PGM_P const inStr/*=nullptr*/, const lcd_uint_t maxlen/*=LCD_WIDTH*/) { + const uint8_t prop = USE_WIDE_GLYPH ? 2 : 1; uint8_t *p = (uint8_t*)pstr; int8_t n = maxlen; while (n > 0) { @@ -73,10 +74,27 @@ lcd_uint_t lcd_put_u8str_ind_P(PGM_P const pstr, const int8_t ind, PGM_P const i } else { lcd_put_wchar(ch); - n--; + n -= ch > 255 ? prop : 1; } } return n; } +// Calculate UTF8 width with a simple check +int calculateWidth(PGM_P const pstr) { + if (!USE_WIDE_GLYPH) return utf8_strlen_P(pstr) * MENU_FONT_WIDTH; + const uint8_t prop = 2; + uint8_t *p = (uint8_t*)pstr; + int n = 0; + + do { + wchar_t ch; + p = get_utf8_value_cb(p, read_byte_rom, &ch); + if (!ch) break; + n += (ch > 255) ? prop : 1; + } while (1); + + return n * MENU_FONT_WIDTH; +} + #endif // HAS_WIRED_LCD diff --git a/Marlin/src/lcd/lcdprint.h b/Marlin/src/lcd/lcdprint.h index fe856535b0ea1..105a66085f3a9 100644 --- a/Marlin/src/lcd/lcdprint.h +++ b/Marlin/src/lcd/lcdprint.h @@ -172,3 +172,5 @@ inline int lcd_put_wchar(const lcd_uint_t col, const lcd_uint_t row, const wchar lcd_moveto(col, row); return lcd_put_wchar(c); } + +int calculateWidth(PGM_P const pstr); diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 14959851fa34c..a9d4241cba29e 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -120,1181 +120,1169 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; } #endif -#if HAS_WIRED_LCD - -#if HAS_MARLINUI_U8GLIB - #include "dogm/marlinui_DOGM.h" +#if EITHER(HAS_LCD_MENU, EXTENSIBLE_UI) + bool MarlinUI::lcd_clicked; #endif -#include "lcdprint.h" - -#include "../sd/cardreader.h" - -#include "../module/temperature.h" -#include "../module/planner.h" -#include "../module/motion.h" - -#if HAS_LCD_MENU - #include "../module/settings.h" -#endif +#if HAS_WIRED_LCD -#if ENABLED(AUTO_BED_LEVELING_UBL) - #include "../feature/bedlevel/bedlevel.h" -#endif + #if HAS_MARLINUI_U8GLIB + #include "dogm/marlinui_DOGM.h" + #endif -#if HAS_TRINAMIC_CONFIG - #include "../feature/tmc_util.h" -#endif + #include "lcdprint.h" -#if HAS_ADC_BUTTONS - #include "../module/thermistor/thermistors.h" -#endif + #include "../sd/cardreader.h" -#if HAS_POWER_MONITOR - #include "../feature/power_monitor.h" -#endif + #include "../module/temperature.h" + #include "../module/planner.h" + #include "../module/motion.h" -#if HAS_ENCODER_ACTION - volatile uint8_t MarlinUI::buttons; - #if HAS_SLOW_BUTTONS - volatile uint8_t MarlinUI::slow_buttons; + #if HAS_LCD_MENU + #include "../module/settings.h" #endif - #if HAS_TOUCH_BUTTONS - #include "touch/touch_buttons.h" - bool MarlinUI::on_edit_screen = false; + + #if ENABLED(AUTO_BED_LEVELING_UBL) + #include "../feature/bedlevel/bedlevel.h" #endif -#endif -#if HAS_LCD_MENU && LCD_TIMEOUT_TO_STATUS > 0 - bool MarlinUI::defer_return_to_status; -#endif + #if HAS_TRINAMIC_CONFIG + #include "../feature/tmc_util.h" + #endif -uint8_t MarlinUI::lcd_status_update_delay = 1; // First update one loop delayed + #if HAS_ADC_BUTTONS + #include "../module/thermistor/thermistors.h" + #endif -#if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) - millis_t MarlinUI::next_filament_display; // = 0 -#endif + #if HAS_POWER_MONITOR + #include "../feature/power_monitor.h" + #endif -millis_t MarlinUI::next_button_update_ms; // = 0 + #if HAS_ENCODER_ACTION + volatile uint8_t MarlinUI::buttons; + #if HAS_SLOW_BUTTONS + volatile uint8_t MarlinUI::slow_buttons; + #endif + #if HAS_TOUCH_BUTTONS + #include "touch/touch_buttons.h" + bool MarlinUI::on_edit_screen = false; + #endif + #endif -#if HAS_MARLINUI_U8GLIB - bool MarlinUI::drawing_screen, MarlinUI::first_page; // = false -#endif + #if SCREENS_CAN_TIME_OUT + bool MarlinUI::defer_return_to_status; + millis_t MarlinUI::return_to_status_ms = 0; + #endif -// Encoder Handling -#if HAS_ENCODER_ACTION - uint32_t MarlinUI::encoderPosition; - volatile int8_t encoderDiff; // Updated in update_buttons, added to encoderPosition every LCD update -#endif + uint8_t MarlinUI::lcd_status_update_delay = 1; // First update one loop delayed -#if ENABLED(SDSUPPORT) + #if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) + millis_t MarlinUI::next_filament_display; // = 0 + #endif - #include "../sd/cardreader.h" + millis_t MarlinUI::next_button_update_ms; // = 0 - #if MARLINUI_SCROLL_NAME - uint8_t MarlinUI::filename_scroll_pos, MarlinUI::filename_scroll_max; + #if HAS_MARLINUI_U8GLIB + bool MarlinUI::drawing_screen, MarlinUI::first_page; // = false #endif - const char * MarlinUI::scrolled_filename(CardReader &theCard, const uint8_t maxlen, uint8_t hash, const bool doScroll) { - const char *outstr = theCard.longest_filename(); - if (theCard.longFilename[0]) { - #if MARLINUI_SCROLL_NAME - if (doScroll) { - for (uint8_t l = FILENAME_LENGTH; l--;) - hash = ((hash << 1) | (hash >> 7)) ^ theCard.filename[l]; // rotate, xor - static uint8_t filename_scroll_hash; - if (filename_scroll_hash != hash) { // If the hash changed... - filename_scroll_hash = hash; // Save the new hash - filename_scroll_max = _MAX(0, utf8_strlen(theCard.longFilename) - maxlen); // Update the scroll limit - filename_scroll_pos = 0; // Reset scroll to the start - lcd_status_update_delay = 8; // Don't scroll right away - } - // Advance byte position corresponding to filename_scroll_pos char position - outstr += TERN(UTF_FILENAME_SUPPORT, utf8_byte_pos_by_char_num(outstr, filename_scroll_pos), filename_scroll_pos); - } - #else - theCard.longFilename[ - TERN(UTF_FILENAME_SUPPORT, utf8_byte_pos_by_char_num(theCard.longFilename, maxlen), maxlen) - ] = '\0'; // cutoff at screen edge - #endif - } - return outstr; - } + // Encoder Handling + #if HAS_ENCODER_ACTION + uint32_t MarlinUI::encoderPosition; + volatile int8_t encoderDiff; // Updated in update_buttons, added to encoderPosition every LCD update + #endif -#endif + #if ENABLED(SDSUPPORT) -#if HAS_LCD_MENU - #include "menu/menu.h" + #include "../sd/cardreader.h" - screenFunc_t MarlinUI::currentScreen; // Initialized in CTOR - bool MarlinUI::screen_changed; + #if MARLINUI_SCROLL_NAME + uint8_t MarlinUI::filename_scroll_pos, MarlinUI::filename_scroll_max; + #endif - #if ENABLED(ENCODER_RATE_MULTIPLIER) - bool MarlinUI::encoderRateMultiplierEnabled; - millis_t MarlinUI::lastEncoderMovementMillis = 0; - void MarlinUI::enable_encoder_multiplier(const bool onoff) { - encoderRateMultiplierEnabled = onoff; - lastEncoderMovementMillis = 0; + const char * MarlinUI::scrolled_filename(CardReader &theCard, const uint8_t maxlen, uint8_t hash, const bool doScroll) { + const char *outstr = theCard.longest_filename(); + if (theCard.longFilename[0]) { + #if MARLINUI_SCROLL_NAME + if (doScroll) { + for (uint8_t l = FILENAME_LENGTH; l--;) + hash = ((hash << 1) | (hash >> 7)) ^ theCard.filename[l]; // rotate, xor + static uint8_t filename_scroll_hash; + if (filename_scroll_hash != hash) { // If the hash changed... + filename_scroll_hash = hash; // Save the new hash + filename_scroll_max = _MAX(0, utf8_strlen(theCard.longFilename) - maxlen); // Update the scroll limit + filename_scroll_pos = 0; // Reset scroll to the start + lcd_status_update_delay = 8; // Don't scroll right away + } + // Advance byte position corresponding to filename_scroll_pos char position + outstr += TERN(UTF_FILENAME_SUPPORT, utf8_byte_pos_by_char_num(outstr, filename_scroll_pos), filename_scroll_pos); + } + #else + theCard.longFilename[ + TERN(UTF_FILENAME_SUPPORT, utf8_byte_pos_by_char_num(theCard.longFilename, maxlen), maxlen) + ] = '\0'; // cutoff at screen edge + #endif + } + return outstr; } - #endif - #if EITHER(REVERSE_MENU_DIRECTION, REVERSE_SELECT_DIRECTION) - int8_t MarlinUI::encoderDirection = ENCODERBASE; #endif - #if HAS_TOUCH_BUTTONS - uint8_t MarlinUI::touch_buttons; - uint8_t MarlinUI::repeat_delay; - #endif - - bool MarlinUI::lcd_clicked; + #if HAS_LCD_MENU + #include "menu/menu.h" - bool MarlinUI::use_click() { - const bool click = lcd_clicked; - lcd_clicked = false; - return click; - } + screenFunc_t MarlinUI::currentScreen; // Initialized in CTOR + bool MarlinUI::screen_changed; - #if EITHER(AUTO_BED_LEVELING_UBL, G26_MESH_VALIDATION) + #if ENABLED(ENCODER_RATE_MULTIPLIER) + bool MarlinUI::encoderRateMultiplierEnabled; + millis_t MarlinUI::lastEncoderMovementMillis = 0; + void MarlinUI::enable_encoder_multiplier(const bool onoff) { + encoderRateMultiplierEnabled = onoff; + lastEncoderMovementMillis = 0; + } + #endif - bool MarlinUI::external_control; // = false + #if EITHER(REVERSE_MENU_DIRECTION, REVERSE_SELECT_DIRECTION) + int8_t MarlinUI::encoderDirection = ENCODERBASE; + #endif - void MarlinUI::wait_for_release() { - while (button_pressed()) safe_delay(50); - safe_delay(50); - } + #if HAS_TOUCH_BUTTONS + uint8_t MarlinUI::touch_buttons; + uint8_t MarlinUI::repeat_delay; + #endif - #endif + #if EITHER(AUTO_BED_LEVELING_UBL, G26_MESH_VALIDATION) - #if !HAS_GRAPHICAL_TFT + bool MarlinUI::external_control; // = false - void _wrap_string(uint8_t &col, uint8_t &row, const char * const string, read_byte_cb_t cb_read_byte, bool wordwrap/*=false*/) { - SETCURSOR(col, row); - if (!string) return; + void MarlinUI::wait_for_release() { + while (button_pressed()) safe_delay(50); + safe_delay(50); + } - auto _newline = [&col, &row]{ - col = 0; row++; // Move col to string len (plus space) - SETCURSOR(0, row); // Simulate carriage return - }; + #endif - uint8_t *p = (uint8_t*)string; - wchar_t ch; - if (wordwrap) { - uint8_t *wrd = nullptr, c = 0; - // find the end of the part - for (;;) { - if (!wrd) wrd = p; // Get word start /before/ advancing - p = get_utf8_value_cb(p, cb_read_byte, &ch); - const bool eol = !ch; // zero ends the string - // End or a break between phrases? - if (eol || ch == ' ' || ch == '-' || ch == '+' || ch == '.') { - if (!c && ch == ' ') { if (wrd) wrd++; continue; } // collapse extra spaces - // Past the right and the word is not too long? - if (col + c > LCD_WIDTH && col >= (LCD_WIDTH) / 4) _newline(); // should it wrap? - c += !eol; // +1 so the space will be printed - col += c; // advance col to new position - while (c) { // character countdown - --c; // count down to zero - wrd = get_utf8_value_cb(wrd, cb_read_byte, &ch); // get characters again - lcd_put_wchar(ch); // character to the LCD + #if !HAS_GRAPHICAL_TFT + + void _wrap_string(uint8_t &col, uint8_t &row, const char * const string, read_byte_cb_t cb_read_byte, bool wordwrap/*=false*/) { + SETCURSOR(col, row); + if (!string) return; + + auto _newline = [&col, &row]{ + col = 0; row++; // Move col to string len (plus space) + SETCURSOR(0, row); // Simulate carriage return + }; + + uint8_t *p = (uint8_t*)string; + wchar_t ch; + if (wordwrap) { + uint8_t *wrd = nullptr, c = 0; + // find the end of the part + for (;;) { + if (!wrd) wrd = p; // Get word start /before/ advancing + p = get_utf8_value_cb(p, cb_read_byte, &ch); + const bool eol = !ch; // zero ends the string + // End or a break between phrases? + if (eol || ch == ' ' || ch == '-' || ch == '+' || ch == '.') { + if (!c && ch == ' ') { if (wrd) wrd++; continue; } // collapse extra spaces + // Past the right and the word is not too long? + if (col + c > LCD_WIDTH && col >= (LCD_WIDTH) / 4) _newline(); // should it wrap? + c += !eol; // +1 so the space will be printed + col += c; // advance col to new position + while (c) { // character countdown + --c; // count down to zero + wrd = get_utf8_value_cb(wrd, cb_read_byte, &ch); // get characters again + lcd_put_wchar(ch); // character to the LCD + } + if (eol) break; // all done! + wrd = nullptr; // set up for next word } - if (eol) break; // all done! - wrd = nullptr; // set up for next word + else c++; // count word characters } - else c++; // count word characters } - } - else { - for (;;) { - p = get_utf8_value_cb(p, cb_read_byte, &ch); - if (!ch) break; - lcd_put_wchar(ch); - col++; - if (col >= LCD_WIDTH) _newline(); + else { + for (;;) { + p = get_utf8_value_cb(p, cb_read_byte, &ch); + if (!ch) break; + lcd_put_wchar(ch); + col++; + if (col >= LCD_WIDTH) _newline(); + } } } - } - void MarlinUI::draw_select_screen_prompt(PGM_P const pref, const char * const string/*=nullptr*/, PGM_P const suff/*=nullptr*/) { - const uint8_t plen = utf8_strlen_P(pref), slen = suff ? utf8_strlen_P(suff) : 0; - uint8_t col = 0, row = 0; - if (!string && plen + slen <= LCD_WIDTH) { - col = (LCD_WIDTH - plen - slen) / 2; - row = LCD_HEIGHT > 3 ? 1 : 0; - } - wrap_string_P(col, row, pref, true); - if (string) { - if (col) { col = 0; row++; } // Move to the start of the next line - wrap_string(col, row, string); + void MarlinUI::draw_select_screen_prompt(PGM_P const pref, const char * const string/*=nullptr*/, PGM_P const suff/*=nullptr*/) { + const uint8_t plen = utf8_strlen_P(pref), slen = suff ? utf8_strlen_P(suff) : 0; + uint8_t col = 0, row = 0; + if (!string && plen + slen <= LCD_WIDTH) { + col = (LCD_WIDTH - plen - slen) / 2; + row = LCD_HEIGHT > 3 ? 1 : 0; + } + wrap_string_P(col, row, pref, true); + if (string) { + if (col) { col = 0; row++; } // Move to the start of the next line + wrap_string(col, row, string); + } + if (suff) wrap_string_P(col, row, suff); } - if (suff) wrap_string_P(col, row, suff); - } - #endif // !HAS_GRAPHICAL_TFT + #endif // !HAS_GRAPHICAL_TFT -#endif // HAS_LCD_MENU + #endif // HAS_LCD_MENU -void MarlinUI::init() { + void MarlinUI::init() { - init_lcd(); + init_lcd(); - #if HAS_DIGITAL_BUTTONS - #if BUTTON_EXISTS(EN1) - SET_INPUT_PULLUP(BTN_EN1); - #endif - #if BUTTON_EXISTS(EN2) - SET_INPUT_PULLUP(BTN_EN2); - #endif - #if BUTTON_EXISTS(ENC) - SET_INPUT_PULLUP(BTN_ENC); - #endif - #if BUTTON_EXISTS(ENC_EN) - SET_INPUT_PULLUP(BTN_ENC_EN); - #endif - #if BUTTON_EXISTS(BACK) - SET_INPUT_PULLUP(BTN_BACK); - #endif - #if BUTTON_EXISTS(UP) - SET_INPUT(BTN_UP); - #endif - #if BUTTON_EXISTS(DWN) - SET_INPUT(BTN_DWN); - #endif - #if BUTTON_EXISTS(LFT) - SET_INPUT(BTN_LFT); - #endif - #if BUTTON_EXISTS(RT) - SET_INPUT(BTN_RT); + #if HAS_DIGITAL_BUTTONS + #if BUTTON_EXISTS(EN1) + SET_INPUT_PULLUP(BTN_EN1); + #endif + #if BUTTON_EXISTS(EN2) + SET_INPUT_PULLUP(BTN_EN2); + #endif + #if BUTTON_EXISTS(ENC) + SET_INPUT_PULLUP(BTN_ENC); + #endif + #if BUTTON_EXISTS(ENC_EN) + SET_INPUT_PULLUP(BTN_ENC_EN); + #endif + #if BUTTON_EXISTS(BACK) + SET_INPUT_PULLUP(BTN_BACK); + #endif + #if BUTTON_EXISTS(UP) + SET_INPUT(BTN_UP); + #endif + #if BUTTON_EXISTS(DWN) + SET_INPUT(BTN_DWN); + #endif + #if BUTTON_EXISTS(LFT) + SET_INPUT(BTN_LFT); + #endif + #if BUTTON_EXISTS(RT) + SET_INPUT(BTN_RT); + #endif #endif - #endif - #if HAS_SHIFT_ENCODER + #if HAS_SHIFT_ENCODER - #if ENABLED(SR_LCD_2W_NL) // Non latching 2 wire shift register + #if ENABLED(SR_LCD_2W_NL) // Non latching 2 wire shift register - SET_OUTPUT(SR_DATA_PIN); - SET_OUTPUT(SR_CLK_PIN); + SET_OUTPUT(SR_DATA_PIN); + SET_OUTPUT(SR_CLK_PIN); - #elif PIN_EXISTS(SHIFT_CLK) + #elif PIN_EXISTS(SHIFT_CLK) - SET_OUTPUT(SHIFT_CLK_PIN); - OUT_WRITE(SHIFT_LD_PIN, HIGH); - #if PIN_EXISTS(SHIFT_EN) - OUT_WRITE(SHIFT_EN_PIN, LOW); - #endif - SET_INPUT_PULLUP(SHIFT_OUT_PIN); + SET_OUTPUT(SHIFT_CLK_PIN); + OUT_WRITE(SHIFT_LD_PIN, HIGH); + #if PIN_EXISTS(SHIFT_EN) + OUT_WRITE(SHIFT_EN_PIN, LOW); + #endif + SET_INPUT_PULLUP(SHIFT_OUT_PIN); - #endif + #endif - #endif // HAS_SHIFT_ENCODER + #endif // HAS_SHIFT_ENCODER - #if BOTH(HAS_ENCODER_ACTION, HAS_SLOW_BUTTONS) - slow_buttons = 0; - #endif + #if BOTH(HAS_ENCODER_ACTION, HAS_SLOW_BUTTONS) + slow_buttons = 0; + #endif - update_buttons(); + update_buttons(); - TERN_(HAS_ENCODER_ACTION, encoderDiff = 0); -} + TERN_(HAS_ENCODER_ACTION, encoderDiff = 0); + } -bool MarlinUI::get_blink() { - static uint8_t blink = 0; - static millis_t next_blink_ms = 0; - millis_t ms = millis(); - if (ELAPSED(ms, next_blink_ms)) { - blink ^= 0xFF; - next_blink_ms = ms + 1000 - (LCD_UPDATE_INTERVAL) / 2; + bool MarlinUI::get_blink() { + static uint8_t blink = 0; + static millis_t next_blink_ms = 0; + millis_t ms = millis(); + if (ELAPSED(ms, next_blink_ms)) { + blink ^= 0xFF; + next_blink_ms = ms + 1000 - (LCD_UPDATE_INTERVAL) / 2; + } + return blink != 0; } - return blink != 0; -} -//////////////////////////////////////////// -///////////// Keypad Handling ////////////// -//////////////////////////////////////////// + //////////////////////////////////////////// + ///////////// Keypad Handling ////////////// + //////////////////////////////////////////// -#if IS_RRW_KEYPAD && HAS_ENCODER_ACTION + #if IS_RRW_KEYPAD && HAS_ENCODER_ACTION - volatile uint8_t MarlinUI::keypad_buttons; + volatile uint8_t MarlinUI::keypad_buttons; - #if HAS_LCD_MENU && !HAS_ADC_BUTTONS + #if HAS_LCD_MENU && !HAS_ADC_BUTTONS - void lcd_move_x(); - void lcd_move_y(); - void lcd_move_z(); + void lcd_move_x(); + void lcd_move_y(); + void lcd_move_z(); - void _reprapworld_keypad_move(const AxisEnum axis, const int16_t dir) { - ui.manual_move.menu_scale = REPRAPWORLD_KEYPAD_MOVE_STEP; - ui.encoderPosition = dir; - switch (axis) { - case X_AXIS: lcd_move_x(); break; - case Y_AXIS: lcd_move_y(); break; - case Z_AXIS: lcd_move_z(); - default: break; + void _reprapworld_keypad_move(const AxisEnum axis, const int16_t dir) { + ui.manual_move.menu_scale = REPRAPWORLD_KEYPAD_MOVE_STEP; + ui.encoderPosition = dir; + switch (axis) { + case X_AXIS: lcd_move_x(); break; + case Y_AXIS: lcd_move_y(); break; + case Z_AXIS: lcd_move_z(); + default: break; + } } - } - #endif + #endif - bool MarlinUI::handle_keypad() { + bool MarlinUI::handle_keypad() { - #if HAS_ADC_BUTTONS + #if HAS_ADC_BUTTONS - #define ADC_MIN_KEY_DELAY 100 - if (keypad_buttons) { - #if HAS_ENCODER_ACTION - refresh(LCDVIEW_REDRAW_NOW); - #if HAS_LCD_MENU - if (encoderDirection == -(ENCODERBASE)) { // HAS_ADC_BUTTONS forces REVERSE_MENU_DIRECTION, so this indicates menu navigation - if (RRK(EN_KEYPAD_UP)) encoderPosition += ENCODER_STEPS_PER_MENU_ITEM; - else if (RRK(EN_KEYPAD_DOWN)) encoderPosition -= ENCODER_STEPS_PER_MENU_ITEM; - else if (RRK(EN_KEYPAD_LEFT)) { MenuItem_back::action(); quick_feedback(); } - else if (RRK(EN_KEYPAD_RIGHT)) { return_to_status(); quick_feedback(); } - } - else - #endif - { + #define ADC_MIN_KEY_DELAY 100 + if (keypad_buttons) { + #if HAS_ENCODER_ACTION + refresh(LCDVIEW_REDRAW_NOW); #if HAS_LCD_MENU - if (RRK(EN_KEYPAD_UP)) encoderPosition -= epps; - else if (RRK(EN_KEYPAD_DOWN)) encoderPosition += epps; - else if (RRK(EN_KEYPAD_LEFT)) { MenuItem_back::action(); quick_feedback(); } - else if (RRK(EN_KEYPAD_RIGHT)) encoderPosition = 0; - #else - if (RRK(EN_KEYPAD_UP) || RRK(EN_KEYPAD_LEFT)) encoderPosition -= epps; - else if (RRK(EN_KEYPAD_DOWN) || RRK(EN_KEYPAD_RIGHT)) encoderPosition += epps; + if (encoderDirection == -(ENCODERBASE)) { // HAS_ADC_BUTTONS forces REVERSE_MENU_DIRECTION, so this indicates menu navigation + if (RRK(EN_KEYPAD_UP)) encoderPosition += ENCODER_STEPS_PER_MENU_ITEM; + else if (RRK(EN_KEYPAD_DOWN)) encoderPosition -= ENCODER_STEPS_PER_MENU_ITEM; + else if (RRK(EN_KEYPAD_LEFT)) { MenuItem_back::action(); quick_feedback(); } + else if (RRK(EN_KEYPAD_RIGHT)) { return_to_status(); quick_feedback(); } + } + else #endif - } - #endif - next_button_update_ms = millis() + ADC_MIN_KEY_DELAY; - return true; - } + { + #if HAS_LCD_MENU + if (RRK(EN_KEYPAD_UP)) encoderPosition -= epps; + else if (RRK(EN_KEYPAD_DOWN)) encoderPosition += epps; + else if (RRK(EN_KEYPAD_LEFT)) { MenuItem_back::action(); quick_feedback(); } + else if (RRK(EN_KEYPAD_RIGHT)) encoderPosition = 0; + #else + if (RRK(EN_KEYPAD_UP) || RRK(EN_KEYPAD_LEFT)) encoderPosition -= epps; + else if (RRK(EN_KEYPAD_DOWN) || RRK(EN_KEYPAD_RIGHT)) encoderPosition += epps; + #endif + } + #endif + next_button_update_ms = millis() + ADC_MIN_KEY_DELAY; + return true; + } - #else // !HAS_ADC_BUTTONS + #else // !HAS_ADC_BUTTONS - static uint8_t keypad_debounce = 0; + static uint8_t keypad_debounce = 0; - if (!RRK( EN_KEYPAD_F1 | EN_KEYPAD_F2 - | EN_KEYPAD_F3 | EN_KEYPAD_DOWN - | EN_KEYPAD_RIGHT | EN_KEYPAD_MIDDLE - | EN_KEYPAD_UP | EN_KEYPAD_LEFT ) - ) { - if (keypad_debounce > 0) keypad_debounce--; - } - else if (!keypad_debounce) { - keypad_debounce = 2; - - const bool homed = all_axes_homed(); + if (!RRK( EN_KEYPAD_F1 | EN_KEYPAD_F2 + | EN_KEYPAD_F3 | EN_KEYPAD_DOWN + | EN_KEYPAD_RIGHT | EN_KEYPAD_MIDDLE + | EN_KEYPAD_UP | EN_KEYPAD_LEFT ) + ) { + if (keypad_debounce > 0) keypad_debounce--; + } + else if (!keypad_debounce) { + keypad_debounce = 2; - #if HAS_LCD_MENU + const bool homed = all_axes_homed(); - if (RRK(EN_KEYPAD_MIDDLE)) goto_screen(menu_move); + #if HAS_LCD_MENU - #if NONE(DELTA, Z_HOME_TO_MAX) - if (RRK(EN_KEYPAD_F2)) _reprapworld_keypad_move(Z_AXIS, 1); - #endif + if (RRK(EN_KEYPAD_MIDDLE)) goto_screen(menu_move); - if (homed) { - #if EITHER(DELTA, Z_HOME_TO_MAX) - if (RRK(EN_KEYPAD_F2)) _reprapworld_keypad_move(Z_AXIS, 1); + #if NONE(DELTA, Z_HOME_TO_MAX) + if (RRK(EN_KEYPAD_F2)) _reprapworld_keypad_move(Z_AXIS, 1); #endif - if (RRK(EN_KEYPAD_F3)) _reprapworld_keypad_move(Z_AXIS, -1); - if (RRK(EN_KEYPAD_LEFT)) _reprapworld_keypad_move(X_AXIS, -1); - if (RRK(EN_KEYPAD_RIGHT)) _reprapworld_keypad_move(X_AXIS, 1); - if (RRK(EN_KEYPAD_DOWN)) _reprapworld_keypad_move(Y_AXIS, 1); - if (RRK(EN_KEYPAD_UP)) _reprapworld_keypad_move(Y_AXIS, -1); - } - #endif // HAS_LCD_MENU + if (homed) { + #if EITHER(DELTA, Z_HOME_TO_MAX) + if (RRK(EN_KEYPAD_F2)) _reprapworld_keypad_move(Z_AXIS, 1); + #endif + if (RRK(EN_KEYPAD_F3)) _reprapworld_keypad_move(Z_AXIS, -1); + if (RRK(EN_KEYPAD_LEFT)) _reprapworld_keypad_move(X_AXIS, -1); + if (RRK(EN_KEYPAD_RIGHT)) _reprapworld_keypad_move(X_AXIS, 1); + if (RRK(EN_KEYPAD_DOWN)) _reprapworld_keypad_move(Y_AXIS, 1); + if (RRK(EN_KEYPAD_UP)) _reprapworld_keypad_move(Y_AXIS, -1); + } - if (!homed && RRK(EN_KEYPAD_F1)) queue.inject_P(G28_STR); - return true; - } + #endif // HAS_LCD_MENU - #endif // !HAS_ADC_BUTTONS + if (!homed && RRK(EN_KEYPAD_F1)) queue.inject_P(G28_STR); + return true; + } - return false; - } + #endif // !HAS_ADC_BUTTONS -#endif // IS_RRW_KEYPAD && HAS_ENCODER_ACTION + return false; + } -/** - * Status Screen - * - * This is very display-dependent, so the lcd implementation draws this. - */ + #endif // IS_RRW_KEYPAD && HAS_ENCODER_ACTION -#if BASIC_PROGRESS_BAR - millis_t MarlinUI::progress_bar_ms; // = 0 - #if PROGRESS_MSG_EXPIRE > 0 - millis_t MarlinUI::expire_status_ms; // = 0 + /** + * Status Screen + * + * This is very display-dependent, so the lcd implementation draws this. + */ + + #if BASIC_PROGRESS_BAR + millis_t MarlinUI::progress_bar_ms; // = 0 + #if PROGRESS_MSG_EXPIRE > 0 + millis_t MarlinUI::expire_status_ms; // = 0 + #endif #endif -#endif -void MarlinUI::status_screen() { + void MarlinUI::status_screen() { - TERN_(HAS_LCD_MENU, ENCODER_RATE_MULTIPLY(false)); + TERN_(HAS_LCD_MENU, ENCODER_RATE_MULTIPLY(false)); - #if BASIC_PROGRESS_BAR + #if BASIC_PROGRESS_BAR - // - // HD44780 implements the following message blinking and - // message expiration because Status Line and Progress Bar - // share the same line on the display. - // + // + // HD44780 implements the following message blinking and + // message expiration because Status Line and Progress Bar + // share the same line on the display. + // - #if DISABLED(PROGRESS_MSG_ONCE) || (PROGRESS_MSG_EXPIRE > 0) - #define GOT_MS - const millis_t ms = millis(); - #endif + #if DISABLED(PROGRESS_MSG_ONCE) || (PROGRESS_MSG_EXPIRE > 0) + #define GOT_MS + const millis_t ms = millis(); + #endif - // If the message will blink rather than expire... - #if DISABLED(PROGRESS_MSG_ONCE) - if (ELAPSED(ms, progress_bar_ms + PROGRESS_BAR_MSG_TIME + PROGRESS_BAR_BAR_TIME)) - progress_bar_ms = ms; - #endif + // If the message will blink rather than expire... + #if DISABLED(PROGRESS_MSG_ONCE) + if (ELAPSED(ms, progress_bar_ms + PROGRESS_BAR_MSG_TIME + PROGRESS_BAR_BAR_TIME)) + progress_bar_ms = ms; + #endif - #if PROGRESS_MSG_EXPIRE > 0 + #if PROGRESS_MSG_EXPIRE > 0 - // Handle message expire - if (expire_status_ms) { + // Handle message expire + if (expire_status_ms) { - // Expire the message if a job is active and the bar has ticks - if (get_progress_percent() > 2 && !print_job_timer.isPaused()) { - if (ELAPSED(ms, expire_status_ms)) { - status_message[0] = '\0'; - expire_status_ms = 0; + // Expire the message if a job is active and the bar has ticks + if (get_progress_percent() > 2 && !print_job_timer.isPaused()) { + if (ELAPSED(ms, expire_status_ms)) { + status_message[0] = '\0'; + expire_status_ms = 0; + } + } + else { + // Defer message expiration before bar appears + // and during any pause (not just SD) + expire_status_ms += LCD_UPDATE_INTERVAL; } } - else { - // Defer message expiration before bar appears - // and during any pause (not just SD) - expire_status_ms += LCD_UPDATE_INTERVAL; - } - } - #endif // PROGRESS_MSG_EXPIRE + #endif // PROGRESS_MSG_EXPIRE - #endif // BASIC_PROGRESS_BAR + #endif // BASIC_PROGRESS_BAR - #if HAS_LCD_MENU - if (use_click()) { - #if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) - next_filament_display = millis() + 5000UL; // Show status message for 5s - #endif - goto_screen(menu_main); - #if DISABLED(NO_LCD_REINIT) - init_lcd(); // May revive the LCD if static electricity killed it - #endif - return; - } + #if HAS_LCD_MENU + if (use_click()) { + #if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) + next_filament_display = millis() + 5000UL; // Show status message for 5s + #endif + goto_screen(menu_main); + #if DISABLED(NO_LCD_REINIT) + init_lcd(); // May revive the LCD if static electricity killed it + #endif + return; + } - #endif + #endif - #if ENABLED(ULTIPANEL_FEEDMULTIPLY) + #if ENABLED(ULTIPANEL_FEEDMULTIPLY) - const int16_t old_frm = feedrate_percentage; - int16_t new_frm = old_frm + int16_t(encoderPosition); + const int16_t old_frm = feedrate_percentage; + int16_t new_frm = old_frm + int16_t(encoderPosition); - // Dead zone at 100% feedrate - if (old_frm == 100) { - if (int16_t(encoderPosition) > ENCODER_FEEDRATE_DEADZONE) - new_frm -= ENCODER_FEEDRATE_DEADZONE; - else if (int16_t(encoderPosition) < -(ENCODER_FEEDRATE_DEADZONE)) - new_frm += ENCODER_FEEDRATE_DEADZONE; - else - new_frm = old_frm; - } - else if ((old_frm < 100 && new_frm > 100) || (old_frm > 100 && new_frm < 100)) - new_frm = 100; - - LIMIT(new_frm, 10, 999); - - if (old_frm != new_frm) { - feedrate_percentage = new_frm; - encoderPosition = 0; - #if BOTH(HAS_BUZZER, BEEP_ON_FEEDRATE_CHANGE) - static millis_t next_beep; - #ifndef GOT_MS - const millis_t ms = millis(); + // Dead zone at 100% feedrate + if (old_frm == 100) { + if (int16_t(encoderPosition) > ENCODER_FEEDRATE_DEADZONE) + new_frm -= ENCODER_FEEDRATE_DEADZONE; + else if (int16_t(encoderPosition) < -(ENCODER_FEEDRATE_DEADZONE)) + new_frm += ENCODER_FEEDRATE_DEADZONE; + else + new_frm = old_frm; + } + else if ((old_frm < 100 && new_frm > 100) || (old_frm > 100 && new_frm < 100)) + new_frm = 100; + + LIMIT(new_frm, 10, 999); + + if (old_frm != new_frm) { + feedrate_percentage = new_frm; + encoderPosition = 0; + #if BOTH(HAS_BUZZER, BEEP_ON_FEEDRATE_CHANGE) + static millis_t next_beep; + #ifndef GOT_MS + const millis_t ms = millis(); + #endif + if (ELAPSED(ms, next_beep)) { + buzz(FEEDRATE_CHANGE_BEEP_DURATION, FEEDRATE_CHANGE_BEEP_FREQUENCY); + next_beep = ms + 500UL; + } #endif - if (ELAPSED(ms, next_beep)) { - buzz(FEEDRATE_CHANGE_BEEP_DURATION, FEEDRATE_CHANGE_BEEP_FREQUENCY); - next_beep = ms + 500UL; - } - #endif - } + } - #endif // ULTIPANEL_FEEDMULTIPLY + #endif // ULTIPANEL_FEEDMULTIPLY - draw_status_screen(); -} + draw_status_screen(); + } -void MarlinUI::kill_screen(PGM_P lcd_error, PGM_P lcd_component) { - init(); - status_printf_P(1, PSTR(S_FMT ": " S_FMT), lcd_error, lcd_component); - TERN_(HAS_LCD_MENU, return_to_status()); + void MarlinUI::kill_screen(PGM_P lcd_error, PGM_P lcd_component) { + init(); + status_printf_P(1, PSTR(S_FMT ": " S_FMT), lcd_error, lcd_component); + TERN_(HAS_LCD_MENU, return_to_status()); - // RED ALERT. RED ALERT. - #ifdef LED_BACKLIGHT_TIMEOUT - leds.set_color(LEDColorRed()); - #ifdef NEOPIXEL_BKGD_LED_INDEX - neo.set_pixel_color(NEOPIXEL_BKGD_LED_INDEX, 255, 0, 0, 0); - neo.show(); + // RED ALERT. RED ALERT. + #ifdef LED_BACKLIGHT_TIMEOUT + leds.set_color(LEDColorRed()); + #ifdef NEOPIXEL_BKGD_INDEX_FIRST + neo.set_background_color(255, 0, 0, 0); + neo.show(); + #endif #endif - #endif - - draw_kill_screen(); -} -void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { + draw_kill_screen(); + } - TERN_(HAS_LCD_MENU, refresh()); + void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) { - #if HAS_ENCODER_ACTION - if (clear_buttons) buttons = 0; - next_button_update_ms = millis() + 500; - #else - UNUSED(clear_buttons); - #endif + TERN_(HAS_LCD_MENU, refresh()); - #if HAS_CHIRP - chirp(); // Buzz and wait. Is the delay needed for buttons to settle? - #if BOTH(HAS_LCD_MENU, USE_BEEPER) - for (int8_t i = 5; i--;) { buzzer.tick(); delay(2); } - #elif HAS_LCD_MENU - delay(10); + #if HAS_ENCODER_ACTION + if (clear_buttons) buttons = 0; + next_button_update_ms = millis() + 500; + #else + UNUSED(clear_buttons); #endif - #endif -} - -//////////////////////////////////////////// -/////////////// Manual Move //////////////// -//////////////////////////////////////////// - -#if HAS_LCD_MENU - ManualMove MarlinUI::manual_move{}; - - millis_t ManualMove::start_time = 0; - float ManualMove::menu_scale = 1; - #if IS_KINEMATIC - float ManualMove::offset = 0; - xyze_pos_t ManualMove::all_axes_destination = { 0 }; - bool ManualMove::processing = false; - #endif - #if MULTI_E_MANUAL - int8_t ManualMove::e_index = 0; - #endif - AxisEnum ManualMove::axis = NO_AXIS_ENUM; - - /** - * If a manual move has been posted and its time has arrived, and if the planner - * has a space for it, then add a linear move to current_position the planner. - * - * If any manual move needs to be interrupted, make sure to force a manual move - * by setting manual_move.start_time to millis() after updating current_position. - * - * To post a manual move: - * - Update current_position to the new place you want to go. - * - Set manual_move.axis to an axis like X_AXIS. Use ALL_AXES_ENUM for diagonal moves. - * - Set manual_move.start_time to a point in the future (in ms) when the move should be done. - * - * For kinematic machines: - * - Set manual_move.offset to modify one axis and post the move. - * This is used to achieve more rapid stepping on kinematic machines. - * - * Currently used by the _lcd_move_xyz function in menu_motion.cpp - * and the ubl_map_move_to_xy funtion in menu_ubl.cpp. - */ - void ManualMove::task() { - - if (processing) return; // Prevent re-entry from idle() calls + #if HAS_CHIRP + chirp(); // Buzz and wait. Is the delay needed for buttons to settle? + #if BOTH(HAS_LCD_MENU, USE_BEEPER) + for (int8_t i = 5; i--;) { buzzer.tick(); delay(2); } + #elif HAS_LCD_MENU + delay(10); + #endif + #endif + } - // Add a manual move to the queue? - if (axis != NO_AXIS_ENUM && ELAPSED(millis(), start_time) && !planner.is_full()) { + //////////////////////////////////////////// + /////////////// Manual Move //////////////// + //////////////////////////////////////////// - const feedRate_t fr_mm_s = (axis <= E_AXIS) ? manual_feedrate_mm_s[axis] : XY_PROBE_FEEDRATE_MM_S; + #if HAS_LCD_MENU - #if IS_KINEMATIC + ManualMove MarlinUI::manual_move{}; - #if HAS_MULTI_EXTRUDER - REMEMBER(ae, active_extruder); - if (axis == E_AXIS) active_extruder = e_index; - #endif + millis_t ManualMove::start_time = 0; + float ManualMove::menu_scale = 1; + #if IS_KINEMATIC + float ManualMove::offset = 0; + xyze_pos_t ManualMove::all_axes_destination = { 0 }; + bool ManualMove::processing = false; + #endif + #if MULTI_E_MANUAL + int8_t ManualMove::e_index = 0; + #endif + AxisEnum ManualMove::axis = NO_AXIS_ENUM; + + /** + * If a manual move has been posted and its time has arrived, and if the planner + * has a space for it, then add a linear move to current_position the planner. + * + * If any manual move needs to be interrupted, make sure to force a manual move + * by setting manual_move.start_time to millis() after updating current_position. + * + * To post a manual move: + * - Update current_position to the new place you want to go. + * - Set manual_move.axis to an axis like X_AXIS. Use ALL_AXES_ENUM for diagonal moves. + * - Set manual_move.start_time to a point in the future (in ms) when the move should be done. + * + * For kinematic machines: + * - Set manual_move.offset to modify one axis and post the move. + * This is used to achieve more rapid stepping on kinematic machines. + * + * Currently used by the _lcd_move_xyz function in menu_motion.cpp + * and the ubl_map_move_to_xy funtion in menu_ubl.cpp. + */ + void ManualMove::task() { + + if (processing) return; // Prevent re-entry from idle() calls + + // Add a manual move to the queue? + if (axis != NO_AXIS_ENUM && ELAPSED(millis(), start_time) && !planner.is_full()) { + + const feedRate_t fr_mm_s = (axis <= LOGICAL_AXES) ? manual_feedrate_mm_s[axis] : XY_PROBE_FEEDRATE_MM_S; + + #if IS_KINEMATIC + + #if HAS_MULTI_EXTRUDER + REMEMBER(ae, active_extruder); + #if MULTI_E_MANUAL + if (axis == E_AXIS) active_extruder = e_index; + #endif + #endif - // Apply a linear offset to a single axis - if (axis == ALL_AXES_ENUM) - destination = all_axes_destination; - else if (axis <= XYZE) { - destination = current_position; - destination[axis] += offset; - } + // Apply a linear offset to a single axis + if (axis == ALL_AXES_ENUM) + destination = all_axes_destination; + else if (axis <= XYZE) { + destination = current_position; + destination[axis] += offset; + } - // Reset for the next move - offset = 0; - axis = NO_AXIS_ENUM; + // Reset for the next move + offset = 0; + axis = NO_AXIS_ENUM; - // DELTA and SCARA machines use segmented moves, which could fill the planner during the call to - // move_to_destination. This will cause idle() to be called, which can then call this function while the - // previous invocation is being blocked. Modifications to offset shouldn't be made while - // processing is true or the planner will get out of sync. - processing = true; - prepare_internal_move_to_destination(fr_mm_s); // will set current_position from destination - processing = false; + // DELTA and SCARA machines use segmented moves, which could fill the planner during the call to + // move_to_destination. This will cause idle() to be called, which can then call this function while the + // previous invocation is being blocked. Modifications to offset shouldn't be made while + // processing is true or the planner will get out of sync. + processing = true; + prepare_internal_move_to_destination(fr_mm_s); // will set current_position from destination + processing = false; - #else + #else - // For Cartesian / Core motion simply move to the current_position - planner.buffer_line(current_position, fr_mm_s, axis == E_AXIS ? e_index : active_extruder); + // For Cartesian / Core motion simply move to the current_position + planner.buffer_line(current_position, fr_mm_s, + TERN_(MULTI_E_MANUAL, axis == E_AXIS ? e_index :) active_extruder + ); - //SERIAL_ECHOLNPAIR("Add planner.move with Axis ", AS_CHAR(axis_codes[axis]), " at FR ", fr_mm_s); + //SERIAL_ECHOLNPAIR("Add planner.move with Axis ", AS_CHAR(axis_codes[axis]), " at FR ", fr_mm_s); - axis = NO_AXIS_ENUM; + axis = NO_AXIS_ENUM; - #endif + #endif + } } - } - // - // Tell ui.update() to start a move to current_position after a short delay. - // - void ManualMove::soon(const AxisEnum move_axis - #if MULTI_E_MANUAL - , const int8_t eindex/*=-1*/ - #endif - ) { - #if MULTI_E_MANUAL - if (move_axis == E_AXIS) e_index = eindex >= 0 ? eindex : active_extruder; - #endif - start_time = millis() + (menu_scale < 0.99f ? 0UL : 250UL); // delay for bigger moves - axis = move_axis; - //SERIAL_ECHOLNPAIR("Post Move with Axis ", AS_CHAR(axis_codes[axis]), " soon."); - } + // + // Tell ui.update() to start a move to current_position after a short delay. + // + void ManualMove::soon(const AxisEnum move_axis + OPTARG(MULTI_E_MANUAL, const int8_t eindex/*=active_extruder*/) + ) { + TERN_(MULTI_E_MANUAL, if (move_axis == E_AXIS) e_index = eindex); + start_time = millis() + (menu_scale < 0.99f ? 0UL : 250UL); // delay for bigger moves + axis = move_axis; + //SERIAL_ECHOLNPAIR("Post Move with Axis ", AS_CHAR(axis_codes[axis]), " soon."); + } - #if ENABLED(AUTO_BED_LEVELING_UBL) + #if ENABLED(AUTO_BED_LEVELING_UBL) - void MarlinUI::external_encoder() { - if (external_control && encoderDiff) { - ubl.encoder_diff += encoderDiff; // Encoder for UBL G29 mesh editing - encoderDiff = 0; // Hide encoder events from the screen handler - refresh(LCDVIEW_REDRAW_NOW); // ...but keep the refresh. + void MarlinUI::external_encoder() { + if (external_control && encoderDiff) { + ubl.encoder_diff += encoderDiff; // Encoder for UBL G29 mesh editing + encoderDiff = 0; // Hide encoder events from the screen handler + refresh(LCDVIEW_REDRAW_NOW); // ...but keep the refresh. + } } - } - #endif - -#endif // HAS_LCD_MENU + #endif -/** - * Update the LCD, read encoder buttons, etc. - * - Read button states - * - Check the SD Card slot state - * - Act on RepRap World keypad input - * - Update the encoder position - * - Apply acceleration to the encoder position - * - Do refresh(LCDVIEW_CALL_REDRAW_NOW) on controller events - * - Reset the Info Screen timeout if there's any input - * - Update status indicators, if any - * - * Run the current LCD menu handler callback function: - * - Call the handler only if lcdDrawUpdate != LCDVIEW_NONE - * - Before calling the handler, LCDVIEW_CALL_NO_REDRAW => LCDVIEW_NONE - * - Call the menu handler. Menu handlers should do the following: - * - If a value changes, set lcdDrawUpdate to LCDVIEW_REDRAW_NOW and draw the value - * (Encoder events automatically set lcdDrawUpdate for you.) - * - if (should_draw()) { redraw } - * - Before exiting the handler set lcdDrawUpdate to: - * - LCDVIEW_CLEAR_CALL_REDRAW to clear screen and set LCDVIEW_CALL_REDRAW_NEXT. - * - LCDVIEW_REDRAW_NOW to draw now (including remaining stripes). - * - LCDVIEW_CALL_REDRAW_NEXT to draw now and get LCDVIEW_REDRAW_NOW on the next loop. - * - LCDVIEW_CALL_NO_REDRAW to draw now and get LCDVIEW_NONE on the next loop. - * - NOTE: For graphical displays menu handlers may be called 2 or more times per loop, - * so don't change lcdDrawUpdate without considering this. - * - * After the menu handler callback runs (or not): - * - Clear the LCD if lcdDrawUpdate == LCDVIEW_CLEAR_CALL_REDRAW - * - Update lcdDrawUpdate for the next loop (i.e., move one state down, usually) - * - * This function is only called from the main thread. - */ + #endif // HAS_LCD_MENU -LCDViewAction MarlinUI::lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; -millis_t next_lcd_update_ms; -#if HAS_LCD_MENU && LCD_TIMEOUT_TO_STATUS - millis_t MarlinUI::return_to_status_ms = 0; -#endif + /** + * Update the LCD, read encoder buttons, etc. + * - Read button states + * - Check the SD Card slot state + * - Act on RepRap World keypad input + * - Update the encoder position + * - Apply acceleration to the encoder position + * - Do refresh(LCDVIEW_CALL_REDRAW_NOW) on controller events + * - Reset the Info Screen timeout if there's any input + * - Update status indicators, if any + * + * Run the current LCD menu handler callback function: + * - Call the handler only if lcdDrawUpdate != LCDVIEW_NONE + * - Before calling the handler, LCDVIEW_CALL_NO_REDRAW => LCDVIEW_NONE + * - Call the menu handler. Menu handlers should do the following: + * - If a value changes, set lcdDrawUpdate to LCDVIEW_REDRAW_NOW and draw the value + * (Encoder events automatically set lcdDrawUpdate for you.) + * - if (should_draw()) { redraw } + * - Before exiting the handler set lcdDrawUpdate to: + * - LCDVIEW_CLEAR_CALL_REDRAW to clear screen and set LCDVIEW_CALL_REDRAW_NEXT. + * - LCDVIEW_REDRAW_NOW to draw now (including remaining stripes). + * - LCDVIEW_CALL_REDRAW_NEXT to draw now and get LCDVIEW_REDRAW_NOW on the next loop. + * - LCDVIEW_CALL_NO_REDRAW to draw now and get LCDVIEW_NONE on the next loop. + * - NOTE: For graphical displays menu handlers may be called 2 or more times per loop, + * so don't change lcdDrawUpdate without considering this. + * + * After the menu handler callback runs (or not): + * - Clear the LCD if lcdDrawUpdate == LCDVIEW_CLEAR_CALL_REDRAW + * - Update lcdDrawUpdate for the next loop (i.e., move one state down, usually) + * + * This function is only called from the main thread. + */ -inline bool can_encode() { - return !BUTTON_PRESSED(ENC_EN); // Update encoder only when ENC_EN is not LOW (pressed) -} + LCDViewAction MarlinUI::lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; + millis_t next_lcd_update_ms; -void MarlinUI::update() { + inline bool can_encode() { + return !BUTTON_PRESSED(ENC_EN); // Update encoder only when ENC_EN is not LOW (pressed) + } - static uint16_t max_display_update_time = 0; - millis_t ms = millis(); + void MarlinUI::update() { - #if HAS_LCD_MENU && LCD_TIMEOUT_TO_STATUS > 0 - #define RESET_STATUS_TIMEOUT() (return_to_status_ms = ms + LCD_TIMEOUT_TO_STATUS) - #else - #define RESET_STATUS_TIMEOUT() NOOP - #endif + static uint16_t max_display_update_time = 0; + millis_t ms = millis(); - #ifdef LED_BACKLIGHT_TIMEOUT - leds.update_timeout(powersupply_on); - #endif + #ifdef LED_BACKLIGHT_TIMEOUT + leds.update_timeout(powersupply_on); + #endif - #if HAS_LCD_MENU + #if HAS_LCD_MENU - // Handle any queued Move Axis motion - manual_move.task(); + // Handle any queued Move Axis motion + manual_move.task(); - // Update button states for button_pressed(), etc. - // If the state changes the next update may be delayed 300-500ms. - update_buttons(); + // Update button states for button_pressed(), etc. + // If the state changes the next update may be delayed 300-500ms. + update_buttons(); - // If the action button is pressed... - static bool wait_for_unclick; // = false + // If the action button is pressed... + static bool wait_for_unclick; // = false - auto do_click = [&]{ - wait_for_unclick = true; // - Set debounce flag to ignore continuous clicks - lcd_clicked = !wait_for_user; // - Keep the click if not waiting for a user-click - wait_for_user = false; // - Any click clears wait for user - quick_feedback(); // - Always make a click sound - }; + auto do_click = [&]{ + wait_for_unclick = true; // - Set debounce flag to ignore continuous clicks + lcd_clicked = !wait_for_user; // - Keep the click if not waiting for a user-click + wait_for_user = false; // - Any click clears wait for user + quick_feedback(); // - Always make a click sound + }; - #if HAS_TOUCH_BUTTONS - if (touch_buttons) { - RESET_STATUS_TIMEOUT(); - if (touch_buttons & (EN_A | EN_B)) { // Menu arrows, in priority - if (ELAPSED(ms, next_button_update_ms)) { - encoderDiff = (ENCODER_STEPS_PER_MENU_ITEM) * epps * encoderDirection; - if (touch_buttons & EN_A) encoderDiff *= -1; - TERN_(AUTO_BED_LEVELING_UBL, external_encoder()); - next_button_update_ms = ms + repeat_delay; // Assume the repeat delay - if (!wait_for_unclick) { - next_button_update_ms += 250; // Longer delay on first press - wait_for_unclick = true; // Avoid Back/Select click while repeating - chirp(); + #if HAS_TOUCH_BUTTONS + if (touch_buttons) { + reset_status_timeout(ms); + if (touch_buttons & (EN_A | EN_B)) { // Menu arrows, in priority + if (ELAPSED(ms, next_button_update_ms)) { + encoderDiff = (ENCODER_STEPS_PER_MENU_ITEM) * epps * encoderDirection; + if (touch_buttons & EN_A) encoderDiff *= -1; + TERN_(AUTO_BED_LEVELING_UBL, external_encoder()); + next_button_update_ms = ms + repeat_delay; // Assume the repeat delay + if (!wait_for_unclick) { + next_button_update_ms += 250; // Longer delay on first press + wait_for_unclick = true; // Avoid Back/Select click while repeating + chirp(); + } } } + else if (!wait_for_unclick && (buttons & EN_C)) // OK button, if not waiting for a debounce release: + do_click(); } - else if (!wait_for_unclick && (buttons & EN_C)) // OK button, if not waiting for a debounce release: - do_click(); - } - // keep wait_for_unclick value - #endif + // keep wait_for_unclick value + #endif - if (!touch_buttons) { - // Integrated LCD click handling via button_pressed - if (!external_control && button_pressed()) { - if (!wait_for_unclick) do_click(); // Handle the click + if (!touch_buttons) { + // Integrated LCD click handling via button_pressed + if (!external_control && button_pressed()) { + if (!wait_for_unclick) do_click(); // Handle the click + } + else + wait_for_unclick = false; } - else - wait_for_unclick = false; - } - if (LCD_BACK_CLICKED()) { - quick_feedback(); - goto_previous_screen(); - } + if (LCD_BACK_CLICKED()) { + quick_feedback(); + goto_previous_screen(); + } - #endif // HAS_LCD_MENU + #endif // HAS_LCD_MENU - if (ELAPSED(ms, next_lcd_update_ms) || TERN0(HAS_MARLINUI_U8GLIB, drawing_screen)) { + if (ELAPSED(ms, next_lcd_update_ms) || TERN0(HAS_MARLINUI_U8GLIB, drawing_screen)) { - next_lcd_update_ms = ms + LCD_UPDATE_INTERVAL; + next_lcd_update_ms = ms + LCD_UPDATE_INTERVAL; - #if HAS_TOUCH_BUTTONS + #if HAS_TOUCH_BUTTONS - if (on_status_screen()) next_lcd_update_ms += (LCD_UPDATE_INTERVAL) * 2; + if (on_status_screen()) next_lcd_update_ms += (LCD_UPDATE_INTERVAL) * 2; - TERN_(HAS_ENCODER_ACTION, touch_buttons = touch.read_buttons()); + TERN_(HAS_ENCODER_ACTION, touch_buttons = touch.read_buttons()); - #endif - - TERN_(LCD_HAS_STATUS_INDICATORS, update_indicators()); + #endif - #if HAS_ENCODER_ACTION + TERN_(LCD_HAS_STATUS_INDICATORS, update_indicators()); - TERN_(HAS_SLOW_BUTTONS, slow_buttons = read_slow_buttons()); // Buttons that take too long to read in interrupt context + #if HAS_ENCODER_ACTION - if (TERN0(IS_RRW_KEYPAD, handle_keypad())) - RESET_STATUS_TIMEOUT(); + TERN_(HAS_SLOW_BUTTONS, slow_buttons = read_slow_buttons()); // Buttons that take too long to read in interrupt context - uint8_t abs_diff = ABS(encoderDiff); + if (TERN0(IS_RRW_KEYPAD, handle_keypad())) + reset_status_timeout(ms); - #if ENCODER_PULSES_PER_STEP > 1 - // When reversing the encoder direction, a movement step can be missed because - // encoderDiff has a non-zero residual value, making the controller unresponsive. - // The fix clears the residual value when the encoder is idle. - // Also check if past half the threshold to compensate for missed single steps. - static int8_t lastEncoderDiff; + uint8_t abs_diff = ABS(encoderDiff); - // Timeout? No decoder change since last check. 10 or 20 times per second. - if (encoderDiff == lastEncoderDiff && abs_diff <= epps / 2) // Same direction & size but not over a half-step? - encoderDiff = 0; // Clear residual pulses. - else if (WITHIN(abs_diff, epps / 2 + 1, epps - 1)) { // Past half of threshold? - abs_diff = epps; // Treat as a full step size - encoderDiff = (encoderDiff < 0 ? -1 : 1) * abs_diff; // ...in the spin direction. - } - lastEncoderDiff = encoderDiff; - #endif + #if ENCODER_PULSES_PER_STEP > 1 + // When reversing the encoder direction, a movement step can be missed because + // encoderDiff has a non-zero residual value, making the controller unresponsive. + // The fix clears the residual value when the encoder is idle. + // Also check if past half the threshold to compensate for missed single steps. + static int8_t lastEncoderDiff; - const bool encoderPastThreshold = (abs_diff >= epps); - if (encoderPastThreshold || lcd_clicked) { - if (encoderPastThreshold && TERN1(IS_TFTGLCD_PANEL, !external_control)) { + // Timeout? No decoder change since last check. 10 or 20 times per second. + if (encoderDiff == lastEncoderDiff && abs_diff <= epps / 2) // Same direction & size but not over a half-step? + encoderDiff = 0; // Clear residual pulses. + else if (WITHIN(abs_diff, epps / 2 + 1, epps - 1)) { // Past half of threshold? + abs_diff = epps; // Treat as a full step size + encoderDiff = (encoderDiff < 0 ? -1 : 1) * abs_diff; // ...in the spin direction. + } + lastEncoderDiff = encoderDiff; + #endif - #if BOTH(HAS_LCD_MENU, ENCODER_RATE_MULTIPLIER) + const bool encoderPastThreshold = (abs_diff >= epps); + if (encoderPastThreshold || lcd_clicked) { + if (encoderPastThreshold && TERN1(IS_TFTGLCD_PANEL, !external_control)) { - int32_t encoderMultiplier = 1; + #if BOTH(HAS_LCD_MENU, ENCODER_RATE_MULTIPLIER) - if (encoderRateMultiplierEnabled) { - const float encoderMovementSteps = float(abs_diff) / epps; + int32_t encoderMultiplier = 1; - if (lastEncoderMovementMillis) { - // Note that the rate is always calculated between two passes through the - // loop and that the abs of the encoderDiff value is tracked. - const float encoderStepRate = encoderMovementSteps / float(ms - lastEncoderMovementMillis) * 1000; + if (encoderRateMultiplierEnabled) { + const float encoderMovementSteps = float(abs_diff) / epps; - if (encoderStepRate >= ENCODER_100X_STEPS_PER_SEC) encoderMultiplier = 100; - else if (encoderStepRate >= ENCODER_10X_STEPS_PER_SEC) encoderMultiplier = 10; + if (lastEncoderMovementMillis) { + // Note that the rate is always calculated between two passes through the + // loop and that the abs of the encoderDiff value is tracked. + const float encoderStepRate = encoderMovementSteps / float(ms - lastEncoderMovementMillis) * 1000; - // Enable to output the encoder steps per second value - //#define ENCODER_RATE_MULTIPLIER_DEBUG - #if ENABLED(ENCODER_RATE_MULTIPLIER_DEBUG) - SERIAL_ECHO_START(); - SERIAL_ECHOPAIR("Enc Step Rate: ", encoderStepRate); - SERIAL_ECHOPAIR(" Multiplier: ", encoderMultiplier); - SERIAL_ECHOPAIR(" ENCODER_10X_STEPS_PER_SEC: ", ENCODER_10X_STEPS_PER_SEC); - SERIAL_ECHOPAIR(" ENCODER_100X_STEPS_PER_SEC: ", ENCODER_100X_STEPS_PER_SEC); - SERIAL_EOL(); - #endif - } + if (encoderStepRate >= ENCODER_100X_STEPS_PER_SEC) encoderMultiplier = 100; + else if (encoderStepRate >= ENCODER_10X_STEPS_PER_SEC) encoderMultiplier = 10; - lastEncoderMovementMillis = ms; - } // encoderRateMultiplierEnabled + // Enable to output the encoder steps per second value + //#define ENCODER_RATE_MULTIPLIER_DEBUG + #if ENABLED(ENCODER_RATE_MULTIPLIER_DEBUG) + SERIAL_ECHO_START(); + SERIAL_ECHOPAIR("Enc Step Rate: ", encoderStepRate); + SERIAL_ECHOPAIR(" Multiplier: ", encoderMultiplier); + SERIAL_ECHOPAIR(" ENCODER_10X_STEPS_PER_SEC: ", ENCODER_10X_STEPS_PER_SEC); + SERIAL_ECHOPAIR(" ENCODER_100X_STEPS_PER_SEC: ", ENCODER_100X_STEPS_PER_SEC); + SERIAL_EOL(); + #endif + } - #else + lastEncoderMovementMillis = ms; + } // encoderRateMultiplierEnabled - constexpr int32_t encoderMultiplier = 1; + #else - #endif // ENCODER_RATE_MULTIPLIER + constexpr int32_t encoderMultiplier = 1; - if (can_encode()) encoderPosition += (encoderDiff * encoderMultiplier) / epps; + #endif // ENCODER_RATE_MULTIPLIER - encoderDiff = 0; - } + if (can_encode()) encoderPosition += (encoderDiff * encoderMultiplier) / epps; - RESET_STATUS_TIMEOUT(); + encoderDiff = 0; + } - refresh(LCDVIEW_REDRAW_NOW); + reset_status_timeout(ms); - #ifdef LED_BACKLIGHT_TIMEOUT - if (!powersupply_on) leds.reset_timeout(ms); - #endif - } + refresh(LCDVIEW_REDRAW_NOW); - #endif + #ifdef LED_BACKLIGHT_TIMEOUT + if (!powersupply_on) leds.reset_timeout(ms); + #endif + } - // This runs every ~100ms when idling often enough. - // Instead of tracking changes just redraw the Status Screen once per second. - if (on_status_screen() && !lcd_status_update_delay--) { - lcd_status_update_delay = TERN(HAS_MARLINUI_U8GLIB, 12, 9); - if (max_display_update_time) max_display_update_time--; // Be sure never go to a very big number - refresh(LCDVIEW_REDRAW_NOW); - } + #endif - #if BOTH(HAS_LCD_MENU, SCROLL_LONG_FILENAMES) - // If scrolling of long file names is enabled and we are in the sd card menu, - // cause a refresh to occur until all the text has scrolled into view. - if (currentScreen == menu_media && !lcd_status_update_delay--) { - lcd_status_update_delay = ++filename_scroll_pos >= filename_scroll_max ? 12 : 4; // Long delay at end and start - if (filename_scroll_pos > filename_scroll_max) filename_scroll_pos = 0; + // This runs every ~100ms when idling often enough. + // Instead of tracking changes just redraw the Status Screen once per second. + if (on_status_screen() && !lcd_status_update_delay--) { + lcd_status_update_delay = TERN(HAS_MARLINUI_U8GLIB, 12, 9); + if (max_display_update_time) max_display_update_time--; // Be sure never go to a very big number refresh(LCDVIEW_REDRAW_NOW); - RESET_STATUS_TIMEOUT(); } - #endif - - // Then we want to use only 50% of the time - const uint16_t bbr2 = planner.block_buffer_runtime() >> 1; - - if ((should_draw() || drawing_screen) && (!bbr2 || bbr2 > max_display_update_time)) { - // Change state of drawing flag between screen updates - if (!drawing_screen) switch (lcdDrawUpdate) { - case LCDVIEW_CALL_NO_REDRAW: - refresh(LCDVIEW_NONE); - break; - case LCDVIEW_CLEAR_CALL_REDRAW: - case LCDVIEW_CALL_REDRAW_NEXT: + #if BOTH(HAS_LCD_MENU, SCROLL_LONG_FILENAMES) + // If scrolling of long file names is enabled and we are in the sd card menu, + // cause a refresh to occur until all the text has scrolled into view. + if (currentScreen == menu_media && !lcd_status_update_delay--) { + lcd_status_update_delay = ++filename_scroll_pos >= filename_scroll_max ? 12 : 4; // Long delay at end and start + if (filename_scroll_pos > filename_scroll_max) filename_scroll_pos = 0; refresh(LCDVIEW_REDRAW_NOW); - case LCDVIEW_REDRAW_NOW: // set above, or by a handler through LCDVIEW_CALL_REDRAW_NEXT - case LCDVIEW_NONE: - break; - } // switch + reset_status_timeout(ms); + } + #endif - TERN_(HAS_ADC_BUTTONS, keypad_buttons = 0); + // Then we want to use only 50% of the time + const uint16_t bbr2 = planner.block_buffer_runtime() >> 1; + + if ((should_draw() || drawing_screen) && (!bbr2 || bbr2 > max_display_update_time)) { + + // Change state of drawing flag between screen updates + if (!drawing_screen) switch (lcdDrawUpdate) { + case LCDVIEW_CALL_NO_REDRAW: + refresh(LCDVIEW_NONE); + break; + case LCDVIEW_CLEAR_CALL_REDRAW: + case LCDVIEW_CALL_REDRAW_NEXT: + refresh(LCDVIEW_REDRAW_NOW); + case LCDVIEW_REDRAW_NOW: // set above, or by a handler through LCDVIEW_CALL_REDRAW_NEXT + case LCDVIEW_NONE: + break; + } // switch + + TERN_(HAS_ADC_BUTTONS, keypad_buttons = 0); + + #if HAS_MARLINUI_U8GLIB + + #if ENABLED(LIGHTWEIGHT_UI) + const bool in_status = on_status_screen(), + do_u8g_loop = !in_status; + lcd_in_status(in_status); + if (in_status) status_screen(); + #else + constexpr bool do_u8g_loop = true; + #endif - #if HAS_MARLINUI_U8GLIB + if (do_u8g_loop) { + if (!drawing_screen) { // If not already drawing pages + u8g.firstPage(); // Start the first page + drawing_screen = first_page = true; // Flag as drawing pages + } + set_font(FONT_MENU); // Setup font for every page draw + u8g.setColorIndex(1); // And reset the color + run_current_screen(); // Draw and process the current screen + first_page = false; + + // The screen handler can clear drawing_screen for an action that changes the screen. + // If still drawing and there's another page, update max-time and return now. + // The nextPage will already be set up on the next call. + if (drawing_screen && (drawing_screen = u8g.nextPage())) { + if (on_status_screen()) + NOLESS(max_display_update_time, millis() - ms); + return; + } + } - #if ENABLED(LIGHTWEIGHT_UI) - const bool in_status = on_status_screen(), - do_u8g_loop = !in_status; - lcd_in_status(in_status); - if (in_status) status_screen(); #else - constexpr bool do_u8g_loop = true; - #endif - if (do_u8g_loop) { - if (!drawing_screen) { // If not already drawing pages - u8g.firstPage(); // Start the first page - drawing_screen = first_page = true; // Flag as drawing pages - } - set_font(FONT_MENU); // Setup font for every page draw - u8g.setColorIndex(1); // And reset the color - run_current_screen(); // Draw and process the current screen - first_page = false; - - // The screen handler can clear drawing_screen for an action that changes the screen. - // If still drawing and there's another page, update max-time and return now. - // The nextPage will already be set up on the next call. - if (drawing_screen && (drawing_screen = u8g.nextPage())) { - if (on_status_screen()) - NOLESS(max_display_update_time, millis() - ms); - return; - } - } + run_current_screen(); - #else - - run_current_screen(); + #endif - #endif + TERN_(HAS_LCD_MENU, lcd_clicked = false); - TERN_(HAS_LCD_MENU, lcd_clicked = false); + // Keeping track of the longest time for an individual LCD update. + // Used to do screen throttling when the planner starts to fill up. + if (on_status_screen()) + NOLESS(max_display_update_time, millis() - ms); + } - // Keeping track of the longest time for an individual LCD update. - // Used to do screen throttling when the planner starts to fill up. - if (on_status_screen()) - NOLESS(max_display_update_time, millis() - ms); - } + #if SCREENS_CAN_TIME_OUT + // Return to Status Screen after a timeout + if (on_status_screen() || defer_return_to_status) + reset_status_timeout(ms); + else if (ELAPSED(ms, return_to_status_ms)) + return_to_status(); + #endif - #if HAS_LCD_MENU && LCD_TIMEOUT_TO_STATUS > 0 - // Return to Status Screen after a timeout - if (on_status_screen() || defer_return_to_status) - RESET_STATUS_TIMEOUT(); - else if (ELAPSED(ms, return_to_status_ms)) - return_to_status(); - #endif + // Change state of drawing flag between screen updates + if (!drawing_screen) switch (lcdDrawUpdate) { + case LCDVIEW_CLEAR_CALL_REDRAW: + clear_lcd(); break; + case LCDVIEW_REDRAW_NOW: + refresh(LCDVIEW_NONE); + case LCDVIEW_NONE: + case LCDVIEW_CALL_REDRAW_NEXT: + case LCDVIEW_CALL_NO_REDRAW: + default: break; + } // switch - // Change state of drawing flag between screen updates - if (!drawing_screen) switch (lcdDrawUpdate) { - case LCDVIEW_CLEAR_CALL_REDRAW: - clear_lcd(); break; - case LCDVIEW_REDRAW_NOW: - refresh(LCDVIEW_NONE); - case LCDVIEW_NONE: - case LCDVIEW_CALL_REDRAW_NEXT: - case LCDVIEW_CALL_NO_REDRAW: - default: break; - } // switch + } // ELAPSED(ms, next_lcd_update_ms) - } // ELAPSED(ms, next_lcd_update_ms) + TERN_(HAS_GRAPHICAL_TFT, tft_idle()); + } - TERN_(HAS_GRAPHICAL_TFT, tft_idle()); -} + #if HAS_ADC_BUTTONS -#if HAS_ADC_BUTTONS + typedef struct { + uint16_t ADCKeyValueMin, ADCKeyValueMax; + uint8_t ADCKeyNo; + } _stADCKeypadTable_; - typedef struct { - uint16_t ADCKeyValueMin, ADCKeyValueMax; - uint8_t ADCKeyNo; - } _stADCKeypadTable_; + #ifndef ADC_BUTTONS_VALUE_SCALE + #define ADC_BUTTONS_VALUE_SCALE 1.0 // for the power voltage equal to the reference voltage + #endif + #ifndef ADC_BUTTONS_R_PULLUP + #define ADC_BUTTONS_R_PULLUP 4.7 // common pull-up resistor in the voltage divider + #endif + #ifndef ADC_BUTTONS_LEFT_R_PULLDOWN + #define ADC_BUTTONS_LEFT_R_PULLDOWN 0.47 // pull-down resistor for LEFT button voltage divider + #endif + #ifndef ADC_BUTTONS_RIGHT_R_PULLDOWN + #define ADC_BUTTONS_RIGHT_R_PULLDOWN 4.7 // pull-down resistor for RIGHT button voltage divider + #endif + #ifndef ADC_BUTTONS_UP_R_PULLDOWN + #define ADC_BUTTONS_UP_R_PULLDOWN 1.0 // pull-down resistor for UP button voltage divider + #endif + #ifndef ADC_BUTTONS_DOWN_R_PULLDOWN + #define ADC_BUTTONS_DOWN_R_PULLDOWN 10.0 // pull-down resistor for DOWN button voltage divider + #endif + #ifndef ADC_BUTTONS_MIDDLE_R_PULLDOWN + #define ADC_BUTTONS_MIDDLE_R_PULLDOWN 2.2 // pull-down resistor for MIDDLE button voltage divider + #endif - #ifndef ADC_BUTTONS_VALUE_SCALE - #define ADC_BUTTONS_VALUE_SCALE 1.0 // for the power voltage equal to the reference voltage - #endif - #ifndef ADC_BUTTONS_R_PULLUP - #define ADC_BUTTONS_R_PULLUP 4.7 // common pull-up resistor in the voltage divider - #endif - #ifndef ADC_BUTTONS_LEFT_R_PULLDOWN - #define ADC_BUTTONS_LEFT_R_PULLDOWN 0.47 // pull-down resistor for LEFT button voltage divider - #endif - #ifndef ADC_BUTTONS_RIGHT_R_PULLDOWN - #define ADC_BUTTONS_RIGHT_R_PULLDOWN 4.7 // pull-down resistor for RIGHT button voltage divider - #endif - #ifndef ADC_BUTTONS_UP_R_PULLDOWN - #define ADC_BUTTONS_UP_R_PULLDOWN 1.0 // pull-down resistor for UP button voltage divider - #endif - #ifndef ADC_BUTTONS_DOWN_R_PULLDOWN - #define ADC_BUTTONS_DOWN_R_PULLDOWN 10.0 // pull-down resistor for DOWN button voltage divider - #endif - #ifndef ADC_BUTTONS_MIDDLE_R_PULLDOWN - #define ADC_BUTTONS_MIDDLE_R_PULLDOWN 2.2 // pull-down resistor for MIDDLE button voltage divider - #endif + // Calculate the ADC value for the voltage divider with specified pull-down resistor value + #define ADC_BUTTON_VALUE(r) int(HAL_ADC_RANGE * (ADC_BUTTONS_VALUE_SCALE) * r / (r + ADC_BUTTONS_R_PULLUP)) + + static constexpr uint16_t adc_button_tolerance = HAL_ADC_RANGE * 25 / 1024, + adc_other_button = HAL_ADC_RANGE * 1000 / 1024; + static const _stADCKeypadTable_ stADCKeyTable[] PROGMEM = { + // VALUE_MIN, VALUE_MAX, KEY + { adc_other_button, HAL_ADC_RANGE, 1 + BLEN_KEYPAD_F1 }, // F1 + { adc_other_button, HAL_ADC_RANGE, 1 + BLEN_KEYPAD_F2 }, // F2 + { adc_other_button, HAL_ADC_RANGE, 1 + BLEN_KEYPAD_F3 }, // F3 + { ADC_BUTTON_VALUE(ADC_BUTTONS_LEFT_R_PULLDOWN) - adc_button_tolerance, + ADC_BUTTON_VALUE(ADC_BUTTONS_LEFT_R_PULLDOWN) + adc_button_tolerance, 1 + BLEN_KEYPAD_LEFT }, // LEFT ( 272 ... 472) + { ADC_BUTTON_VALUE(ADC_BUTTONS_RIGHT_R_PULLDOWN) - adc_button_tolerance, + ADC_BUTTON_VALUE(ADC_BUTTONS_RIGHT_R_PULLDOWN) + adc_button_tolerance, 1 + BLEN_KEYPAD_RIGHT }, // RIGHT (1948 ... 2148) + { ADC_BUTTON_VALUE(ADC_BUTTONS_UP_R_PULLDOWN) - adc_button_tolerance, + ADC_BUTTON_VALUE(ADC_BUTTONS_UP_R_PULLDOWN) + adc_button_tolerance, 1 + BLEN_KEYPAD_UP }, // UP ( 618 ... 818) + { ADC_BUTTON_VALUE(ADC_BUTTONS_DOWN_R_PULLDOWN) - adc_button_tolerance, + ADC_BUTTON_VALUE(ADC_BUTTONS_DOWN_R_PULLDOWN) + adc_button_tolerance, 1 + BLEN_KEYPAD_DOWN }, // DOWN (2686 ... 2886) + { ADC_BUTTON_VALUE(ADC_BUTTONS_MIDDLE_R_PULLDOWN) - adc_button_tolerance, + ADC_BUTTON_VALUE(ADC_BUTTONS_MIDDLE_R_PULLDOWN) + adc_button_tolerance, 1 + BLEN_KEYPAD_MIDDLE }, // ENTER (1205 ... 1405) + }; - // Calculate the ADC value for the voltage divider with specified pull-down resistor value - #define ADC_BUTTON_VALUE(r) int(HAL_ADC_RANGE * (ADC_BUTTONS_VALUE_SCALE) * r / (r + ADC_BUTTONS_R_PULLUP)) - - static constexpr uint16_t adc_button_tolerance = HAL_ADC_RANGE * 25 / 1024, - adc_other_button = HAL_ADC_RANGE * 1000 / 1024; - static const _stADCKeypadTable_ stADCKeyTable[] PROGMEM = { - // VALUE_MIN, VALUE_MAX, KEY - { adc_other_button, HAL_ADC_RANGE, 1 + BLEN_KEYPAD_F1 }, // F1 - { adc_other_button, HAL_ADC_RANGE, 1 + BLEN_KEYPAD_F2 }, // F2 - { adc_other_button, HAL_ADC_RANGE, 1 + BLEN_KEYPAD_F3 }, // F3 - { ADC_BUTTON_VALUE(ADC_BUTTONS_LEFT_R_PULLDOWN) - adc_button_tolerance, - ADC_BUTTON_VALUE(ADC_BUTTONS_LEFT_R_PULLDOWN) + adc_button_tolerance, 1 + BLEN_KEYPAD_LEFT }, // LEFT ( 272 ... 472) - { ADC_BUTTON_VALUE(ADC_BUTTONS_RIGHT_R_PULLDOWN) - adc_button_tolerance, - ADC_BUTTON_VALUE(ADC_BUTTONS_RIGHT_R_PULLDOWN) + adc_button_tolerance, 1 + BLEN_KEYPAD_RIGHT }, // RIGHT (1948 ... 2148) - { ADC_BUTTON_VALUE(ADC_BUTTONS_UP_R_PULLDOWN) - adc_button_tolerance, - ADC_BUTTON_VALUE(ADC_BUTTONS_UP_R_PULLDOWN) + adc_button_tolerance, 1 + BLEN_KEYPAD_UP }, // UP ( 618 ... 818) - { ADC_BUTTON_VALUE(ADC_BUTTONS_DOWN_R_PULLDOWN) - adc_button_tolerance, - ADC_BUTTON_VALUE(ADC_BUTTONS_DOWN_R_PULLDOWN) + adc_button_tolerance, 1 + BLEN_KEYPAD_DOWN }, // DOWN (2686 ... 2886) - { ADC_BUTTON_VALUE(ADC_BUTTONS_MIDDLE_R_PULLDOWN) - adc_button_tolerance, - ADC_BUTTON_VALUE(ADC_BUTTONS_MIDDLE_R_PULLDOWN) + adc_button_tolerance, 1 + BLEN_KEYPAD_MIDDLE }, // ENTER (1205 ... 1405) - }; - - uint8_t get_ADC_keyValue() { - if (thermalManager.ADCKey_count >= 16) { - const uint16_t currentkpADCValue = thermalManager.current_ADCKey_raw; - thermalManager.current_ADCKey_raw = HAL_ADC_RANGE; - thermalManager.ADCKey_count = 0; - if (currentkpADCValue < adc_other_button) - LOOP_L_N(i, ADC_KEY_NUM) { - const uint16_t lo = pgm_read_word(&stADCKeyTable[i].ADCKeyValueMin), - hi = pgm_read_word(&stADCKeyTable[i].ADCKeyValueMax); - if (WITHIN(currentkpADCValue, lo, hi)) return pgm_read_byte(&stADCKeyTable[i].ADCKeyNo); - } + uint8_t get_ADC_keyValue() { + if (thermalManager.ADCKey_count >= 16) { + const uint16_t currentkpADCValue = thermalManager.current_ADCKey_raw; + thermalManager.current_ADCKey_raw = HAL_ADC_RANGE; + thermalManager.ADCKey_count = 0; + if (currentkpADCValue < adc_other_button) + LOOP_L_N(i, ADC_KEY_NUM) { + const uint16_t lo = pgm_read_word(&stADCKeyTable[i].ADCKeyValueMin), + hi = pgm_read_word(&stADCKeyTable[i].ADCKeyValueMax); + if (WITHIN(currentkpADCValue, lo, hi)) return pgm_read_byte(&stADCKeyTable[i].ADCKeyNo); + } + } + return 0; } - return 0; - } -#endif // HAS_ADC_BUTTONS + #endif // HAS_ADC_BUTTONS -#if HAS_ENCODER_ACTION + #if HAS_ENCODER_ACTION - /** - * Read encoder buttons from the hardware registers - * Warning: This function is called from interrupt context! - */ - void MarlinUI::update_buttons() { - const millis_t now = millis(); - if (ELAPSED(now, next_button_update_ms)) { + /** + * Read encoder buttons from the hardware registers + * Warning: This function is called from interrupt context! + */ + void MarlinUI::update_buttons() { + const millis_t now = millis(); + if (ELAPSED(now, next_button_update_ms)) { - #if HAS_DIGITAL_BUTTONS + #if HAS_DIGITAL_BUTTONS - #if ANY_BUTTON(EN1, EN2, ENC, BACK) + #if ANY_BUTTON(EN1, EN2, ENC, BACK) - uint8_t newbutton = 0; - if (BUTTON_PRESSED(EN1)) newbutton |= EN_A; - if (BUTTON_PRESSED(EN2)) newbutton |= EN_B; - if (can_encode() && BUTTON_PRESSED(ENC)) newbutton |= EN_C; - if (BUTTON_PRESSED(BACK)) newbutton |= EN_D; + uint8_t newbutton = 0; + if (BUTTON_PRESSED(EN1)) newbutton |= EN_A; + if (BUTTON_PRESSED(EN2)) newbutton |= EN_B; + if (can_encode() && BUTTON_PRESSED(ENC)) newbutton |= EN_C; + if (BUTTON_PRESSED(BACK)) newbutton |= EN_D; - #else + #else - constexpr uint8_t newbutton = 0; + constexpr uint8_t newbutton = 0; - #endif + #endif - // - // Directional buttons - // - #if ANY_BUTTON(UP, DWN, LFT, RT) + // + // Directional buttons + // + #if ANY_BUTTON(UP, DWN, LFT, RT) - const int8_t pulses = epps * encoderDirection; + const int8_t pulses = epps * encoderDirection; - if (BUTTON_PRESSED(UP)) { - encoderDiff = (ENCODER_STEPS_PER_MENU_ITEM) * pulses; - next_button_update_ms = now + 300; - } - else if (BUTTON_PRESSED(DWN)) { - encoderDiff = -(ENCODER_STEPS_PER_MENU_ITEM) * pulses; - next_button_update_ms = now + 300; - } - else if (BUTTON_PRESSED(LFT)) { - encoderDiff = -pulses; - next_button_update_ms = now + 300; - } - else if (BUTTON_PRESSED(RT)) { - encoderDiff = pulses; - next_button_update_ms = now + 300; - } + if (BUTTON_PRESSED(UP)) { + encoderDiff = (ENCODER_STEPS_PER_MENU_ITEM) * pulses; + next_button_update_ms = now + 300; + } + else if (BUTTON_PRESSED(DWN)) { + encoderDiff = -(ENCODER_STEPS_PER_MENU_ITEM) * pulses; + next_button_update_ms = now + 300; + } + else if (BUTTON_PRESSED(LFT)) { + encoderDiff = -pulses; + next_button_update_ms = now + 300; + } + else if (BUTTON_PRESSED(RT)) { + encoderDiff = pulses; + next_button_update_ms = now + 300; + } - #endif // UP || DWN || LFT || RT + #endif // UP || DWN || LFT || RT - buttons = (newbutton | TERN0(HAS_SLOW_BUTTONS, slow_buttons) - #if BOTH(HAS_TOUCH_BUTTONS, HAS_ENCODER_ACTION) - | (touch_buttons & TERN(HAS_ENCODER_WHEEL, ~(EN_A | EN_B), 0xFF)) - #endif - ); + buttons = (newbutton | TERN0(HAS_SLOW_BUTTONS, slow_buttons) + #if BOTH(HAS_TOUCH_BUTTONS, HAS_ENCODER_ACTION) + | (touch_buttons & TERN(HAS_ENCODER_WHEEL, ~(EN_A | EN_B), 0xFF)) + #endif + ); - #elif HAS_ADC_BUTTONS + #elif HAS_ADC_BUTTONS - buttons = 0; + buttons = 0; - #endif + #endif - #if HAS_ADC_BUTTONS - if (keypad_buttons == 0) { - const uint8_t b = get_ADC_keyValue(); - if (WITHIN(b, 1, 8)) keypad_buttons = _BV(b - 1); - } - #endif + #if HAS_ADC_BUTTONS + if (keypad_buttons == 0) { + const uint8_t b = get_ADC_keyValue(); + if (WITHIN(b, 1, 8)) keypad_buttons = _BV(b - 1); + } + #endif - #if HAS_SHIFT_ENCODER - /** - * Set up Rotary Encoder bit values (for two pin encoders to indicate movement). - * These values are independent of which pins are used for EN_A / EN_B indications. - * The rotary encoder part is also independent of the LCD chipset. - */ - uint8_t val = 0; - WRITE(SHIFT_LD_PIN, LOW); - WRITE(SHIFT_LD_PIN, HIGH); - LOOP_L_N(i, 8) { - val >>= 1; - if (READ(SHIFT_OUT_PIN)) SBI(val, 7); - WRITE(SHIFT_CLK_PIN, HIGH); - WRITE(SHIFT_CLK_PIN, LOW); - } - TERN(REPRAPWORLD_KEYPAD, keypad_buttons, buttons) = ~val; - #endif + #if HAS_SHIFT_ENCODER + /** + * Set up Rotary Encoder bit values (for two pin encoders to indicate movement). + * These values are independent of which pins are used for EN_A / EN_B indications. + * The rotary encoder part is also independent of the LCD chipset. + */ + uint8_t val = 0; + WRITE(SHIFT_LD_PIN, LOW); + WRITE(SHIFT_LD_PIN, HIGH); + LOOP_L_N(i, 8) { + val >>= 1; + if (READ(SHIFT_OUT_PIN)) SBI(val, 7); + WRITE(SHIFT_CLK_PIN, HIGH); + WRITE(SHIFT_CLK_PIN, LOW); + } + TERN(REPRAPWORLD_KEYPAD, keypad_buttons, buttons) = ~val; + #endif - #if IS_TFTGLCD_PANEL - next_button_update_ms = now + (LCD_UPDATE_INTERVAL / 2); - buttons = slow_buttons; - TERN_(AUTO_BED_LEVELING_UBL, external_encoder()); - #endif + #if IS_TFTGLCD_PANEL + next_button_update_ms = now + (LCD_UPDATE_INTERVAL / 2); + buttons = slow_buttons; + TERN_(AUTO_BED_LEVELING_UBL, external_encoder()); + #endif - } // next_button_update_ms + } // next_button_update_ms - #if HAS_ENCODER_WHEEL - static uint8_t lastEncoderBits; + #if HAS_ENCODER_WHEEL + static uint8_t lastEncoderBits; - // Manage encoder rotation - #define ENCODER_SPIN(_E1, _E2) switch (lastEncoderBits) { case _E1: encoderDiff += encoderDirection; break; case _E2: encoderDiff -= encoderDirection; } + // Manage encoder rotation + #define ENCODER_SPIN(_E1, _E2) switch (lastEncoderBits) { case _E1: encoderDiff += encoderDirection; break; case _E2: encoderDiff -= encoderDirection; } - uint8_t enc = 0; - if (buttons & EN_A) enc |= B01; - if (buttons & EN_B) enc |= B10; - if (enc != lastEncoderBits) { - switch (enc) { - case ENCODER_PHASE_0: ENCODER_SPIN(ENCODER_PHASE_3, ENCODER_PHASE_1); break; - case ENCODER_PHASE_1: ENCODER_SPIN(ENCODER_PHASE_0, ENCODER_PHASE_2); break; - case ENCODER_PHASE_2: ENCODER_SPIN(ENCODER_PHASE_1, ENCODER_PHASE_3); break; - case ENCODER_PHASE_3: ENCODER_SPIN(ENCODER_PHASE_2, ENCODER_PHASE_0); break; + uint8_t enc = 0; + if (buttons & EN_A) enc |= B01; + if (buttons & EN_B) enc |= B10; + if (enc != lastEncoderBits) { + switch (enc) { + case ENCODER_PHASE_0: ENCODER_SPIN(ENCODER_PHASE_3, ENCODER_PHASE_1); break; + case ENCODER_PHASE_1: ENCODER_SPIN(ENCODER_PHASE_0, ENCODER_PHASE_2); break; + case ENCODER_PHASE_2: ENCODER_SPIN(ENCODER_PHASE_1, ENCODER_PHASE_3); break; + case ENCODER_PHASE_3: ENCODER_SPIN(ENCODER_PHASE_2, ENCODER_PHASE_0); break; + } + #if BOTH(HAS_LCD_MENU, AUTO_BED_LEVELING_UBL) + external_encoder(); + #endif + lastEncoderBits = enc; } - #if BOTH(HAS_LCD_MENU, AUTO_BED_LEVELING_UBL) - external_encoder(); - #endif - lastEncoderBits = enc; - } - #endif // HAS_ENCODER_WHEEL - } + #endif // HAS_ENCODER_WHEEL + } -#endif // HAS_ENCODER_ACTION + #endif // HAS_ENCODER_ACTION #endif // HAS_WIRED_LCD @@ -1613,8 +1601,9 @@ void MarlinUI::update() { if (status) { if (old_status < 2) { - TERN_(EXTENSIBLE_UI, ExtUI::onMediaInserted()); // ExtUI response - #if ENABLED(BROWSE_MEDIA_ON_INSERT) + #if ENABLED(EXTENSIBLE_UI) + ExtUI::onMediaInserted(); + #elif ENABLED(BROWSE_MEDIA_ON_INSERT) clear_menu_history(); quick_feedback(); goto_screen(MEDIA_MENU_GATEWAY); @@ -1625,8 +1614,9 @@ void MarlinUI::update() { } else { if (old_status < 2) { - TERN_(EXTENSIBLE_UI, ExtUI::onMediaRemoved()); // ExtUI response - #if PIN_EXISTS(SD_DETECT) + #if ENABLED(EXTENSIBLE_UI) + ExtUI::onMediaRemoved(); + #elif PIN_EXISTS(SD_DETECT) LCD_MESSAGEPGM(MSG_MEDIA_REMOVED); #if HAS_LCD_MENU if (!defer_return_to_status) return_to_status(); diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index ba0221713b535..0f6a8261afe35 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -182,11 +182,7 @@ static bool constexpr processing = false; #endif static void task(); - static void soon(const AxisEnum axis - #if MULTI_E_MANUAL - , const int8_t eindex=-1 - #endif - ); + static void soon(const AxisEnum axis OPTARG(MULTI_E_MANUAL, const int8_t eindex=active_extruder)); }; #endif @@ -449,10 +445,13 @@ class MarlinUI { static PGM_P get_preheat_label(const uint8_t m); #endif + #if SCREENS_CAN_TIME_OUT + static inline void reset_status_timeout(const millis_t ms) { return_to_status_ms = ms + LCD_TIMEOUT_TO_STATUS; } + #else + static inline void reset_status_timeout(const millis_t) {} + #endif + #if HAS_LCD_MENU - #if LCD_TIMEOUT_TO_STATUS - static millis_t return_to_status_ms; - #endif #if HAS_TOUCH_BUTTONS static uint8_t touch_buttons; @@ -478,15 +477,12 @@ class MarlinUI { static void set_selection(const bool sel) { selection = sel; } static bool update_selection(); - static bool lcd_clicked; - static bool use_click(); - static void synchronize(PGM_P const msg=nullptr); static screenFunc_t currentScreen; static bool screen_changed; static void goto_screen(const screenFunc_t screen, const uint16_t encoder=0, const uint8_t top=0, const uint8_t items=0); - static void save_previous_screen(); + static void push_current_screen(); // goto_previous_screen and go_back may also be used as menu item callbacks static void _goto_previous_screen(TERN_(TURBO_BACK_MENU_ITEM, const bool is_back)); @@ -501,12 +497,12 @@ class MarlinUI { static void lcd_in_status(const bool inStatus); #endif + FORCE_INLINE static bool screen_is_sticky() { + return TERN1(SCREENS_CAN_TIME_OUT, defer_return_to_status); + } + FORCE_INLINE static void defer_status_screen(const bool defer=true) { - #if LCD_TIMEOUT_TO_STATUS > 0 - defer_return_to_status = defer; - #else - UNUSED(defer); - #endif + TERN(SCREENS_CAN_TIME_OUT, defer_return_to_status = defer, UNUSED(defer)); } static inline void goto_previous_screen_no_defer() { @@ -531,12 +527,23 @@ class MarlinUI { #elif HAS_WIRED_LCD - static constexpr bool lcd_clicked = false; static constexpr bool on_status_screen() { return true; } FORCE_INLINE static void run_current_screen() { status_screen(); } #endif + #if EITHER(HAS_LCD_MENU, EXTENSIBLE_UI) + static bool lcd_clicked; + static inline bool use_click() { + const bool click = lcd_clicked; + lcd_clicked = false; + return click; + } + #else + static constexpr bool lcd_clicked = false; + static inline bool use_click() { return false; } + #endif + #if BOTH(HAS_LCD_MENU, ADVANCED_PAUSE_FEATURE) static void pause_show_message(const PauseMessage message, const PauseMode mode=PAUSE_MODE_SAME, const uint8_t extruder=active_extruder); #else @@ -647,16 +654,18 @@ class MarlinUI { private: + #if SCREENS_CAN_TIME_OUT + static millis_t return_to_status_ms; + static bool defer_return_to_status; + #else + static constexpr bool defer_return_to_status = false; + #endif + #if HAS_STATUS_MESSAGE static void finish_status(const bool persist); #endif #if HAS_WIRED_LCD - #if HAS_LCD_MENU && LCD_TIMEOUT_TO_STATUS > 0 - static bool defer_return_to_status; - #else - static constexpr bool defer_return_to_status = false; - #endif static void draw_status_screen(); #if HAS_GRAPHICAL_TFT static void tft_idle(); diff --git a/Marlin/src/lcd/menu/menu.cpp b/Marlin/src/lcd/menu/menu.cpp index 6143e8da1ec6f..01c8bb80c0ef2 100644 --- a/Marlin/src/lcd/menu/menu.cpp +++ b/Marlin/src/lcd/menu/menu.cpp @@ -50,9 +50,12 @@ int8_t encoderTopLine, encoderLine, screen_items; typedef struct { - screenFunc_t menu_function; - uint32_t encoder_position; - int8_t top_line, items; + screenFunc_t menu_function; // The screen's function + uint32_t encoder_position; // The position of the encoder + int8_t top_line, items; // The amount of scroll, and the number of items + #if SCREENS_CAN_TIME_OUT + bool sticky; // The screen is sticky + #endif } menuPosition; menuPosition screen_history[6]; uint8_t screen_history_depth = 0; @@ -75,9 +78,9 @@ bool MenuEditItemBase::liveEdit; void MarlinUI::return_to_status() { goto_screen(status_screen); } -void MarlinUI::save_previous_screen() { +void MarlinUI::push_current_screen() { if (screen_history_depth < COUNT(screen_history)) - screen_history[screen_history_depth++] = { currentScreen, encoderPosition, encoderTopLine, screen_items }; + screen_history[screen_history_depth++] = { currentScreen, encoderPosition, encoderTopLine, screen_items OPTARG(SCREENS_CAN_TIME_OUT, screen_is_sticky()) }; } void MarlinUI::_goto_previous_screen(TERN_(TURBO_BACK_MENU_ITEM, const bool is_back/*=false*/)) { @@ -90,6 +93,7 @@ void MarlinUI::_goto_previous_screen(TERN_(TURBO_BACK_MENU_ITEM, const bool is_b is_back ? 0 : sh.top_line, sh.items ); + defer_status_screen(TERN_(SCREENS_CAN_TIME_OUT, sh.sticky)); } else return_to_status(); @@ -147,7 +151,7 @@ void MenuEditItemBase::goto_edit_screen( ) { TERN_(HAS_TOUCH_BUTTONS, ui.on_edit_screen = true); ui.screen_changed = true; - ui.save_previous_screen(); + ui.push_current_screen(); ui.refresh(); editLabel = el; editValue = ev; @@ -237,7 +241,7 @@ void MarlinUI::goto_screen(screenFunc_t screen, const uint16_t encoder/*=0*/, co // void MarlinUI::synchronize(PGM_P const msg/*=nullptr*/) { static PGM_P sync_message = msg ?: GET_TEXT(MSG_MOVING); - save_previous_screen(); + push_current_screen(); goto_screen([]{ if (should_draw()) MenuItem_static::draw(LCD_HEIGHT >= 4, sync_message); }); @@ -371,6 +375,7 @@ void MenuItem_confirm::select_screen( selectFunc_t yesFunc, selectFunc_t noFunc, PGM_P const pref, const char * const string/*=nullptr*/, PGM_P const suff/*=nullptr*/ ) { + ui.defer_status_screen(); const bool ui_selection = ui.update_selection(), got_click = ui.use_click(); if (got_click || ui.should_draw()) { draw_select_screen(yes, no, ui_selection, pref, string, suff); @@ -378,7 +383,6 @@ void MenuItem_confirm::select_screen( selectFunc_t callFunc = ui_selection ? yesFunc : noFunc; if (callFunc) callFunc(); else ui.goto_previous_screen(); } - ui.defer_status_screen(); } } diff --git a/Marlin/src/lcd/menu/menu.h b/Marlin/src/lcd/menu/menu.h index 290832c49c684..28d377da0cf26 100644 --- a/Marlin/src/lcd/menu/menu.h +++ b/Marlin/src/lcd/menu/menu.h @@ -132,14 +132,15 @@ class MenuItem_confirm : public MenuItemBase { // The Menu Edit shadow value typedef union { - bool state; - float decimal; - int8_t int8; - int16_t int16; - int32_t int32; - uint8_t uint8; - uint16_t uint16; - uint32_t uint32; + bool state; + float decimal; + int8_t int8; + int16_t int16; + int32_t int32; + uint8_t uint8; + uint16_t uint16; + uint32_t uint32; + celsius_t celsius; } chimera_t; extern chimera_t editable; diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index e751b534466f9..a6719f1847582 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -68,10 +68,7 @@ void menu_backlash(); START_MENU(); BACK_ITEM(MSG_ADVANCED_SETTINGS); #define EDIT_DAC_PERCENT(A) EDIT_ITEM(uint8, MSG_DAC_PERCENT_##A, &driverPercent[_AXIS(A)], 0, 100, []{ stepper_dac.set_current_percents(driverPercent); }) - EDIT_DAC_PERCENT(X); - EDIT_DAC_PERCENT(Y); - EDIT_DAC_PERCENT(Z); - EDIT_DAC_PERCENT(E); + LOGICAL_AXIS_CODE(EDIT_DAC_PERCENT(E), EDIT_DAC_PERCENT(X), EDIT_DAC_PERCENT(Y), EDIT_DAC_PERCENT(Z), EDIT_DAC_PERCENT(I), EDIT_DAC_PERCENT(J), EDIT_DAC_PERCENT(K)); ACTION_ITEM(MSG_DAC_EEPROM_WRITE, stepper_dac.commit_eeprom); END_MENU(); } @@ -359,7 +356,7 @@ void menu_backlash(); #elif ENABLED(LIMITED_MAX_FR_EDITING) DEFAULT_MAX_FEEDRATE #else - { 9999, 9999, 9999, 9999 } + LOGICAL_AXIS_ARRAY(9999, 9999, 9999, 9999, 9999, 9999, 9999) #endif ; #if ENABLED(LIMITED_MAX_FR_EDITING) && !defined(MAX_FEEDRATE_EDIT_VALUES) @@ -372,9 +369,7 @@ void menu_backlash(); BACK_ITEM(MSG_ADVANCED_SETTINGS); #define EDIT_VMAX(N) EDIT_ITEM_FAST(float5, MSG_VMAX_##N, &planner.settings.max_feedrate_mm_s[_AXIS(N)], 1, max_fr_edit_scaled[_AXIS(N)]) - EDIT_VMAX(A); - EDIT_VMAX(B); - EDIT_VMAX(C); + LINEAR_AXIS_CODE(EDIT_VMAX(A), EDIT_VMAX(B), EDIT_VMAX(C), EDIT_VMAX(I), EDIT_VMAX(J), EDIT_VMAX(K)); #if E_STEPPERS EDIT_ITEM_FAST(float5, MSG_VMAX_E, &planner.settings.max_feedrate_mm_s[E_AXIS_N(active_extruder)], 1, max_fr_edit_scaled.e); @@ -404,7 +399,7 @@ void menu_backlash(); #elif ENABLED(LIMITED_MAX_ACCEL_EDITING) DEFAULT_MAX_ACCELERATION #else - { 99000, 99000, 99000, 99000 } + LOGICAL_AXIS_ARRAY(99000, 99000, 99000, 99000, 99000, 99000, 99000) #endif ; #if ENABLED(LIMITED_MAX_ACCEL_EDITING) && !defined(MAX_ACCEL_EDIT_VALUES) @@ -419,16 +414,19 @@ void menu_backlash(); // M204 P Acceleration EDIT_ITEM_FAST(float5_25, MSG_ACC, &planner.settings.acceleration, 25, max_accel); - // M204 R Retract Acceleration - EDIT_ITEM_FAST(float5, MSG_A_RETRACT, &planner.settings.retract_acceleration, 100, planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(active_extruder)]); + #if HAS_EXTRUDERS + // M204 R Retract Acceleration + EDIT_ITEM_FAST(float5, MSG_A_RETRACT, &planner.settings.retract_acceleration, 100, planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(active_extruder)]); + #endif // M204 T Travel Acceleration EDIT_ITEM_FAST(float5_25, MSG_A_TRAVEL, &planner.settings.travel_acceleration, 25, max_accel); #define EDIT_AMAX(Q,L) EDIT_ITEM_FAST(long5_25, MSG_AMAX_##Q, &planner.settings.max_acceleration_mm_per_s2[_AXIS(Q)], L, max_accel_edit_scaled[_AXIS(Q)], []{ planner.reset_acceleration_rates(); }) - EDIT_AMAX(A, 100); - EDIT_AMAX(B, 100); - EDIT_AMAX(C, 10); + LINEAR_AXIS_CODE( + EDIT_AMAX(A, 100), EDIT_AMAX(B, 100), EDIT_AMAX(C, 10), + EDIT_AMAX(I, 10), EDIT_AMAX(J, 10), EDIT_AMAX(K, 10) + ); #if ENABLED(DISTINCT_E_FACTORS) EDIT_ITEM_FAST(long5_25, MSG_AMAX_E, &planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(active_extruder)], 100, max_accel_edit_scaled.e, []{ planner.reset_acceleration_rates(); }); @@ -474,14 +472,17 @@ void menu_backlash(); #endif ; #define EDIT_JERK(N) EDIT_ITEM_FAST(float3, MSG_V##N##_JERK, &planner.max_jerk[_AXIS(N)], 1, max_jerk_edit[_AXIS(N)]) - EDIT_JERK(A); - EDIT_JERK(B); #if ENABLED(DELTA) - EDIT_JERK(C); + #define EDIT_JERK_C() EDIT_JERK(C) #else - EDIT_ITEM_FAST(float52sign, MSG_VC_JERK, &planner.max_jerk.c, 0.1f, max_jerk_edit.c); + #define EDIT_JERK_C() EDIT_ITEM_FAST(float52sign, MSG_VC_JERK, &planner.max_jerk.c, 0.1f, max_jerk_edit.c) #endif - #if HAS_CLASSIC_E_JERK + LINEAR_AXIS_CODE( + EDIT_JERK(A), EDIT_JERK(B), EDIT_JERK_C(), + EDIT_JERK(I), EDIT_JERK(J), EDIT_JERK(K) + ); + + #if HAS_EXTRUDERS EDIT_ITEM_FAST(float52sign, MSG_VE_JERK, &planner.max_jerk.e, 0.1f, max_jerk_edit.e); #endif @@ -517,9 +518,10 @@ void menu_advanced_steps_per_mm() { BACK_ITEM(MSG_ADVANCED_SETTINGS); #define EDIT_QSTEPS(Q) EDIT_ITEM_FAST(float51, MSG_##Q##_STEPS, &planner.settings.axis_steps_per_mm[_AXIS(Q)], 5, 9999, []{ planner.refresh_positioning(); }) - EDIT_QSTEPS(A); - EDIT_QSTEPS(B); - EDIT_QSTEPS(C); + LINEAR_AXIS_CODE( + EDIT_QSTEPS(A), EDIT_QSTEPS(B), EDIT_QSTEPS(C), + EDIT_QSTEPS(I), EDIT_QSTEPS(J), EDIT_QSTEPS(K) + ); #if ENABLED(DISTINCT_E_FACTORS) LOOP_L_N(n, E_STEPPERS) diff --git a/Marlin/src/lcd/menu/menu_backlash.cpp b/Marlin/src/lcd/menu/menu_backlash.cpp index c1dca025b1cb4..b9adacc5021dd 100644 --- a/Marlin/src/lcd/menu/menu_backlash.cpp +++ b/Marlin/src/lcd/menu/menu_backlash.cpp @@ -45,8 +45,21 @@ void menu_backlash() { #endif #define EDIT_BACKLASH_DISTANCE(N) EDIT_ITEM_FAST(float43, MSG_BACKLASH_##N, &backlash.distance_mm[_AXIS(N)], 0.0f, 9.9f); if (_CAN_CALI(A)) EDIT_BACKLASH_DISTANCE(A); - if (_CAN_CALI(B)) EDIT_BACKLASH_DISTANCE(B); - if (_CAN_CALI(C)) EDIT_BACKLASH_DISTANCE(C); + #if HAS_Y_AXIS && _CAN_CALI(B) + EDIT_BACKLASH_DISTANCE(B); + #endif + #if HAS_Z_AXIS && _CAN_CALI(C) + EDIT_BACKLASH_DISTANCE(C); + #endif + #if LINEAR_AXES >= 4 && _CAN_CALI(I) + EDIT_BACKLASH_DISTANCE(I); + #endif + #if LINEAR_AXES >= 5 && _CAN_CALI(J) + EDIT_BACKLASH_DISTANCE(J); + #endif + #if LINEAR_AXES >= 6 && _CAN_CALI(K) + EDIT_BACKLASH_DISTANCE(K); + #endif #ifdef BACKLASH_SMOOTHING_MM EDIT_ITEM_FAST(float43, MSG_BACKLASH_SMOOTHING, &backlash.smoothing_mm, 0.0f, 9.9f); diff --git a/Marlin/src/lcd/menu/menu_item.h b/Marlin/src/lcd/menu/menu_item.h index bcd93e11f8f85..0f2bd3cb1f1cc 100644 --- a/Marlin/src/lcd/menu/menu_item.h +++ b/Marlin/src/lcd/menu/menu_item.h @@ -39,7 +39,7 @@ class MenuItem_submenu : public MenuItemBase { FORCE_INLINE static void draw(const bool sel, const uint8_t row, PGM_P const pstr, ...) { _draw(sel, row, pstr, '>', LCD_STR_ARROW_RIGHT[0]); } - static inline void action(PGM_P const, const screenFunc_t func) { ui.save_previous_screen(); ui.goto_screen(func); } + static inline void action(PGM_P const, const screenFunc_t func) { ui.push_current_screen(); ui.goto_screen(func); } }; // Any menu item that invokes an immediate action @@ -406,7 +406,7 @@ class MenuItem_bool : public MenuEditItemBase { #define _CONFIRM_ITEM_INNER_P(PLABEL, V...) do { \ if (encoderLine == _thisItemNr && ui.use_click()) { \ - ui.save_previous_screen(); \ + ui.push_current_screen(); \ ui.goto_screen([]{MenuItem_confirm::select_screen(V);}); \ return; \ } \ diff --git a/Marlin/src/lcd/menu/menu_led.cpp b/Marlin/src/lcd/menu/menu_led.cpp index 5ab5e8a9d8dc1..284e80c931b76 100644 --- a/Marlin/src/lcd/menu/menu_led.cpp +++ b/Marlin/src/lcd/menu/menu_led.cpp @@ -84,18 +84,20 @@ EDIT_ITEM(uint8, MSG_INTENSITY_R, &leds.color.r, 0, 255, leds.update, true); EDIT_ITEM(uint8, MSG_INTENSITY_G, &leds.color.g, 0, 255, leds.update, true); EDIT_ITEM(uint8, MSG_INTENSITY_B, &leds.color.b, 0, 255, leds.update, true); - #if EITHER(RGBW_LED, NEOPIXEL_LED) + #if HAS_WHITE_LED EDIT_ITEM(uint8, MSG_INTENSITY_W, &leds.color.w, 0, 255, leds.update, true); - #if ENABLED(NEOPIXEL_LED) - EDIT_ITEM(uint8, MSG_LED_BRIGHTNESS, &leds.color.i, 0, 255, leds.update, true); - #endif + #endif + #if ENABLED(NEOPIXEL_LED) + EDIT_ITEM(uint8, MSG_LED_BRIGHTNESS, &leds.color.i, 0, 255, leds.update, true); #endif #if ENABLED(NEOPIXEL2_SEPARATE) STATIC_ITEM_N(MSG_LED_CHANNEL_N, 2, SS_DEFAULT|SS_INVERT); EDIT_ITEM(uint8, MSG_INTENSITY_R, &leds2.color.r, 0, 255, leds2.update, true); EDIT_ITEM(uint8, MSG_INTENSITY_G, &leds2.color.g, 0, 255, leds2.update, true); EDIT_ITEM(uint8, MSG_INTENSITY_B, &leds2.color.b, 0, 255, leds2.update, true); - EDIT_ITEM(uint8, MSG_INTENSITY_W, &leds2.color.w, 0, 255, leds2.update, true); + #if HAS_WHITE_LED2 + EDIT_ITEM(uint8, MSG_INTENSITY_W, &leds2.color.w, 0, 255, leds2.update, true); + #endif EDIT_ITEM(uint8, MSG_NEO2_BRIGHTNESS, &leds2.color.i, 0, 255, leds2.update, true); #endif END_MENU(); diff --git a/Marlin/src/lcd/menu/menu_main.cpp b/Marlin/src/lcd/menu/menu_main.cpp index aad9161b75f81..921c2435b58ae 100644 --- a/Marlin/src/lcd/menu/menu_main.cpp +++ b/Marlin/src/lcd/menu/menu_main.cpp @@ -254,6 +254,38 @@ void menu_main() { START_MENU(); BACK_ITEM(MSG_INFO_SCREEN); + #if ENABLED(SDSUPPORT) + + #if !defined(MEDIA_MENU_AT_TOP) && !HAS_ENCODER_WHEEL + #define MEDIA_MENU_AT_TOP + #endif + + auto sdcard_menu_items = [&]{ + #if ENABLED(MENU_ADDAUTOSTART) + ACTION_ITEM(MSG_RUN_AUTO_FILES, card.autofile_begin); // Run Auto Files + #endif + + if (card_detected) { + if (!card_open) { + #if PIN_EXISTS(SD_DETECT) + GCODES_ITEM(MSG_CHANGE_MEDIA, PSTR("M21")); // M21 Change Media + #else // - or - + GCODES_ITEM(MSG_RELEASE_MEDIA, PSTR("M22")); // M22 Release Media + #endif + SUBMENU(MSG_MEDIA_MENU, MEDIA_MENU_GATEWAY); // Media Menu (or Password First) + } + } + else { + #if PIN_EXISTS(SD_DETECT) + ACTION_ITEM(MSG_NO_MEDIA, nullptr); // "No Media" + #else + GCODES_ITEM(MSG_ATTACH_MEDIA, PSTR("M21")); // M21 Attach Media + #endif + } + }; + + #endif + if (busy) { #if MACHINE_CAN_PAUSE ACTION_ITEM(MSG_PAUSE_PRINT, ui.pause_print); @@ -281,36 +313,9 @@ void menu_main() { } else { - #if !HAS_ENCODER_WHEEL && ENABLED(SDSUPPORT) - - // *** IF THIS SECTION IS CHANGED, REPRODUCE BELOW *** - - // - // Run Auto Files - // - #if ENABLED(MENU_ADDAUTOSTART) - ACTION_ITEM(MSG_RUN_AUTO_FILES, card.autofile_begin); - #endif - - if (card_detected) { - if (!card_open) { - SUBMENU(MSG_MEDIA_MENU, MEDIA_MENU_GATEWAY); - #if PIN_EXISTS(SD_DETECT) - GCODES_ITEM(MSG_CHANGE_MEDIA, PSTR("M21")); - #else - GCODES_ITEM(MSG_RELEASE_MEDIA, PSTR("M22")); - #endif - } - } - else { - #if PIN_EXISTS(SD_DETECT) - ACTION_ITEM(MSG_NO_MEDIA, nullptr); - #else - GCODES_ITEM(MSG_ATTACH_MEDIA, PSTR("M21")); - #endif - } - - #endif // !HAS_ENCODER_WHEEL && SDSUPPORT + #if BOTH(SDSUPPORT, MEDIA_MENU_AT_TOP) + sdcard_menu_items(); + #endif if (TERN0(MACHINE_CAN_PAUSE, printingIsPaused())) ACTION_ITEM(MSG_RESUME_PRINT, ui.resume_print); @@ -387,39 +392,9 @@ void menu_main() { GCODES_ITEM(MSG_SWITCH_PS_ON, PSTR("M80")); #endif - #if BOTH(HAS_ENCODER_WHEEL, SDSUPPORT) - - if (!busy) { - - // *** IF THIS SECTION IS CHANGED, REPRODUCE ABOVE *** - - // - // Autostart - // - #if ENABLED(MENU_ADDAUTOSTART) - ACTION_ITEM(MSG_RUN_AUTO_FILES, card.autofile_begin); - #endif - - if (card_detected) { - if (!card_open) { - #if PIN_EXISTS(SD_DETECT) - GCODES_ITEM(MSG_CHANGE_MEDIA, PSTR("M21")); - #else - GCODES_ITEM(MSG_RELEASE_MEDIA, PSTR("M22")); - #endif - SUBMENU(MSG_MEDIA_MENU, MEDIA_MENU_GATEWAY); - } - } - else { - #if PIN_EXISTS(SD_DETECT) - ACTION_ITEM(MSG_NO_MEDIA, nullptr); - #else - GCODES_ITEM(MSG_ATTACH_MEDIA, PSTR("M21")); - #endif - } - } - - #endif // HAS_ENCODER_WHEEL && SDSUPPORT + #if ENABLED(SDSUPPORT) && DISABLED(MEDIA_MENU_AT_TOP) + sdcard_menu_items(); + #endif #if HAS_SERVICE_INTERVALS static auto _service_reset = [](const int index) { diff --git a/Marlin/src/lcd/menu/menu_media.cpp b/Marlin/src/lcd/menu/menu_media.cpp index 7a525d06b5a02..8630f48b3736f 100644 --- a/Marlin/src/lcd/menu/menu_media.cpp +++ b/Marlin/src/lcd/menu/menu_media.cpp @@ -104,7 +104,7 @@ class MenuItem_sdfolder : public MenuItem_sdbase { } }; -void menu_media() { +void menu_media_filelist() { ui.encoder_direction_menus(); #if HAS_MARLINUI_U8GLIB @@ -115,7 +115,11 @@ void menu_media() { #endif START_MENU(); - BACK_ITEM_P(TERN1(BROWSE_MEDIA_ON_INSERT, screen_history_depth) ? GET_TEXT(MSG_MAIN) : GET_TEXT(MSG_BACK)); + #if ENABLED(MULTI_VOLUME) + ACTION_ITEM(MSG_BACK, []{ ui.goto_screen(menu_media); }); + #else + BACK_ITEM_P(TERN1(BROWSE_MEDIA_ON_INSERT, screen_history_depth) ? GET_TEXT(MSG_MAIN) : GET_TEXT(MSG_BACK)); + #endif if (card.flag.workDirIsRoot) { #if !PIN_EXISTS(SD_DETECT) ACTION_ITEM(MSG_REFRESH, []{ encoderTopLine = 0; card.mount(); }); @@ -138,4 +142,22 @@ void menu_media() { END_MENU(); } +#if ENABLED(MULTI_VOLUME) + void menu_media_select() { + START_MENU(); + BACK_ITEM_P(TERN1(BROWSE_MEDIA_ON_INSERT, screen_history_depth) ? GET_TEXT(MSG_MAIN) : GET_TEXT(MSG_BACK)); + #if ENABLED(VOLUME_SD_ONBOARD) + ACTION_ITEM(MSG_SD_CARD, []{ card.changeMedia(&card.media_driver_sdcard); card.mount(); ui.goto_screen(menu_media_filelist); }); + #endif + #if ENABLED(VOLUME_USB_FLASH_DRIVE) + ACTION_ITEM(MSG_USB_DISK, []{ card.changeMedia(&card.media_driver_usbFlash); card.mount(); ui.goto_screen(menu_media_filelist); }); + #endif + END_MENU(); + } +#endif + +void menu_media() { + TERN(MULTI_VOLUME, menu_media_select, menu_media_filelist)(); +} + #endif // HAS_LCD_MENU && SDSUPPORT diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index 06d635ffc835e..aea5f2357b58d 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -28,6 +28,8 @@ #if HAS_LCD_MENU +#define LARGE_AREA_TEST ((X_BED_SIZE) >= 1000 || (Y_BED_SIZE) >= 1000 || (Z_MAX_POS) >= 1000) + #include "menu_item.h" #include "menu_addon.h" @@ -85,26 +87,35 @@ static void _lcd_move_xyz(PGM_P const name, const AxisEnum axis) { MenuEditItemBase::draw_edit_screen(name, ftostr63(imp_pos)); } else - MenuEditItemBase::draw_edit_screen(name, ui.manual_move.menu_scale >= 0.1f ? ftostr41sign(pos) : ftostr63(pos)); + MenuEditItemBase::draw_edit_screen(name, ui.manual_move.menu_scale >= 0.1f ? (LARGE_AREA_TEST ? ftostr51sign(pos) : ftostr41sign(pos)) : ftostr63(pos)); } } void lcd_move_x() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_X), X_AXIS); } -void lcd_move_y() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_Y), Y_AXIS); } -void lcd_move_z() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_Z), Z_AXIS); } +#if HAS_Y_AXIS + void lcd_move_y() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_Y), Y_AXIS); } +#endif +#if HAS_Z_AXIS + void lcd_move_z() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_Z), Z_AXIS); } +#endif +#if LINEAR_AXES >= 4 + void lcd_move_i() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_I), I_AXIS); } +#endif +#if LINEAR_AXES >= 5 + void lcd_move_j() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_J), J_AXIS); } +#endif +#if LINEAR_AXES >= 6 + void lcd_move_k() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_K), K_AXIS); } +#endif #if E_MANUAL - static void lcd_move_e(TERN_(MULTI_E_MANUAL, const int8_t eindex=-1)) { + static void lcd_move_e(TERN_(MULTI_E_MANUAL, const int8_t eindex=active_extruder)) { if (ui.use_click()) return ui.goto_previous_screen_no_defer(); if (ui.encoderPosition) { if (!ui.manual_move.processing) { const float diff = float(int32_t(ui.encoderPosition)) * ui.manual_move.menu_scale; TERN(IS_KINEMATIC, ui.manual_move.offset, current_position.e) += diff; - ui.manual_move.soon(E_AXIS - #if MULTI_E_MANUAL - , eindex - #endif - ); + ui.manual_move.soon(E_AXIS OPTARG(MULTI_E_MANUAL, eindex)); ui.refresh(LCDVIEW_REDRAW_NOW); } ui.encoderPosition = 0; @@ -139,7 +150,7 @@ void _goto_manual_move(const_float_t scale) { ui.goto_screen(_manual_move_func_ptr); } -void _menu_move_distance(const AxisEnum axis, const screenFunc_t func, const int8_t eindex=-1) { +void _menu_move_distance(const AxisEnum axis, const screenFunc_t func, const int8_t eindex=active_extruder) { _manual_move_func_ptr = func; START_MENU(); if (LCD_HEIGHT >= 4) { @@ -156,11 +167,13 @@ void _menu_move_distance(const AxisEnum axis, const screenFunc_t func, const int BACK_ITEM(MSG_MOVE_AXIS); if (parser.using_inch_units()) { + if (LARGE_AREA_TEST) SUBMENU(MSG_MOVE_1IN, []{ _goto_manual_move(IN_TO_MM(1.000f)); }); SUBMENU(MSG_MOVE_01IN, []{ _goto_manual_move(IN_TO_MM(0.100f)); }); SUBMENU(MSG_MOVE_001IN, []{ _goto_manual_move(IN_TO_MM(0.010f)); }); SUBMENU(MSG_MOVE_0001IN, []{ _goto_manual_move(IN_TO_MM(0.001f)); }); } else { + if (LARGE_AREA_TEST) SUBMENU(MSG_MOVE_100MM, []{ _goto_manual_move(100); }); SUBMENU(MSG_MOVE_10MM, []{ _goto_manual_move(10); }); SUBMENU(MSG_MOVE_1MM, []{ _goto_manual_move( 1); }); SUBMENU(MSG_MOVE_01MM, []{ _goto_manual_move( 0.1f); }); @@ -188,7 +201,7 @@ void _menu_move_distance(const AxisEnum axis, const screenFunc_t func, const int #if E_MANUAL inline void _goto_menu_move_distance_e() { - ui.goto_screen([]{ _menu_move_distance(E_AXIS, []{ lcd_move_e(TERN_(MULTI_E_MANUAL, active_extruder)); }, -1); }); + ui.goto_screen([]{ _menu_move_distance(E_AXIS, []{ lcd_move_e(); }); }); } inline void _menu_move_distance_e_maybe() { @@ -221,14 +234,27 @@ void menu_move() { if (NONE(IS_KINEMATIC, NO_MOTION_BEFORE_HOMING) || all_axes_homed()) { if (TERN1(DELTA, current_position.z <= delta_clip_start_height)) { SUBMENU(MSG_MOVE_X, []{ _menu_move_distance(X_AXIS, lcd_move_x); }); - SUBMENU(MSG_MOVE_Y, []{ _menu_move_distance(Y_AXIS, lcd_move_y); }); + #if HAS_Y_AXIS + SUBMENU(MSG_MOVE_Y, []{ _menu_move_distance(Y_AXIS, lcd_move_y); }); + #endif } #if ENABLED(DELTA) else ACTION_ITEM(MSG_FREE_XY, []{ line_to_z(delta_clip_start_height); ui.synchronize(); }); #endif - SUBMENU(MSG_MOVE_Z, []{ _menu_move_distance(Z_AXIS, lcd_move_z); }); + #if HAS_Z_AXIS + SUBMENU(MSG_MOVE_Z, []{ _menu_move_distance(Z_AXIS, lcd_move_z); }); + #endif + #if LINEAR_AXES >= 4 + SUBMENU(MSG_MOVE_I, []{ _menu_move_distance(I_AXIS, lcd_move_i); }); + #endif + #if LINEAR_AXES >= 5 + SUBMENU(MSG_MOVE_J, []{ _menu_move_distance(J_AXIS, lcd_move_j); }); + #endif + #if LINEAR_AXES >= 6 + SUBMENU(MSG_MOVE_K, []{ _menu_move_distance(K_AXIS, lcd_move_k); }); + #endif } else GCODES_ITEM(MSG_AUTO_HOME, G28_STR); @@ -325,8 +351,21 @@ void menu_motion() { GCODES_ITEM(MSG_AUTO_HOME, G28_STR); #if ENABLED(INDIVIDUAL_AXIS_HOMING_MENU) GCODES_ITEM(MSG_AUTO_HOME_X, PSTR("G28X")); - GCODES_ITEM(MSG_AUTO_HOME_Y, PSTR("G28Y")); - GCODES_ITEM(MSG_AUTO_HOME_Z, PSTR("G28Z")); + #if HAS_Y_AXIS + GCODES_ITEM(MSG_AUTO_HOME_Y, PSTR("G28Y")); + #endif + #if HAS_Z_AXIS + GCODES_ITEM(MSG_AUTO_HOME_Z, PSTR("G28Z")); + #endif + #if LINEAR_AXES >= 4 + GCODES_ITEM(MSG_AUTO_HOME_I, PSTR("G28" I_STR)); + #endif + #if LINEAR_AXES >= 5 + GCODES_ITEM(MSG_AUTO_HOME_J, PSTR("G28" J_STR)); + #endif + #if LINEAR_AXES >= 6 + GCODES_ITEM(MSG_AUTO_HOME_K, PSTR("G28" K_STR)); + #endif #endif // diff --git a/Marlin/src/lcd/menu/menu_password.cpp b/Marlin/src/lcd/menu/menu_password.cpp index 590ce48d592e7..d3a35abff2e0e 100644 --- a/Marlin/src/lcd/menu/menu_password.cpp +++ b/Marlin/src/lcd/menu/menu_password.cpp @@ -177,7 +177,7 @@ void Password::menu_password() { START_MENU(); BACK_ITEM(MSG_ADVANCED_SETTINGS); SUBMENU(MSG_CHANGE_PASSWORD, screen_set_password); - ACTION_ITEM(MSG_REMOVE_PASSWORD, []{ ui.save_previous_screen(); remove_password(); } ); + ACTION_ITEM(MSG_REMOVE_PASSWORD, []{ ui.push_current_screen(); remove_password(); } ); #if ENABLED(EEPROM_SETTINGS) ACTION_ITEM(MSG_STORE_EEPROM, ui.store_settings); #endif diff --git a/Marlin/src/lcd/menu/menu_probe_offset.cpp b/Marlin/src/lcd/menu/menu_probe_offset.cpp index 008db6a8b842c..5ed217131a1fe 100644 --- a/Marlin/src/lcd/menu/menu_probe_offset.cpp +++ b/Marlin/src/lcd/menu/menu_probe_offset.cpp @@ -42,7 +42,7 @@ // Global storage float z_offset_backup, calculated_z_offset, z_offset_ref; -#if ENABLED(HAS_LEVELING) +#if HAS_LEVELING bool leveling_was_active; #endif diff --git a/Marlin/src/lcd/menu/menu_temperature.cpp b/Marlin/src/lcd/menu/menu_temperature.cpp index 33a3d2f44541f..65cef5b76df75 100644 --- a/Marlin/src/lcd/menu/menu_temperature.cpp +++ b/Marlin/src/lcd/menu/menu_temperature.cpp @@ -57,8 +57,14 @@ void Temperature::lcd_preheat(const uint8_t e, const int8_t indh, const int8_t i if (indb >= 0 && ui.material_preset[indb].bed_temp > 0) setTargetBed(ui.material_preset[indb].bed_temp); #endif #if HAS_FAN - if (indh >= 0) - set_fan_speed(active_extruder < (FAN_COUNT) ? active_extruder : 0, ui.material_preset[indh].fan_speed); + if (indh >= 0) { + const uint8_t fan_index = active_extruder < (FAN_COUNT) ? active_extruder : 0; + if (true + #if REDUNDANT_PART_COOLING_FAN + && fan_index != REDUNDANT_PART_COOLING_FAN + #endif + ) set_fan_speed(fan_index, ui.material_preset[indh].fan_speed); + } #endif ui.return_to_status(); } @@ -163,10 +169,13 @@ void menu_temperature() { // Nozzle [1-5]: // #if HOTENDS == 1 - EDIT_ITEM_FAST(int3, MSG_NOZZLE, &thermalManager.temp_hotend[0].target, 0, thermalManager.hotend_max_target(0), []{ thermalManager.start_watching_hotend(0); }); + editable.celsius = thermalManager.temp_hotend[0].target; + EDIT_ITEM_FAST(int3, MSG_NOZZLE, &editable.celsius, 0, thermalManager.hotend_max_target(0), []{ thermalManager.setTargetHotend(editable.celsius, 0); }); #elif HAS_MULTI_HOTEND - HOTEND_LOOP() - EDIT_ITEM_FAST_N(int3, e, MSG_NOZZLE_N, &thermalManager.temp_hotend[e].target, 0, thermalManager.hotend_max_target(e), []{ thermalManager.start_watching_hotend(MenuItemBase::itemIndex); }); + HOTEND_LOOP() { + editable.celsius = thermalManager.temp_hotend[e].target; + EDIT_ITEM_FAST_N(int3, e, MSG_NOZZLE_N, &editable.celsius, 0, thermalManager.hotend_max_target(e), []{ thermalManager.setTargetHotend(editable.celsius, MenuItemBase::itemIndex); }); + } #endif #if ENABLED(SINGLENOZZLE_STANDBY_TEMP) @@ -215,37 +224,37 @@ void menu_temperature() { #if HAS_FAN0 _FAN_EDIT_ITEMS(0,FIRST_FAN_SPEED); #endif - #if HAS_FAN1 + #if HAS_FAN1 && REDUNDANT_PART_COOLING_FAN != 1 FAN_EDIT_ITEMS(1); #elif SNFAN(1) singlenozzle_item(1); #endif - #if HAS_FAN2 + #if HAS_FAN2 && REDUNDANT_PART_COOLING_FAN != 2 FAN_EDIT_ITEMS(2); #elif SNFAN(2) singlenozzle_item(2); #endif - #if HAS_FAN3 + #if HAS_FAN3 && REDUNDANT_PART_COOLING_FAN != 3 FAN_EDIT_ITEMS(3); #elif SNFAN(3) singlenozzle_item(3); #endif - #if HAS_FAN4 + #if HAS_FAN4 && REDUNDANT_PART_COOLING_FAN != 4 FAN_EDIT_ITEMS(4); #elif SNFAN(4) singlenozzle_item(4); #endif - #if HAS_FAN5 + #if HAS_FAN5 && REDUNDANT_PART_COOLING_FAN != 5 FAN_EDIT_ITEMS(5); #elif SNFAN(5) singlenozzle_item(5); #endif - #if HAS_FAN6 + #if HAS_FAN6 && REDUNDANT_PART_COOLING_FAN != 6 FAN_EDIT_ITEMS(6); #elif SNFAN(6) singlenozzle_item(6); #endif - #if HAS_FAN7 + #if HAS_FAN7 && REDUNDANT_PART_COOLING_FAN != 7 FAN_EDIT_ITEMS(7); #elif SNFAN(7) singlenozzle_item(7); diff --git a/Marlin/src/lcd/menu/menu_tmc.cpp b/Marlin/src/lcd/menu/menu_tmc.cpp index 69193701eb1ff..ad7d632058797 100644 --- a/Marlin/src/lcd/menu/menu_tmc.cpp +++ b/Marlin/src/lcd/menu/menu_tmc.cpp @@ -95,54 +95,22 @@ void menu_tmc_current() { void menu_tmc_hybrid_thrs() { START_MENU(); BACK_ITEM(MSG_TMC_DRIVERS); - #if AXIS_HAS_STEALTHCHOP(X) - TMC_EDIT_STORED_HYBRID_THRS(X, STR_X); - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - TMC_EDIT_STORED_HYBRID_THRS(Y, STR_Y); - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - TMC_EDIT_STORED_HYBRID_THRS(Z, STR_Z); - #endif - #if AXIS_HAS_STEALTHCHOP(X2) - TMC_EDIT_STORED_HYBRID_THRS(X2, STR_X2); - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - TMC_EDIT_STORED_HYBRID_THRS(Y2, STR_Y2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - TMC_EDIT_STORED_HYBRID_THRS(Z2, STR_Z2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z3) - TMC_EDIT_STORED_HYBRID_THRS(Z3, STR_Z3); - #endif - #if AXIS_HAS_STEALTHCHOP(Z4) - TMC_EDIT_STORED_HYBRID_THRS(Z4, STR_Z4); - #endif - #if AXIS_HAS_STEALTHCHOP(E0) - TMC_EDIT_STORED_HYBRID_THRS(E0, LCD_STR_E0); - #endif - #if AXIS_HAS_STEALTHCHOP(E1) - TMC_EDIT_STORED_HYBRID_THRS(E1, LCD_STR_E1); - #endif - #if AXIS_HAS_STEALTHCHOP(E2) - TMC_EDIT_STORED_HYBRID_THRS(E2, LCD_STR_E2); - #endif - #if AXIS_HAS_STEALTHCHOP(E3) - TMC_EDIT_STORED_HYBRID_THRS(E3, LCD_STR_E3); - #endif - #if AXIS_HAS_STEALTHCHOP(E4) - TMC_EDIT_STORED_HYBRID_THRS(E4, LCD_STR_E4); - #endif - #if AXIS_HAS_STEALTHCHOP(E5) - TMC_EDIT_STORED_HYBRID_THRS(E5, LCD_STR_E5); - #endif - #if AXIS_HAS_STEALTHCHOP(E6) - TMC_EDIT_STORED_HYBRID_THRS(E6, LCD_STR_E6); - #endif - #if AXIS_HAS_STEALTHCHOP(E7) - TMC_EDIT_STORED_HYBRID_THRS(E7, LCD_STR_E7); - #endif + TERN_(X_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(X, STR_X)); + TERN_(Y_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(Y, STR_Y)); + TERN_(Z_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(Z, STR_Z)); + TERN_(X2_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(X2, STR_X2)); + TERN_(Y2_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(Y2, STR_Y2)); + TERN_(Z2_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(Z2, STR_Z2)); + TERN_(Z3_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(Z3, STR_Z3)); + TERN_(Z4_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(Z4, STR_Z4)); + TERN_(E0_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E0, LCD_STR_E0)); + TERN_(E1_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E1, LCD_STR_E1)); + TERN_(E2_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E2, LCD_STR_E2)); + TERN_(E3_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E3, LCD_STR_E3)); + TERN_(E4_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E4, LCD_STR_E4)); + TERN_(E5_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E5, LCD_STR_E5)); + TERN_(E6_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E6, LCD_STR_E6)); + TERN_(E7_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E7, LCD_STR_E7)); END_MENU(); } @@ -155,30 +123,17 @@ void menu_tmc_current() { void menu_tmc_homing_thrs() { START_MENU(); BACK_ITEM(MSG_TMC_DRIVERS); - #if X_SENSORLESS - TMC_EDIT_STORED_SGT(X); - #if X2_SENSORLESS - TMC_EDIT_STORED_SGT(X2); - #endif - #endif - #if Y_SENSORLESS - TMC_EDIT_STORED_SGT(Y); - #if Y2_SENSORLESS - TMC_EDIT_STORED_SGT(Y2); - #endif - #endif - #if Z_SENSORLESS - TMC_EDIT_STORED_SGT(Z); - #if Z2_SENSORLESS - TMC_EDIT_STORED_SGT(Z2); - #endif - #if Z3_SENSORLESS - TMC_EDIT_STORED_SGT(Z3); - #endif - #if Z4_SENSORLESS - TMC_EDIT_STORED_SGT(Z4); - #endif - #endif + TERN_( X_SENSORLESS, TMC_EDIT_STORED_SGT(X)); + TERN_(X2_SENSORLESS, TMC_EDIT_STORED_SGT(X2)); + TERN_( Y_SENSORLESS, TMC_EDIT_STORED_SGT(Y)); + TERN_(Y2_SENSORLESS, TMC_EDIT_STORED_SGT(Y2)); + TERN_( Z_SENSORLESS, TMC_EDIT_STORED_SGT(Z)); + TERN_(Z2_SENSORLESS, TMC_EDIT_STORED_SGT(Z2)); + TERN_(Z3_SENSORLESS, TMC_EDIT_STORED_SGT(Z3)); + TERN_(Z4_SENSORLESS, TMC_EDIT_STORED_SGT(Z4)); + TERN_( I_SENSORLESS, TMC_EDIT_STORED_SGT(I)); + TERN_( J_SENSORLESS, TMC_EDIT_STORED_SGT(J)); + TERN_( K_SENSORLESS, TMC_EDIT_STORED_SGT(K)); END_MENU(); } @@ -192,54 +147,22 @@ void menu_tmc_current() { START_MENU(); STATIC_ITEM(MSG_TMC_STEALTH_ENABLED); BACK_ITEM(MSG_TMC_DRIVERS); - #if AXIS_HAS_STEALTHCHOP(X) - TMC_EDIT_STEP_MODE(X, STR_X); - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - TMC_EDIT_STEP_MODE(Y, STR_Y); - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - TMC_EDIT_STEP_MODE(Z, STR_Z); - #endif - #if AXIS_HAS_STEALTHCHOP(X2) - TMC_EDIT_STEP_MODE(X2, STR_X2); - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - TMC_EDIT_STEP_MODE(Y2, STR_Y2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - TMC_EDIT_STEP_MODE(Z2, STR_Z2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z3) - TMC_EDIT_STEP_MODE(Z3, STR_Z3); - #endif - #if AXIS_HAS_STEALTHCHOP(Z4) - TMC_EDIT_STEP_MODE(Z4, STR_Z4); - #endif - #if AXIS_HAS_STEALTHCHOP(E0) - TMC_EDIT_STEP_MODE(E0, LCD_STR_E0); - #endif - #if AXIS_HAS_STEALTHCHOP(E1) - TMC_EDIT_STEP_MODE(E1, LCD_STR_E1); - #endif - #if AXIS_HAS_STEALTHCHOP(E2) - TMC_EDIT_STEP_MODE(E2, LCD_STR_E2); - #endif - #if AXIS_HAS_STEALTHCHOP(E3) - TMC_EDIT_STEP_MODE(E3, LCD_STR_E3); - #endif - #if AXIS_HAS_STEALTHCHOP(E4) - TMC_EDIT_STEP_MODE(E4, LCD_STR_E4); - #endif - #if AXIS_HAS_STEALTHCHOP(E5) - TMC_EDIT_STEP_MODE(E5, LCD_STR_E5); - #endif - #if AXIS_HAS_STEALTHCHOP(E6) - TMC_EDIT_STEP_MODE(E6, LCD_STR_E6); - #endif - #if AXIS_HAS_STEALTHCHOP(E7) - TMC_EDIT_STEP_MODE(E7, LCD_STR_E7); - #endif + TERN_( X_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(X, STR_X)); + TERN_(X2_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(X2, STR_X2)); + TERN_( Y_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(Y, STR_Y)); + TERN_(Y2_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(Y2, STR_Y2)); + TERN_( Z_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(Z, STR_Z)); + TERN_(Z2_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(Z2, STR_Z2)); + TERN_(Z3_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(Z3, STR_Z3)); + TERN_(Z4_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(Z4, STR_Z4)); + TERN_(E0_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E0, LCD_STR_E0)); + TERN_(E1_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E1, LCD_STR_E1)); + TERN_(E2_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E2, LCD_STR_E2)); + TERN_(E3_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E3, LCD_STR_E3)); + TERN_(E4_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E4, LCD_STR_E4)); + TERN_(E5_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E5, LCD_STR_E5)); + TERN_(E6_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E6, LCD_STR_E6)); + TERN_(E7_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E7, LCD_STR_E7)); END_MENU(); } @@ -249,15 +172,9 @@ void menu_tmc() { START_MENU(); BACK_ITEM(MSG_ADVANCED_SETTINGS); SUBMENU(MSG_TMC_CURRENT, menu_tmc_current); - #if ENABLED(HYBRID_THRESHOLD) - SUBMENU(MSG_TMC_HYBRID_THRS, menu_tmc_hybrid_thrs); - #endif - #if ENABLED(SENSORLESS_HOMING) - SUBMENU(MSG_TMC_HOMING_THRS, menu_tmc_homing_thrs); - #endif - #if HAS_STEALTHCHOP - SUBMENU(MSG_TMC_STEPPING_MODE, menu_tmc_step_mode); - #endif + TERN_(HYBRID_THRESHOLD, SUBMENU(MSG_TMC_HYBRID_THRS, menu_tmc_hybrid_thrs)); + TERN_(SENSORLESS_HOMING, SUBMENU(MSG_TMC_HOMING_THRS, menu_tmc_homing_thrs)); + TERN_(HAS_STEALTHCHOP, SUBMENU(MSG_TMC_STEPPING_MODE, menu_tmc_step_mode)); END_MENU(); } diff --git a/Marlin/src/lcd/menu/menu_tramming.cpp b/Marlin/src/lcd/menu/menu_tramming.cpp index da7afd86ef796..7ccb320f31e93 100644 --- a/Marlin/src/lcd/menu/menu_tramming.cpp +++ b/Marlin/src/lcd/menu/menu_tramming.cpp @@ -92,7 +92,7 @@ void goto_tramming_wizard() { // Inject G28, wait for homing to complete, set_all_unhomed(); - queue.inject_P(TERN(G28_L0_ENSURES_LEVELING_OFF, PSTR("G28L0"), G28_STR)); + queue.inject_P(TERN(CAN_SET_LEVELING_AFTER_G28, PSTR("G28L0"), G28_STR)); ui.goto_screen([]{ _lcd_draw_homing(); diff --git a/Marlin/src/lcd/menu/menu_ubl.cpp b/Marlin/src/lcd/menu/menu_ubl.cpp index 880b76ff76515..467bd81acfc70 100644 --- a/Marlin/src/lcd/menu/menu_ubl.cpp +++ b/Marlin/src/lcd/menu/menu_ubl.cpp @@ -176,7 +176,7 @@ void _menu_ubl_height_adjust() { void _lcd_ubl_edit_mesh() { START_MENU(); BACK_ITEM(MSG_UBL_TOOLS); - GCODES_ITEM(MSG_UBL_FINE_TUNE_ALL, PSTR("G29P4R999T")); + GCODES_ITEM(MSG_UBL_FINE_TUNE_ALL, PSTR("G29P4RT")); GCODES_ITEM(MSG_UBL_FINE_TUNE_CLOSEST, PSTR("G29P4T")); SUBMENU(MSG_UBL_MESH_HEIGHT_ADJUST, _menu_ubl_height_adjust); ACTION_ITEM(MSG_INFO_SCREEN, ui.return_to_status); @@ -594,9 +594,9 @@ void _menu_ubl_tools() { GCODES_ITEM(MSG_UBL_1_BUILD_COLD_MESH, PSTR("G29NP1")); GCODES_ITEM(MSG_UBL_2_SMART_FILLIN, PSTR("G29P3T0")); SUBMENU(MSG_UBL_3_VALIDATE_MESH_MENU, _lcd_ubl_validate_mesh); - GCODES_ITEM(MSG_UBL_4_FINE_TUNE_ALL, PSTR("G29P4R999T")); + GCODES_ITEM(MSG_UBL_4_FINE_TUNE_ALL, PSTR("G29P4RT")); SUBMENU(MSG_UBL_5_VALIDATE_MESH_MENU, _lcd_ubl_validate_mesh); - GCODES_ITEM(MSG_UBL_6_FINE_TUNE_ALL, PSTR("G29P4R999T")); + GCODES_ITEM(MSG_UBL_6_FINE_TUNE_ALL, PSTR("G29P4RT")); ACTION_ITEM(MSG_UBL_7_SAVE_MESH, _lcd_ubl_save_mesh_cmd); END_MENU(); } diff --git a/Marlin/src/lcd/tft/touch.cpp b/Marlin/src/lcd/tft/touch.cpp index 3d4e0a40e1ebe..64dfaa5755f28 100644 --- a/Marlin/src/lcd/tft/touch.cpp +++ b/Marlin/src/lcd/tft/touch.cpp @@ -93,9 +93,7 @@ void Touch::idle() { } #endif - #if LCD_TIMEOUT_TO_STATUS - ui.return_to_status_ms = last_touch_ms + LCD_TIMEOUT_TO_STATUS; - #endif + ui.reset_status_timeout(last_touch_ms); if (touch_time) { #if ENABLED(TOUCH_SCREEN_CALIBRATION) diff --git a/Marlin/src/lcd/tft/ui_1024x600.cpp b/Marlin/src/lcd/tft/ui_1024x600.cpp index 87b016b1eca3f..18c50c92f7a29 100644 --- a/Marlin/src/lcd/tft/ui_1024x600.cpp +++ b/Marlin/src/lcd/tft/ui_1024x600.cpp @@ -653,10 +653,12 @@ static void drawAxisValue(const AxisEnum axis) { static void moveAxis(const AxisEnum axis, const int8_t direction) { quick_feedback(); - if (axis == E_AXIS && thermalManager.tooColdToExtrude(motionAxisState.e_selection)) { - drawMessage("Too cold"); - return; - } + #if ENABLED(PREVENT_COLD_EXTRUSION) + if (axis == E_AXIS && thermalManager.tooColdToExtrude(motionAxisState.e_selection)) { + drawMessage("Too cold"); + return; + } + #endif const float diff = motionAxisState.currentStepSize * direction; @@ -724,11 +726,7 @@ static void moveAxis(const AxisEnum axis, const int8_t direction) { drawMessage(msg); #endif - ui.manual_move.soon(axis - #if MULTI_E_MANUAL - , motionAxisState.e_selection - #endif - ); + ui.manual_move.soon(axis OPTARG(MULTI_E_MANUAL, motionAxisState.e_selection)); } drawAxisValue(axis); diff --git a/Marlin/src/lcd/tft/ui_320x240.cpp b/Marlin/src/lcd/tft/ui_320x240.cpp index 89a127b01ed95..786dc61f60d9b 100644 --- a/Marlin/src/lcd/tft/ui_320x240.cpp +++ b/Marlin/src/lcd/tft/ui_320x240.cpp @@ -638,10 +638,12 @@ static void drawAxisValue(const AxisEnum axis) { static void moveAxis(const AxisEnum axis, const int8_t direction) { quick_feedback(); - if (axis == E_AXIS && thermalManager.tooColdToExtrude(motionAxisState.e_selection)) { - drawMessage("Too cold"); - return; - } + #if ENABLED(PREVENT_COLD_EXTRUSION) + if (axis == E_AXIS && thermalManager.tooColdToExtrude(motionAxisState.e_selection)) { + drawMessage("Too cold"); + return; + } + #endif const float diff = motionAxisState.currentStepSize * direction; @@ -709,11 +711,7 @@ static void moveAxis(const AxisEnum axis, const int8_t direction) { drawMessage(msg); #endif - ui.manual_move.soon(axis - #if MULTI_E_MANUAL - , motionAxisState.e_selection - #endif - ); + ui.manual_move.soon(axis OPTARG(MULTI_E_MANUAL, motionAxisState.e_selection)); } drawAxisValue(axis); diff --git a/Marlin/src/lcd/tft/ui_480x320.cpp b/Marlin/src/lcd/tft/ui_480x320.cpp index 6923bdd71c0e3..02e3354d93af1 100644 --- a/Marlin/src/lcd/tft/ui_480x320.cpp +++ b/Marlin/src/lcd/tft/ui_480x320.cpp @@ -640,10 +640,12 @@ static void drawAxisValue(const AxisEnum axis) { static void moveAxis(const AxisEnum axis, const int8_t direction) { quick_feedback(); - if (axis == E_AXIS && thermalManager.tooColdToExtrude(motionAxisState.e_selection)) { - drawMessage("Too cold"); - return; - } + #if ENABLED(PREVENT_COLD_EXTRUSION) + if (axis == E_AXIS && thermalManager.tooColdToExtrude(motionAxisState.e_selection)) { + drawMessage("Too cold"); + return; + } + #endif const float diff = motionAxisState.currentStepSize * direction; @@ -711,11 +713,7 @@ static void moveAxis(const AxisEnum axis, const int8_t direction) { drawMessage(msg); #endif - ui.manual_move.soon(axis - #if MULTI_E_MANUAL - , motionAxisState.e_selection - #endif - ); + ui.manual_move.soon(axis OPTARG(MULTI_E_MANUAL, motionAxisState.e_selection)); } drawAxisValue(axis); diff --git a/Marlin/src/lcd/tft_io/tft_ids.h b/Marlin/src/lcd/tft_io/tft_ids.h new file mode 100644 index 0000000000000..c4f6127c685a9 --- /dev/null +++ b/Marlin/src/lcd/tft_io/tft_ids.h @@ -0,0 +1,35 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#define LTDC_RGB 0xABAB +#define SSD1963 0x5761 +#define ST7735 0x89F0 +#define ST7789 0x8552 +#define ST7796 0x7796 +#define R61505 0x1505 +#define ILI9328 0x9328 +#define ILI9341 0x9341 +#define ILI9488 0x9488 +#define ILI9488_ID1 0x8066 // Some ILI9488 have 0x8066 in the 0x04 +#define LERDGE_ST7796 0xFFFE +#define AUTO 0xFFFF diff --git a/Marlin/src/lcd/tft_io/tft_io.cpp b/Marlin/src/lcd/tft_io/tft_io.cpp index fa81d95a4daee..29c7da235c0e8 100644 --- a/Marlin/src/lcd/tft_io/tft_io.cpp +++ b/Marlin/src/lcd/tft_io/tft_io.cpp @@ -20,18 +20,34 @@ * */ -#include "tft_io.h" +#include "../../inc/MarlinConfigPre.h" #if HAS_SPI_TFT || HAS_FSMC_TFT || HAS_LTDC_TFT -#include "st7735.h" -#include "st7789v.h" -#include "st7796s.h" -#include "r65105.h" -#include "ili9328.h" +#include "tft_io.h" +#include "tft_ids.h" + +#if TFT_DRIVER == ST7735 || TFT_DRIVER == AUTO + #include "st7735.h" +#endif +#if TFT_DRIVER == ST7789 || TFT_DRIVER == AUTO + #include "st7789v.h" +#endif +#if TFT_DRIVER == ST7796 || TFT_DRIVER == AUTO + #include "st7796s.h" +#endif +#if TFT_DRIVER == R61505 || TFT_DRIVER == AUTO + #include "r65105.h" +#endif +#if TFT_DRIVER == ILI9488 || TFT_DRIVER == ILI9488_ID1 || TFT_DRIVER == AUTO + #include "ili9488.h" +#endif +#if TFT_DRIVER == SSD1963 || TFT_DRIVER == AUTO + #include "ssd1963.h" +#endif + #include "ili9341.h" -#include "ili9488.h" -#include "ssd1963.h" +#include "ili9328.h" #define DEBUG_OUT ENABLED(DEBUG_GRAPHICAL_TFT) #include "../../core/debug_out.h" @@ -236,4 +252,4 @@ void TFT_IO::write_esc_sequence(const uint16_t *Sequence) { io.DataTransferEnd(); } -#endif // HAS_SPI_TFT || HAS_FSMC_TFT +#endif // HAS_SPI_TFT || HAS_FSMC_TFT || HAS_LTDC_TFT diff --git a/Marlin/src/lcd/tft_io/tft_io.h b/Marlin/src/lcd/tft_io/tft_io.h index 846b45e8e0934..0e4322f0d71b7 100644 --- a/Marlin/src/lcd/tft_io/tft_io.h +++ b/Marlin/src/lcd/tft_io/tft_io.h @@ -23,8 +23,6 @@ #include "../../inc/MarlinConfig.h" -#if HAS_SPI_TFT || HAS_FSMC_TFT || HAS_LTDC_TFT - #if HAS_SPI_TFT #include HAL_PATH(../../HAL, tft/tft_spi.h) #elif HAS_FSMC_TFT @@ -35,9 +33,9 @@ #error "TFT IO only supports SPI, FSMC or LTDC interface" #endif -#define TFT_EXCHANGE_XY (1UL << 1) -#define TFT_INVERT_X (1UL << 2) -#define TFT_INVERT_Y (1UL << 3) +#define TFT_EXCHANGE_XY _BV32(1) +#define TFT_INVERT_X _BV32(2) +#define TFT_INVERT_Y _BV32(3) #define TFT_NO_ROTATION (0x00) #define TFT_ROTATE_90 (TFT_EXCHANGE_XY | TFT_INVERT_X) @@ -65,8 +63,8 @@ // TFT_ORIENTATION is the "sum" of TFT_DEFAULT_ORIENTATION plus user TFT_ROTATION #define TFT_ORIENTATION ((TFT_DEFAULT_ORIENTATION) ^ (TFT_ROTATION)) -#define TFT_COLOR_RGB (1UL << 3) -#define TFT_COLOR_BGR (1UL << 4) +#define TFT_COLOR_RGB _BV32(3) +#define TFT_COLOR_BGR _BV32(4) // Each TFT Driver is responsible for its default color mode. // #ifndef TFT_COLOR @@ -93,27 +91,14 @@ #define TOUCH_ORIENTATION TOUCH_LANDSCAPE #endif -#define LTDC_RGB 0xABAB -#define SSD1963 0x5761 -#define ST7735 0x89F0 -#define ST7789 0x8552 -#define ST7796 0x7796 -#define R61505 0x1505 -#define ILI9328 0x9328 -#define ILI9341 0x9341 -#define ILI9488 0x9488 -#define ILI9488_ID1 0x8066 //Some ILI9488 have 0x8066 in the 0x04 -#define LERDGE_ST7796 0xFFFE -#define AUTO 0xFFFF - #ifndef TFT_DRIVER #define TFT_DRIVER AUTO #endif -#define ESC_REG(x) 0xFFFF, 0x00FF & (uint16_t)x -#define ESC_DELAY(x) 0xFFFF, 0x8000 | (x & 0x7FFF) -#define ESC_END 0xFFFF, 0x7FFF -#define ESC_FFFF 0xFFFF, 0xFFFF +#define ESC_REG(x) 0xFFFF, 0x00FF & (uint16_t)x +#define ESC_DELAY(x) 0xFFFF, 0x8000 | (x & 0x7FFF) +#define ESC_END 0xFFFF, 0x7FFF +#define ESC_FFFF 0xFFFF, 0xFFFF class TFT_IO { public: @@ -143,5 +128,3 @@ class TFT_IO { protected: static uint32_t lcd_id; }; - -#endif // HAS_SPI_TFT || HAS_FSMC_TFT diff --git a/Marlin/src/libs/BL24CXX.cpp b/Marlin/src/libs/BL24CXX.cpp index 8de320d57619a..adcd5ed8943ad 100644 --- a/Marlin/src/libs/BL24CXX.cpp +++ b/Marlin/src/libs/BL24CXX.cpp @@ -27,7 +27,12 @@ */ #include "BL24CXX.h" -#include +#ifdef __STM32F1__ + #include +#else + #include "../HAL/shared/Delay.h" + #define delay_us(n) DELAY_US(n) +#endif #ifndef EEPROM_WRITE_DELAY #define EEPROM_WRITE_DELAY 10 @@ -37,8 +42,13 @@ #endif // IO direction setting -#define SDA_IN() do{ PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH &= 0XFFFF0FFF; PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH |= 8 << 12; }while(0) -#define SDA_OUT() do{ PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH &= 0XFFFF0FFF; PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH |= 3 << 12; }while(0) +#ifdef __STM32F1__ + #define SDA_IN() do{ PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH &= 0XFFFF0FFF; PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH |= 8 << 12; }while(0) + #define SDA_OUT() do{ PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH &= 0XFFFF0FFF; PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH |= 3 << 12; }while(0) +#elif STM32F1 + #define SDA_IN() SET_INPUT(IIC_EEPROM_SDA) + #define SDA_OUT() SET_OUTPUT(IIC_EEPROM_SDA) +#endif // IO ops #define IIC_SCL_0() WRITE(IIC_EEPROM_SCL, LOW) diff --git a/Marlin/src/libs/L64XX/L64XX_Marlin.cpp b/Marlin/src/libs/L64XX/L64XX_Marlin.cpp index a6aed2ad24fb4..876405a40c5fe 100644 --- a/Marlin/src/libs/L64XX/L64XX_Marlin.cpp +++ b/Marlin/src/libs/L64XX/L64XX_Marlin.cpp @@ -37,19 +37,27 @@ L64XX_Marlin L64xxManager; #include "../../module/planner.h" #include "../../HAL/shared/Delay.h" -static const char str_X[] PROGMEM = "X ", str_Y[] PROGMEM = "Y ", str_Z[] PROGMEM = "Z ", +static const char LINEAR_AXIS_LIST( + str_X[] PROGMEM = "X ", str_Y[] PROGMEM = "Y ", str_Z[] PROGMEM = "Z ", + str_I[] PROGMEM = AXIS4_STR " ", str_J[] PROGMEM = AXIS5_STR " ", str_K[] PROGMEM = AXIS6_STR " " + ), str_X2[] PROGMEM = "X2", str_Y2[] PROGMEM = "Y2", str_Z2[] PROGMEM = "Z2", str_Z3[] PROGMEM = "Z3", str_Z4[] PROGMEM = "Z4", - str_E0[] PROGMEM = "E0", str_E1[] PROGMEM = "E1", - str_E2[] PROGMEM = "E2", str_E3[] PROGMEM = "E3", - str_E4[] PROGMEM = "E4", str_E5[] PROGMEM = "E5", - str_E6[] PROGMEM = "E6", str_E7[] PROGMEM = "E7" + LIST_N(EXTRUDERS, + str_E0[] PROGMEM = "E0", str_E1[] PROGMEM = "E1", + str_E2[] PROGMEM = "E2", str_E3[] PROGMEM = "E3", + str_E4[] PROGMEM = "E4", str_E5[] PROGMEM = "E5", + str_E6[] PROGMEM = "E6", str_E7[] PROGMEM = "E7" + ) ; +#define _EN_ITEM(N) , str_E##N PGM_P const L64XX_Marlin::index_to_axis[] PROGMEM = { - str_X, str_Y, str_Z, str_X2, str_Y2, str_Z2, str_Z3, str_Z4, - str_E0, str_E1, str_E2, str_E3, str_E4, str_E5, str_E6, str_E7 + LINEAR_AXIS_LIST(str_X, str_Y, str_Z, str_I, str_J, str_K), + str_X2, str_Y2, str_Z2, str_Z3, str_Z4 + REPEAT(E_STEPPERS, _EN_ITEM) }; +#undef _EN_ITEM #define DEBUG_OUT ENABLED(L6470_CHITCHAT) #include "../../core/debug_out.h" @@ -58,16 +66,17 @@ void echo_yes_no(const bool yes) { DEBUG_ECHOPGM_P(yes ? PSTR(" YES") : PSTR(" N uint8_t L64XX_Marlin::dir_commands[MAX_L64XX]; // array to hold direction command for each driver +#define _EN_ITEM(N) , INVERT_E##N##_DIR const uint8_t L64XX_Marlin::index_to_dir[MAX_L64XX] = { - INVERT_X_DIR, INVERT_Y_DIR, INVERT_Z_DIR + LINEAR_AXIS_LIST(INVERT_X_DIR, INVERT_Y_DIR, INVERT_Z_DIR, INVERT_I_DIR, INVERT_J_DIR, INVERT_K_DIR) , (INVERT_X_DIR) ^ BOTH(X_DUAL_STEPPER_DRIVERS, INVERT_X2_VS_X_DIR) // X2 , (INVERT_Y_DIR) ^ BOTH(Y_DUAL_STEPPER_DRIVERS, INVERT_Y2_VS_Y_DIR) // Y2 , (INVERT_Z_DIR) ^ ENABLED(INVERT_Z2_VS_Z_DIR) // Z2 , (INVERT_Z_DIR) ^ ENABLED(INVERT_Z3_VS_Z_DIR) // Z3 , (INVERT_Z_DIR) ^ ENABLED(INVERT_Z4_VS_Z_DIR) // Z4 - , INVERT_E0_DIR, INVERT_E1_DIR, INVERT_E2_DIR, INVERT_E3_DIR - , INVERT_E4_DIR, INVERT_E5_DIR, INVERT_E6_DIR, INVERT_E7_DIR + REPEAT(E_STEPPERS, _EN_ITEM) }; +#undef _EN_ITEM volatile uint8_t L64XX_Marlin::spi_abort = false; uint8_t L64XX_Marlin::spi_active = false; @@ -326,6 +335,15 @@ void L64XX_Marlin::set_param(const L64XX_axis_t axis, const uint8_t param, const #if AXIS_IS_L64XX(Z) case Z : SET_L6470_PARAM(Z); break; #endif + #if AXIS_IS_L64XX(I) + case I : SET_L6470_PARAM(I); break; + #endif + #if AXIS_IS_L64XX(J) + case J : SET_L6470_PARAM(J); break; + #endif + #if AXIS_IS_L64XX(K) + case K : SET_L6470_PARAM(K); break; + #endif #if AXIS_IS_L64XX(X2) case X2: SET_L6470_PARAM(X2); break; #endif @@ -370,8 +388,7 @@ void L64XX_Marlin::set_param(const L64XX_axis_t axis, const uint8_t param, const inline void echo_min_max(const char a, const_float_t min, const_float_t max) { DEBUG_CHAR(' '); DEBUG_CHAR(a); - DEBUG_ECHOPAIR(" min = ", min); - DEBUG_ECHOLNPAIR(" max = ", max); + DEBUG_ECHOLNPAIR(" min = ", min, " max = ", max); } inline void echo_oct_used(const_float_t oct, const uint8_t stall) { DEBUG_ECHOPAIR("over_current_threshold used : ", oct); @@ -433,10 +450,15 @@ uint8_t L64XX_Marlin::get_user_input(uint8_t &driver_count, L64XX_axis_t axis_in // Position calcs & checks // - const float X_center = LOGICAL_X_POSITION(current_position.x), - Y_center = LOGICAL_Y_POSITION(current_position.y), - Z_center = LOGICAL_Z_POSITION(current_position.z), - E_center = current_position.e; + const float LOGICAL_AXIS_LIST( + E_center = current_position.e, + X_center = LOGICAL_X_POSITION(current_position.x), + Y_center = LOGICAL_Y_POSITION(current_position.y), + Z_center = LOGICAL_Z_POSITION(current_position.z), + I_center = LOGICAL_I_POSITION(current_position.i), + J_center = LOGICAL_J_POSITION(current_position.j), + K_center = LOGICAL_K_POSITION(current_position.k) + ); switch (axis_mon[0][0]) { default: position_max = position_min = 0; break; @@ -451,31 +473,73 @@ uint8_t L64XX_Marlin::get_user_input(uint8_t &driver_count, L64XX_axis_t axis_in } } break; - case 'Y': { - position_min = Y_center - displacement; - position_max = Y_center + displacement; - echo_min_max('Y', position_min, position_max); - if (TERN0(HAS_ENDSTOPS, position_min < (Y_MIN_POS) || position_max > (Y_MAX_POS))) { - err_out_of_bounds(); - return true; - } - } break; + #if HAS_Y_AXIS + case 'Y': { + position_min = Y_center - displacement; + position_max = Y_center + displacement; + echo_min_max('Y', position_min, position_max); + if (TERN0(HAS_ENDSTOPS, position_min < (Y_MIN_POS) || position_max > (Y_MAX_POS))) { + err_out_of_bounds(); + return true; + } + } break; + #endif - case 'Z': { - position_min = Z_center - displacement; - position_max = Z_center + displacement; - echo_min_max('Z', position_min, position_max); - if (TERN0(HAS_ENDSTOPS, position_min < (Z_MIN_POS) || position_max > (Z_MAX_POS))) { - err_out_of_bounds(); - return true; - } - } break; + #if HAS_Z_AXIS + case 'Z': { + position_min = Z_center - displacement; + position_max = Z_center + displacement; + echo_min_max('Z', position_min, position_max); + if (TERN0(HAS_ENDSTOPS, position_min < (Z_MIN_POS) || position_max > (Z_MAX_POS))) { + err_out_of_bounds(); + return true; + } + } break; + #endif - case 'E': { - position_min = E_center - displacement; - position_max = E_center + displacement; - echo_min_max('E', position_min, position_max); - } break; + #if LINEAR_AXES >= 4 + case AXIS4_NAME: { + position_min = I_center - displacement; + position_max = I_center + displacement; + echo_min_max(AXIS4_NAME, position_min, position_max); + if (TERN0(HAS_ENDSTOPS, position_min < (I_MIN_POS) || position_max > (I_MAX_POS))) { + err_out_of_bounds(); + return true; + } + } break; + #endif + + #if LINEAR_AXES >= 5 + case AXIS5_NAME: { + position_min = J_center - displacement; + position_max = J_center + displacement; + echo_min_max(AXIS5_NAME, position_min, position_max); + if (TERN1(HAS_ENDSTOPS, position_min < (J_MIN_POS) || position_max > (J_MAX_POS))) { + err_out_of_bounds(); + return true; + } + } break; + #endif + + #if LINEAR_AXES >= 6 + case AXIS6_NAME: { + position_min = K_center - displacement; + position_max = K_center + displacement; + echo_min_max(AXIS6_NAME, position_min, position_max); + if (TERN2(HAS_ENDSTOPS, position_min < (K_MIN_POS) || position_max > (K_MAX_POS))) { + err_out_of_bounds(); + return true; + } + } break; + #endif + + #if HAS_EXTRUDERS + case 'E': { + position_min = E_center - displacement; + position_max = E_center + displacement; + echo_min_max('E', position_min, position_max); + } break; + #endif } // @@ -660,7 +724,7 @@ void L64XX_Marlin::say_axis(const L64XX_axis_t axis, const uint8_t label/*=true* bool L64XX_Marlin::monitor_paused = false; // Flag to skip monitor during M122, M906, M916, M917, M918, etc. struct L6470_driver_data { - uint8_t driver_index; + L64XX_axis_t driver_index; uint32_t driver_status; uint8_t is_otw; uint8_t otw_counter; @@ -671,52 +735,61 @@ void L64XX_Marlin::say_axis(const L64XX_axis_t axis, const uint8_t label/*=true* L6470_driver_data driver_L6470_data[] = { #if AXIS_IS_L64XX(X) - { 0, 0, 0, 0, 0, 0, 0 }, + { X, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(Y) - { 1, 0, 0, 0, 0, 0, 0 }, + { Y, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(Z) - { 2, 0, 0, 0, 0, 0, 0 }, + { Z, 0, 0, 0, 0, 0, 0 }, + #endif + #if AXIS_IS_L64XX(I) + { I, 0, 0, 0, 0, 0, 0 }, + #endif + #if AXIS_IS_L64XX(J) + { J, 0, 0, 0, 0, 0, 0 }, + #endif + #if AXIS_IS_L64XX(K) + { K, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(X2) - { 3, 0, 0, 0, 0, 0, 0 }, + { X2, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(Y2) - { 4, 0, 0, 0, 0, 0, 0 }, + { Y2, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(Z2) - { 5, 0, 0, 0, 0, 0, 0 }, + { Z2, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(Z3) - { 6, 0, 0, 0, 0, 0, 0 }, + { Z3, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(Z4) - { 7, 0, 0, 0, 0, 0, 0 }, + { Z4, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(E0) - { 8, 0, 0, 0, 0, 0, 0 }, + { E0, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(E1) - { 9, 0, 0, 0, 0, 0, 0 }, + { E1, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(E2) - { 10, 0, 0, 0, 0, 0, 0 }, + { E2, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(E3) - { 11, 0, 0, 0, 0, 0, 0 }, + { E3, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(E4) - { 12, 0, 0, 0, 0, 0, 0 }, + { E4, 0, 0, 0, 0, 0, 0 }, #endif #if AXIS_IS_L64XX(E5) - { 13, 0, 0, 0, 0, 0, 0 } + { E5, 0, 0, 0, 0, 0, 0 } #endif #if AXIS_IS_L64XX(E6) - { 14, 0, 0, 0, 0, 0, 0 } + { E6, 0, 0, 0, 0, 0, 0 } #endif #if AXIS_IS_L64XX(E7) - { 16, 0, 0, 0, 0, 0, 0 } + { E7, 0, 0, 0, 0, 0, 0 } #endif }; @@ -863,6 +936,15 @@ void L64XX_Marlin::say_axis(const L64XX_axis_t axis, const uint8_t label/*=true* #if AXIS_IS_L64XX(Z) monitor_update(Z); #endif + #if AXIS_IS_L64XX(I) + monitor_update(I); + #endif + #if AXIS_IS_L64XX(J) + monitor_update(J); + #endif + #if AXIS_IS_L64XX(K) + monitor_update(K); + #endif #if AXIS_IS_L64XX(X2) monitor_update(X2); #endif @@ -896,6 +978,12 @@ void L64XX_Marlin::say_axis(const L64XX_axis_t axis, const uint8_t label/*=true* #if AXIS_IS_L64XX(E5) monitor_update(E5); #endif + #if AXIS_IS_L64XX(E6) + monitor_update(E6); + #endif + #if AXIS_IS_L64XX(E7) + monitor_update(E7); + #endif if (TERN0(L6470_DEBUG, report_L6470_status)) DEBUG_EOL(); diff --git a/Marlin/src/libs/L64XX/L64XX_Marlin.h b/Marlin/src/libs/L64XX/L64XX_Marlin.h index c8d273990f5ac..e11d8e872e60a 100644 --- a/Marlin/src/libs/L64XX/L64XX_Marlin.h +++ b/Marlin/src/libs/L64XX/L64XX_Marlin.h @@ -35,7 +35,9 @@ #define dSPIN_STEP_CLOCK_REV dSPIN_STEP_CLOCK+1 #define HAS_L64XX_EXTRUDER (AXIS_IS_L64XX(E0) || AXIS_IS_L64XX(E1) || AXIS_IS_L64XX(E2) || AXIS_IS_L64XX(E3) || AXIS_IS_L64XX(E4) || AXIS_IS_L64XX(E5) || AXIS_IS_L64XX(E6) || AXIS_IS_L64XX(E7)) -enum L64XX_axis_t : uint8_t { X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7, MAX_L64XX }; +#define _EN_ITEM(N) , E##N +enum L64XX_axis_t : uint8_t { LINEAR_AXIS_LIST(X, Y, Z, I, J, K), X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM), MAX_L64XX }; +#undef _EN_ITEM class L64XX_Marlin : public L64XXHelper { public: diff --git a/Marlin/src/libs/vector_3.cpp b/Marlin/src/libs/vector_3.cpp index f1bff7d4c601b..b8202217ddcaf 100644 --- a/Marlin/src/libs/vector_3.cpp +++ b/Marlin/src/libs/vector_3.cpp @@ -52,10 +52,9 @@ */ vector_3 vector_3::cross(const vector_3 &left, const vector_3 &right) { - 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 + return vector_3(left.y * right.z - left.z * right.y, // YZ cross + left.z * right.x - left.x * right.z, // ZX cross + left.x * right.y - left.y * right.x); // XY cross } vector_3 vector_3::get_normal() const { @@ -64,16 +63,16 @@ vector_3 vector_3::get_normal() const { return normalized; } -void vector_3::normalize() { - *this *= RSQRT(sq(x) + sq(y) + sq(z)); -} +float vector_3::magnitude() const { return SQRT(sq(x) + sq(y) + sq(z)); } + +void vector_3::normalize() { *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, _z = z; - *this = { matrix.vectors[0][0] * _x + matrix.vectors[1][0] * _y + matrix.vectors[2][0] * _z, - matrix.vectors[0][1] * _x + matrix.vectors[1][1] * _y + matrix.vectors[2][1] * _z, - matrix.vectors[0][2] * _x + matrix.vectors[1][2] * _y + matrix.vectors[2][2] * _z }; + *this = { matrix.vectors[0].x * _x + matrix.vectors[1].x * _y + matrix.vectors[2].x * _z, + matrix.vectors[0].y * _x + matrix.vectors[1].y * _y + matrix.vectors[2].y * _z, + matrix.vectors[0].z * _x + matrix.vectors[1].z * _y + matrix.vectors[2].z * _z }; } void vector_3::debug(PGM_P const title) { @@ -105,9 +104,9 @@ matrix_3x3 matrix_3x3::create_from_rows(const vector_3 &row_0, const vector_3 &r //row_1.debug(PSTR("row_1")); //row_2.debug(PSTR("row_2")); matrix_3x3 new_matrix; - new_matrix.vectors[0] = row_0; - new_matrix.vectors[1] = row_1; - new_matrix.vectors[2] = row_2; + new_matrix.vectors[0].x = row_0.x; new_matrix.vectors[1].y = row_0.y; new_matrix.vectors[2].z = row_0.z; + new_matrix.vectors[3].x = row_1.x; new_matrix.vectors[4].y = row_1.y; new_matrix.vectors[5].z = row_1.z; + new_matrix.vectors[6].x = row_2.x; new_matrix.vectors[7].y = row_2.y; new_matrix.vectors[8].z = row_2.z; //new_matrix.debug(PSTR("new_matrix")); return new_matrix; } diff --git a/Marlin/src/libs/vector_3.h b/Marlin/src/libs/vector_3.h index 5ce59149610d2..5d99fcec20db9 100644 --- a/Marlin/src/libs/vector_3.h +++ b/Marlin/src/libs/vector_3.h @@ -44,12 +44,16 @@ class matrix_3x3; -struct vector_3 : xyz_float_t { - vector_3(const_float_t _x, const_float_t _y, const_float_t _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); } - vector_3() { reset(); } +struct vector_3 { + union { + struct { float x, y, z; }; + float pos[3]; + }; + vector_3(const_float_t _x, const_float_t _y, const_float_t _z) : x(_x), y(_y), z(_z) {} + vector_3(const xy_float_t &in) { x = in.x; TERN_(HAS_Y_AXIS, y = in.y); } + vector_3(const xyz_float_t &in) { x = in.x; TERN_(HAS_Y_AXIS, y = in.y); TERN_(HAS_Z_AXIS, z = in.z); } + vector_3(const xyze_float_t &in) { x = in.x; TERN_(HAS_Y_AXIS, y = in.y); TERN_(HAS_Z_AXIS, z = in.z); } + vector_3() { x = y = z = 0; } // Factory method static vector_3 cross(const vector_3 &a, const vector_3 &b); @@ -59,19 +63,26 @@ struct vector_3 : xyz_float_t { void apply_rotation(const matrix_3x3 &matrix); // Accessors - float get_length() const; + float magnitude() 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; } + float& operator[](const int n) { return pos[n]; } + const float& operator[](const int n) const { return pos[n]; } + + vector_3& operator*=(const float &v) { x *= v; y *= v; z *= v; return *this; } + vector_3 operator+(const vector_3 &v) { return vector_3(x + v.x, y + v.y, z + v.z); } + vector_3 operator-(const vector_3 &v) { return vector_3(x - v.x, y - v.y, z - v.z); } + vector_3 operator*(const float &v) { return vector_3(x * v, y * v, z * v); } + + operator xy_float_t() { return xy_float_t({ x, y }); } + operator xyz_float_t() { return xyz_float_t({ x, y, z }); } void debug(PGM_P const title); }; struct matrix_3x3 { - abc_float_t vectors[3]; + vector_3 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); @@ -83,6 +94,4 @@ struct matrix_3x3 { void debug(PGM_P const title); void apply_rotation_xyz(float &x, float &y, float &z); - - FORCE_INLINE void apply_rotation_xyz(xyz_pos_t &pos) { apply_rotation_xyz(pos.x, pos.y, pos.z); } }; diff --git a/Marlin/src/module/delta.cpp b/Marlin/src/module/delta.cpp index 1be3df220f140..96d8841f1312c 100644 --- a/Marlin/src/module/delta.cpp +++ b/Marlin/src/module/delta.cpp @@ -245,6 +245,9 @@ void home_delta() { TERN_(X_SENSORLESS, sensorless_t stealth_states_x = start_sensorless_homing_per_axis(X_AXIS)); TERN_(Y_SENSORLESS, sensorless_t stealth_states_y = start_sensorless_homing_per_axis(Y_AXIS)); TERN_(Z_SENSORLESS, sensorless_t stealth_states_z = start_sensorless_homing_per_axis(Z_AXIS)); + TERN_(I_SENSORLESS, sensorless_t stealth_states_i = start_sensorless_homing_per_axis(I_AXIS)); + TERN_(J_SENSORLESS, sensorless_t stealth_states_j = start_sensorless_homing_per_axis(J_AXIS)); + TERN_(K_SENSORLESS, sensorless_t stealth_states_k = start_sensorless_homing_per_axis(K_AXIS)); #endif // Move all carriages together linearly until an endstop is hit. @@ -257,6 +260,9 @@ void home_delta() { TERN_(X_SENSORLESS, end_sensorless_homing_per_axis(X_AXIS, stealth_states_x)); TERN_(Y_SENSORLESS, end_sensorless_homing_per_axis(Y_AXIS, stealth_states_y)); TERN_(Z_SENSORLESS, end_sensorless_homing_per_axis(Z_AXIS, stealth_states_z)); + TERN_(I_SENSORLESS, end_sensorless_homing_per_axis(I_AXIS, stealth_states_i)); + TERN_(J_SENSORLESS, end_sensorless_homing_per_axis(J_AXIS, stealth_states_j)); + TERN_(K_SENSORLESS, end_sensorless_homing_per_axis(K_AXIS, stealth_states_k)); #endif endstops.validate_homing_move(); diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index dff0b6832a3fc..8f6827de27768 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -259,6 +259,66 @@ void Endstops::init() { #endif #endif + #if HAS_I_MIN + #if ENABLED(ENDSTOPPULLUP_IMIN) + SET_INPUT_PULLUP(I_MIN_PIN); + #elif ENABLED(ENDSTOPPULLDOWN_IMIN) + SET_INPUT_PULLDOWN(I_MIN_PIN); + #else + SET_INPUT(I_MIN_PIN); + #endif + #endif + + #if HAS_I_MAX + #if ENABLED(ENDSTOPPULLUP_IMAX) + SET_INPUT_PULLUP(I_MAX_PIN); + #elif ENABLED(ENDSTOPPULLDOWN_IMAX) + SET_INPUT_PULLDOWN(I_MAX_PIN); + #else + SET_INPUT(I_MAX_PIN); + #endif + #endif + + #if HAS_J_MIN + #if ENABLED(ENDSTOPPULLUP_JMIN) + SET_INPUT_PULLUP(J_MIN_PIN); + #elif ENABLED(ENDSTOPPULLDOWN_IMIN) + SET_INPUT_PULLDOWN(J_MIN_PIN); + #else + SET_INPUT(J_MIN_PIN); + #endif + #endif + + #if HAS_J_MAX + #if ENABLED(ENDSTOPPULLUP_JMAX) + SET_INPUT_PULLUP(J_MAX_PIN); + #elif ENABLED(ENDSTOPPULLDOWN_JMAX) + SET_INPUT_PULLDOWN(J_MAX_PIN); + #else + SET_INPUT(J_MAX_PIN); + #endif + #endif + + #if HAS_K_MIN + #if ENABLED(ENDSTOPPULLUP_KMIN) + SET_INPUT_PULLUP(K_MIN_PIN); + #elif ENABLED(ENDSTOPPULLDOWN_KMIN) + SET_INPUT_PULLDOWN(K_MIN_PIN); + #else + SET_INPUT(K_MIN_PIN); + #endif + #endif + + #if HAS_K_MAX + #if ENABLED(ENDSTOPPULLUP_KMAX) + SET_INPUT_PULLUP(K_MAX_PIN); + #elif ENABLED(ENDSTOPPULLDOWN_KMIN) + SET_INPUT_PULLDOWN(K_MAX_PIN); + #else + SET_INPUT(K_MAX_PIN); + #endif + #endif + #if PIN_EXISTS(CALIBRATION) #if ENABLED(CALIBRATION_PIN_PULLUP) SET_INPUT_PULLUP(CALIBRATION_PIN); @@ -361,7 +421,8 @@ void Endstops::event_handler() { prev_hit_state = hit_state; if (hit_state) { #if HAS_STATUS_MESSAGE - char chrX = ' ', chrY = ' ', chrZ = ' ', chrP = ' '; + char LINEAR_AXIS_LIST(chrX = ' ', chrY = ' ', chrZ = ' ', chrI = ' ', chrJ = ' ', chrK = ' '), + chrP = ' '; #define _SET_STOP_CHAR(A,C) (chr## A = C) #else #define _SET_STOP_CHAR(A,C) NOOP @@ -377,12 +438,20 @@ void Endstops::event_handler() { #define ENDSTOP_HIT_TEST_X() _ENDSTOP_HIT_TEST(X,'X') #define ENDSTOP_HIT_TEST_Y() _ENDSTOP_HIT_TEST(Y,'Y') #define ENDSTOP_HIT_TEST_Z() _ENDSTOP_HIT_TEST(Z,'Z') + #define ENDSTOP_HIT_TEST_I() _ENDSTOP_HIT_TEST(I,'I') + #define ENDSTOP_HIT_TEST_J() _ENDSTOP_HIT_TEST(J,'J') + #define ENDSTOP_HIT_TEST_K() _ENDSTOP_HIT_TEST(K,'K') SERIAL_ECHO_START(); SERIAL_ECHOPGM(STR_ENDSTOPS_HIT); - ENDSTOP_HIT_TEST_X(); - ENDSTOP_HIT_TEST_Y(); - ENDSTOP_HIT_TEST_Z(); + LINEAR_AXIS_CODE( + ENDSTOP_HIT_TEST_X(), + ENDSTOP_HIT_TEST_Y(), + ENDSTOP_HIT_TEST_Z(), + _ENDSTOP_HIT_TEST(I,'I'), + _ENDSTOP_HIT_TEST(J,'J'), + _ENDSTOP_HIT_TEST(K,'K') + ); #if HAS_CUSTOM_PROBE_PIN #define P_AXIS Z_AXIS @@ -390,7 +459,13 @@ void Endstops::event_handler() { #endif SERIAL_EOL(); - TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %c %c %c %c"), GET_TEXT(MSG_LCD_ENDSTOPS), chrX, chrY, chrZ, chrP)); + TERN_(HAS_STATUS_MESSAGE, + ui.status_printf_P(0, + PSTR(S_FMT GANG_N_1(LINEAR_AXES, " %c") " %c"), + GET_TEXT(MSG_LCD_ENDSTOPS), + LINEAR_AXIS_LIST(chrX, chrY, chrZ, chrI, chrJ, chrK), chrP + ) + ); #if BOTH(SD_ABORT_ON_ENDSTOP_HIT, SDSUPPORT) if (planner.abort_on_endstop_hit) { @@ -470,6 +545,24 @@ void _O2 Endstops::report_states() { #if HAS_Z4_MAX ES_REPORT(Z4_MAX); #endif + #if HAS_I_MIN + ES_REPORT(I_MIN); + #endif + #if HAS_I_MAX + ES_REPORT(I_MAX); + #endif + #if HAS_J_MIN + ES_REPORT(J_MIN); + #endif + #if HAS_J_MAX + ES_REPORT(J_MAX); + #endif + #if HAS_K_MIN + ES_REPORT(K_MIN); + #endif + #if HAS_K_MAX + ES_REPORT(K_MAX); + #endif #if BOTH(MARLIN_DEV_MODE, PROBE_ACTIVATION_SWITCH) print_es_state(probe_switch_activated(), PSTR(STR_PROBE_EN)); #endif @@ -542,6 +635,10 @@ void Endstops::update() { #define Z_AXIS_HEAD Z_AXIS #endif + #define I_AXIS_HEAD I_AXIS + #define J_AXIS_HEAD J_AXIS + #define K_AXIS_HEAD K_AXIS + /** * Check and update endstops */ @@ -649,6 +746,84 @@ void Endstops::update() { #endif #endif + #if HAS_I_MIN + #if ENABLED(I_DUAL_ENDSTOPS) + UPDATE_ENDSTOP_BIT(I, MIN); + #if HAS_I2_MIN + UPDATE_ENDSTOP_BIT(I2, MAX); + #else + COPY_LIVE_STATE(I_MIN, I2_MIN); + #endif + #else + UPDATE_ENDSTOP_BIT(I, MIN); + #endif + #endif + + #if HAS_I_MAX + #if ENABLED(I_DUAL_ENDSTOPS) + UPDATE_ENDSTOP_BIT(I, MAX); + #if HAS_I2_MAX + UPDATE_ENDSTOP_BIT(I2, MAX); + #else + COPY_LIVE_STATE(I_MAX, I2_MAX); + #endif + #else + UPDATE_ENDSTOP_BIT(I, MAX); + #endif + #endif + + #if HAS_J_MIN + #if ENABLED(J_DUAL_ENDSTOPS) + UPDATE_ENDSTOP_BIT(J, MIN); + #if HAS_J2_MIN + UPDATE_ENDSTOP_BIT(J2, MIN); + #else + COPY_LIVE_STATE(J_MIN, J2_MIN); + #endif + #else + UPDATE_ENDSTOP_BIT(J, MIN); + #endif + #endif + + #if HAS_J_MAX + #if ENABLED(J_DUAL_ENDSTOPS) + UPDATE_ENDSTOP_BIT(J, MAX); + #if HAS_J2_MAX + UPDATE_ENDSTOP_BIT(J2, MAX); + #else + COPY_LIVE_STATE(J_MAX, J2_MAX); + #endif + #else + UPDATE_ENDSTOP_BIT(J, MAX); + #endif + #endif + + #if HAS_K_MIN + #if ENABLED(K_DUAL_ENDSTOPS) + UPDATE_ENDSTOP_BIT(K, MIN); + #if HAS_K2_MIN + UPDATE_ENDSTOP_BIT(K2, MIN); + #else + COPY_LIVE_STATE(K_MIN, K2_MIN); + #endif + #else + UPDATE_ENDSTOP_BIT(K, MIN); + #endif + #endif + + #if HAS_K_MAX + #if ENABLED(K_DUAL_ENDSTOPS) + UPDATE_ENDSTOP_BIT(K, MAX); + #if HAS_K2_MAX + UPDATE_ENDSTOP_BIT(K2, MAX); + #else + COPY_LIVE_STATE(K_MAX, K2_MAX); + #endif + #else + UPDATE_ENDSTOP_BIT(K, MAX); + #endif + #endif + #if ENDSTOP_NOISE_THRESHOLD /** @@ -757,9 +932,13 @@ void Endstops::update() { #endif // If G38 command is active check Z_MIN_PROBE for ALL movement if (G38_move && TEST_ENDSTOP(_ENDSTOP(Z, MIN_PROBE)) != _G38_OPEN_STATE) { - if (stepper.axis_is_moving(X_AXIS)) { _ENDSTOP_HIT(X, MIN); planner.endstop_triggered(X_AXIS); } - else if (stepper.axis_is_moving(Y_AXIS)) { _ENDSTOP_HIT(Y, MIN); planner.endstop_triggered(Y_AXIS); } - else if (stepper.axis_is_moving(Z_AXIS)) { _ENDSTOP_HIT(Z, MIN); planner.endstop_triggered(Z_AXIS); } + if (stepper.axis_is_moving(X_AXIS)) { _ENDSTOP_HIT(X, TERN(X_HOME_TO_MIN, MIN, MAX)); planner.endstop_triggered(X_AXIS); } + #if HAS_Y_AXIS + else if (stepper.axis_is_moving(Y_AXIS)) { _ENDSTOP_HIT(Y, TERN(Y_HOME_TO_MIN, MIN, MAX)); planner.endstop_triggered(Y_AXIS); } + #endif + #if HAS_Z_AXIS + else if (stepper.axis_is_moving(Z_AXIS)) { _ENDSTOP_HIT(Z, TERN(Z_HOME_TO_MIN, MIN, MAX)); planner.endstop_triggered(Z_AXIS); } + #endif G38_did_trigger = true; } #endif @@ -797,79 +976,128 @@ void Endstops::update() { } } - if (stepper.axis_is_moving(Y_AXIS)) { - if (stepper.motor_direction(Y_AXIS_HEAD)) { // -direction - #if HAS_Y_MIN || (Y_SPI_SENSORLESS && Y_HOME_TO_MIN) - PROCESS_ENDSTOP_Y(MIN); - #if CORE_DIAG(XY, X, MIN) - PROCESS_CORE_ENDSTOP(X,MIN,Y,MIN); - #elif CORE_DIAG(XY, X, MAX) - PROCESS_CORE_ENDSTOP(X,MAX,Y,MIN); - #elif CORE_DIAG(YZ, Z, MIN) - PROCESS_CORE_ENDSTOP(Z,MIN,Y,MIN); - #elif CORE_DIAG(YZ, Z, MAX) - PROCESS_CORE_ENDSTOP(Z,MAX,Y,MIN); + #if HAS_Y_AXIS + if (stepper.axis_is_moving(Y_AXIS)) { + if (stepper.motor_direction(Y_AXIS_HEAD)) { // -direction + #if HAS_Y_MIN || (Y_SPI_SENSORLESS && Y_HOME_TO_MIN) + PROCESS_ENDSTOP_Y(MIN); + #if CORE_DIAG(XY, X, MIN) + PROCESS_CORE_ENDSTOP(X,MIN,Y,MIN); + #elif CORE_DIAG(XY, X, MAX) + PROCESS_CORE_ENDSTOP(X,MAX,Y,MIN); + #elif CORE_DIAG(YZ, Z, MIN) + PROCESS_CORE_ENDSTOP(Z,MIN,Y,MIN); + #elif CORE_DIAG(YZ, Z, MAX) + PROCESS_CORE_ENDSTOP(Z,MAX,Y,MIN); + #endif #endif - #endif + } + else { // +direction + #if HAS_Y_MAX || (Y_SPI_SENSORLESS && Y_HOME_TO_MAX) + PROCESS_ENDSTOP_Y(MAX); + #if CORE_DIAG(XY, X, MIN) + PROCESS_CORE_ENDSTOP(X,MIN,Y,MAX); + #elif CORE_DIAG(XY, X, MAX) + PROCESS_CORE_ENDSTOP(X,MAX,Y,MAX); + #elif CORE_DIAG(YZ, Z, MIN) + PROCESS_CORE_ENDSTOP(Z,MIN,Y,MAX); + #elif CORE_DIAG(YZ, Z, MAX) + PROCESS_CORE_ENDSTOP(Z,MAX,Y,MAX); + #endif + #endif + } } - else { // +direction - #if HAS_Y_MAX || (Y_SPI_SENSORLESS && Y_HOME_TO_MAX) - PROCESS_ENDSTOP_Y(MAX); - #if CORE_DIAG(XY, X, MIN) - PROCESS_CORE_ENDSTOP(X,MIN,Y,MAX); - #elif CORE_DIAG(XY, X, MAX) - PROCESS_CORE_ENDSTOP(X,MAX,Y,MAX); - #elif CORE_DIAG(YZ, Z, MIN) - PROCESS_CORE_ENDSTOP(Z,MIN,Y,MAX); - #elif CORE_DIAG(YZ, Z, MAX) - PROCESS_CORE_ENDSTOP(Z,MAX,Y,MAX); + #endif + + #if HAS_Z_AXIS + if (stepper.axis_is_moving(Z_AXIS)) { + if (stepper.motor_direction(Z_AXIS_HEAD)) { // Z -direction. Gantry down, bed up. + + #if HAS_Z_MIN || (Z_SPI_SENSORLESS && Z_HOME_TO_MIN) + if ( TERN1(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN, z_probe_enabled) + && TERN1(HAS_CUSTOM_PROBE_PIN, !z_probe_enabled) + ) PROCESS_ENDSTOP_Z(MIN); + #if CORE_DIAG(XZ, X, MIN) + PROCESS_CORE_ENDSTOP(X,MIN,Z,MIN); + #elif CORE_DIAG(XZ, X, MAX) + PROCESS_CORE_ENDSTOP(X,MAX,Z,MIN); + #elif CORE_DIAG(YZ, Y, MIN) + PROCESS_CORE_ENDSTOP(Y,MIN,Z,MIN); + #elif CORE_DIAG(YZ, Y, MAX) + PROCESS_CORE_ENDSTOP(Y,MAX,Z,MIN); + #endif #endif - #endif + + // When closing the gap check the enabled probe + #if HAS_CUSTOM_PROBE_PIN + if (z_probe_enabled) PROCESS_ENDSTOP(Z, MIN_PROBE); + #endif + } + else { // Z +direction. Gantry up, bed down. + #if HAS_Z_MAX || (Z_SPI_SENSORLESS && Z_HOME_TO_MAX) + #if ENABLED(Z_MULTI_ENDSTOPS) + PROCESS_ENDSTOP_Z(MAX); + #elif !HAS_CUSTOM_PROBE_PIN || Z_MAX_PIN != Z_MIN_PROBE_PIN // No probe or probe is Z_MIN || Probe is not Z_MAX + PROCESS_ENDSTOP(Z, MAX); + #endif + #if CORE_DIAG(XZ, X, MIN) + PROCESS_CORE_ENDSTOP(X,MIN,Z,MAX); + #elif CORE_DIAG(XZ, X, MAX) + PROCESS_CORE_ENDSTOP(X,MAX,Z,MAX); + #elif CORE_DIAG(YZ, Y, MIN) + PROCESS_CORE_ENDSTOP(Y,MIN,Z,MAX); + #elif CORE_DIAG(YZ, Y, MAX) + PROCESS_CORE_ENDSTOP(Y,MAX,Z,MAX); + #endif + #endif + } } - } + #endif - if (stepper.axis_is_moving(Z_AXIS)) { - if (stepper.motor_direction(Z_AXIS_HEAD)) { // Z -direction. Gantry down, bed up. - - #if HAS_Z_MIN || (Z_SPI_SENSORLESS && Z_HOME_TO_MIN) - if ( TERN1(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN, z_probe_enabled) - && TERN1(HAS_CUSTOM_PROBE_PIN, !z_probe_enabled) - ) PROCESS_ENDSTOP_Z(MIN); - #if CORE_DIAG(XZ, X, MIN) - PROCESS_CORE_ENDSTOP(X,MIN,Z,MIN); - #elif CORE_DIAG(XZ, X, MAX) - PROCESS_CORE_ENDSTOP(X,MAX,Z,MIN); - #elif CORE_DIAG(YZ, Y, MIN) - PROCESS_CORE_ENDSTOP(Y,MIN,Z,MIN); - #elif CORE_DIAG(YZ, Y, MAX) - PROCESS_CORE_ENDSTOP(Y,MAX,Z,MIN); + #if LINEAR_AXES >= 4 + if (stepper.axis_is_moving(I_AXIS)) { + if (stepper.motor_direction(I_AXIS_HEAD)) { // -direction + #if HAS_I_MIN || (I_SPI_SENSORLESS && I_HOME_TO_MIN) + PROCESS_ENDSTOP(I, MIN); #endif - #endif + } + else { // +direction + #if HAS_I_MAX || (I_SPI_SENSORLESS && I_HOME_TO_MAX) + PROCESS_ENDSTOP(I, MAX); + #endif + } + } + #endif - // When closing the gap check the enabled probe - #if HAS_CUSTOM_PROBE_PIN - if (z_probe_enabled) PROCESS_ENDSTOP(Z, MIN_PROBE); - #endif + #if LINEAR_AXES >= 5 + if (stepper.axis_is_moving(J_AXIS)) { + if (stepper.motor_direction(J_AXIS_HEAD)) { // -direction + #if HAS_J_MIN || (J_SPI_SENSORLESS && J_HOME_TO_MIN) + PROCESS_ENDSTOP(J, MIN); + #endif + } + else { // +direction + #if HAS_J_MAX || (J_SPI_SENSORLESS && J_HOME_TO_MAX) + PROCESS_ENDSTOP(J, MAX); + #endif + } } - else { // Z +direction. Gantry up, bed down. - #if HAS_Z_MAX || (Z_SPI_SENSORLESS && Z_HOME_TO_MAX) - #if ENABLED(Z_MULTI_ENDSTOPS) - PROCESS_ENDSTOP_Z(MAX); - #elif !HAS_CUSTOM_PROBE_PIN || Z_MAX_PIN != Z_MIN_PROBE_PIN // No probe or probe is Z_MIN || Probe is not Z_MAX - PROCESS_ENDSTOP(Z, MAX); + #endif + + #if LINEAR_AXES >= 6 + if (stepper.axis_is_moving(K_AXIS)) { + if (stepper.motor_direction(K_AXIS_HEAD)) { // -direction + #if HAS_K_MIN || (K_SPI_SENSORLESS && K_HOME_TO_MIN) + PROCESS_ENDSTOP(K, MIN); #endif - #if CORE_DIAG(XZ, X, MIN) - PROCESS_CORE_ENDSTOP(X,MIN,Z,MAX); - #elif CORE_DIAG(XZ, X, MAX) - PROCESS_CORE_ENDSTOP(X,MAX,Z,MAX); - #elif CORE_DIAG(YZ, Y, MIN) - PROCESS_CORE_ENDSTOP(Y,MIN,Z,MAX); - #elif CORE_DIAG(YZ, Y, MAX) - PROCESS_CORE_ENDSTOP(Y,MAX,Z,MAX); + } + else { // +direction + #if HAS_K_MAX || (K_SPI_SENSORLESS && K_HOME_TO_MAX) + PROCESS_ENDSTOP(K, MAX); #endif - #endif + } } - } + #endif } // Endstops::update() #if ENABLED(SPI_ENDSTOPS) @@ -912,6 +1140,24 @@ void Endstops::update() { hit = true; } #endif + #if I_SPI_SENSORLESS + if (tmc_spi_homing.i && stepperI.test_stall_status()) { + SBI(live_state, I_ENDSTOP); + hit = true; + } + #endif + #if J_SPI_SENSORLESS + if (tmc_spi_homing.j && stepperJ.test_stall_status()) { + SBI(live_state, J_ENDSTOP); + hit = true; + } + #endif + #if K_SPI_SENSORLESS + if (tmc_spi_homing.k && stepperK.test_stall_status()) { + SBI(live_state, K_ENDSTOP); + hit = true; + } + #endif if (TERN0(ENDSTOP_INTERRUPTS_FEATURE, hit)) update(); @@ -922,6 +1168,9 @@ void Endstops::update() { TERN_(X_SPI_SENSORLESS, CBI(live_state, X_ENDSTOP)); TERN_(Y_SPI_SENSORLESS, CBI(live_state, Y_ENDSTOP)); TERN_(Z_SPI_SENSORLESS, CBI(live_state, Z_ENDSTOP)); + TERN_(I_SPI_SENSORLESS, CBI(live_state, I_ENDSTOP)); + TERN_(J_SPI_SENSORLESS, CBI(live_state, J_ENDSTOP)); + TERN_(K_SPI_SENSORLESS, CBI(live_state, K_ENDSTOP)); } #endif // SPI_ENDSTOPS @@ -998,6 +1247,24 @@ void Endstops::update() { #if HAS_Z4_MAX ES_GET_STATE(Z4_MAX); #endif + #if HAS_I_MAX + ES_GET_STATE(I_MAX); + #endif + #if HAS_I_MIN + ES_GET_STATE(I_MIN); + #endif + #if HAS_J_MAX + ES_GET_STATE(J_MAX); + #endif + #if HAS_J_MIN + ES_GET_STATE(J_MIN); + #endif + #if HAS_K_MAX + ES_GET_STATE(K_MAX); + #endif + #if HAS_K_MIN + ES_GET_STATE(K_MIN); + #endif uint16_t endstop_change = live_state_local ^ old_live_state_local; #define ES_REPORT_CHANGE(S) if (TEST(endstop_change, S)) SERIAL_ECHOPAIR(" " STRINGIFY(S) ":", TEST(live_state_local, S)) @@ -1054,6 +1321,24 @@ void Endstops::update() { #if HAS_Z4_MAX ES_REPORT_CHANGE(Z4_MAX); #endif + #if HAS_I_MIN + ES_REPORT_CHANGE(I_MIN); + #endif + #if HAS_I_MAX + ES_REPORT_CHANGE(I_MAX); + #endif + #if HAS_J_MIN + ES_REPORT_CHANGE(J_MIN); + #endif + #if HAS_J_MAX + ES_REPORT_CHANGE(J_MAX); + #endif + #if HAS_K_MIN + ES_REPORT_CHANGE(K_MIN); + #endif + #if HAS_K_MAX + ES_REPORT_CHANGE(K_MAX); + #endif SERIAL_ECHOLNPGM("\n"); analogWrite(pin_t(LED_PIN), local_LED_status); local_LED_status ^= 255; diff --git a/Marlin/src/module/endstops.h b/Marlin/src/module/endstops.h index 5da09f41cf514..e8365ce1ede38 100644 --- a/Marlin/src/module/endstops.h +++ b/Marlin/src/module/endstops.h @@ -39,6 +39,12 @@ enum EndstopEnum : char { _ES_ITEM(HAS_Y_MAX, Y_MAX) _ES_ITEM(HAS_Z_MIN, Z_MIN) _ES_ITEM(HAS_Z_MAX, Z_MAX) + _ES_ITEM(HAS_I_MIN, I_MIN) + _ES_ITEM(HAS_I_MAX, I_MAX) + _ES_ITEM(HAS_J_MIN, J_MIN) + _ES_ITEM(HAS_J_MAX, J_MAX) + _ES_ITEM(HAS_K_MIN, K_MIN) + _ES_ITEM(HAS_K_MAX, K_MAX) // Extra Endstops for XYZ #if ENABLED(X_DUAL_ENDSTOPS) @@ -75,7 +81,7 @@ enum EndstopEnum : char { #if HAS_Y_MIN || HAS_Y_MAX , Y_ENDSTOP = TERN(Y_HOME_TO_MAX, Y_MAX, Y_MIN) #endif - #if HAS_Z_MIN || HAS_Z_MAX + #if HAS_Z_MIN || HAS_Z_MAX || HOMING_Z_WITH_PROBE , Z_ENDSTOP = TERN(Z_HOME_TO_MAX, Z_MAX, TERN(HOMING_Z_WITH_PROBE, Z_MIN_PROBE, Z_MIN)) #endif }; @@ -217,7 +223,7 @@ class Endstops { typedef struct { union { bool any; - struct { bool x:1, y:1, z:1; }; + struct { bool LINEAR_AXIS_LIST(x:1, y:1, z:1, i:1, j:1, k:1); }; }; } tmc_spi_homing_t; static tmc_spi_homing_t tmc_spi_homing; diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 235a969f66e7c..63fdd5afc3db4 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -89,7 +89,7 @@ bool relative_mode; // = false; #define Z_INIT_POS Z_HOME_POS #endif -xyze_pos_t current_position = { X_HOME_POS, Y_HOME_POS, Z_INIT_POS }; +xyze_pos_t current_position = LOGICAL_AXIS_ARRAY(0, X_HOME_POS, Y_HOME_POS, Z_INIT_POS, I_HOME_POS, J_HOME_POS, K_HOME_POS); /** * Cartesian Destination @@ -143,7 +143,7 @@ xyz_pos_t cartes; #if IS_KINEMATIC - abc_pos_t delta; + abce_pos_t delta; #if HAS_SCARA_OFFSET abc_pos_t scara_home_offset; @@ -195,16 +195,35 @@ inline void report_more_positions() { // Report the logical position for a given machine position inline void report_logical_position(const xyze_pos_t &rpos) { const xyze_pos_t lpos = rpos.asLogical(); - SERIAL_ECHOPAIR_P(X_LBL, lpos.x, SP_Y_LBL, lpos.y, SP_Z_LBL, lpos.z, SP_E_LBL, lpos.e); + SERIAL_ECHOPAIR_P( + LIST_N(DOUBLE(LINEAR_AXES), + X_LBL, lpos.x, + SP_Y_LBL, lpos.y, + SP_Z_LBL, lpos.z, + SP_I_LBL, lpos.i, + SP_J_LBL, lpos.j, + SP_K_LBL, lpos.k + ) + #if HAS_EXTRUDERS + , SP_E_LBL, lpos.e + #endif + ); } // Report the real current position according to the steppers. // Forward kinematics and un-leveling are applied. void report_real_position() { get_cartesian_from_steppers(); - xyze_pos_t npos = cartes; - npos.e = planner.get_axis_position_mm(E_AXIS); + xyze_pos_t npos = LOGICAL_AXIS_ARRAY( + planner.get_axis_position_mm(E_AXIS), + cartes.x, cartes.y, cartes.z, + planner.get_axis_position_mm(I_AXIS), + planner.get_axis_position_mm(J_AXIS), + planner.get_axis_position_mm(K_AXIS) + ); + TERN_(HAS_POSITION_MODIFIERS, planner.unapply_modifiers(npos, true)); + report_logical_position(npos); report_more_positions(); } @@ -247,7 +266,18 @@ void report_current_position_projected() { get_cartesian_from_steppers(); const xyz_pos_t lpos = cartes.asLogical(); - SERIAL_ECHOPAIR("X:", lpos.x, " Y:", lpos.y, " Z:", lpos.z, " E:", current_position.e); + SERIAL_ECHOPAIR( + "X:", lpos.x + #if HAS_Y_AXIS + , " Y:", lpos.y + #endif + #if HAS_Z_AXIS + , " Z:", lpos.z + #endif + #if HAS_EXTRUDERS + , " E:", current_position.e + #endif + ); stepper.report_positions(); #if IS_SCARA @@ -275,6 +305,10 @@ void report_current_position_projected() { #endif +void home_if_needed(const bool keeplev/*=false*/) { + if (!all_axes_trusted()) gcode.home_all_axes(keeplev); +} + /** * Run out the planner buffer and re-sync the current * position from the last-updated stepper positions. @@ -309,7 +343,9 @@ void sync_plan_position() { planner.set_position_mm(current_position); } -void sync_plan_position_e() { planner.set_e_position_mm(current_position.e); } +#if HAS_EXTRUDERS + void sync_plan_position_e() { planner.set_e_position_mm(current_position.e); } +#endif /** * Get the stepper positions in the cartes[] array. @@ -323,20 +359,21 @@ void sync_plan_position_e() { planner.set_e_position_mm(current_position.e); } void get_cartesian_from_steppers() { #if ENABLED(DELTA) forward_kinematics(planner.get_axis_positions_mm()); - #else - #if IS_SCARA - forward_kinematics( - planner.get_axis_position_degrees(A_AXIS) - , planner.get_axis_position_degrees(B_AXIS) - #if ENABLED(AXEL_TPARA) - , planner.get_axis_position_degrees(C_AXIS) - #endif - ); - #else - cartes.x = planner.get_axis_position_mm(X_AXIS); - cartes.y = planner.get_axis_position_mm(Y_AXIS); - #endif + #elif IS_SCARA + forward_kinematics( + planner.get_axis_position_degrees(A_AXIS), planner.get_axis_position_degrees(B_AXIS) + OPTARG(AXEL_TPARA, planner.get_axis_position_degrees(C_AXIS)) + ); cartes.z = planner.get_axis_position_mm(Z_AXIS); + #else + LINEAR_AXIS_CODE( + cartes.x = planner.get_axis_position_mm(X_AXIS), + cartes.y = planner.get_axis_position_mm(Y_AXIS), + cartes.z = planner.get_axis_position_mm(Z_AXIS), + cartes.i = planner.get_axis_position_mm(I_AXIS), + cartes.j = planner.get_axis_position_mm(J_AXIS), + cartes.k = planner.get_axis_position_mm(K_AXIS) + ); #endif } @@ -354,11 +391,10 @@ void get_cartesian_from_steppers() { void set_current_from_steppers_for_axis(const AxisEnum axis) { get_cartesian_from_steppers(); xyze_pos_t pos = cartes; - pos.e = planner.get_axis_position_mm(E_AXIS); - #if HAS_POSITION_MODIFIERS - planner.unapply_modifiers(pos, true); - #endif + TERN_(HAS_EXTRUDERS, pos.e = planner.get_axis_position_mm(E_AXIS)); + + TERN_(HAS_POSITION_MODIFIERS, planner.unapply_modifiers(pos, true)); if (axis == ALL_AXES_ENUM) current_position = pos; @@ -371,7 +407,7 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) { * (or from wherever it has been told it is located). */ void line_to_current_position(const_feedRate_t fr_mm_s/*=feedrate_mm_s*/) { - planner.buffer_line(current_position, fr_mm_s, active_extruder); + planner.buffer_line(current_position, fr_mm_s); } #if HAS_EXTRUDERS @@ -397,7 +433,7 @@ void line_to_current_position(const_feedRate_t fr_mm_s/*=feedrate_mm_s*/) { #else if (current_position == destination) return; - planner.buffer_line(destination, scaled_fr_mm_s, active_extruder); + planner.buffer_line(destination, scaled_fr_mm_s); #endif current_position = destination; @@ -411,9 +447,7 @@ void line_to_current_position(const_feedRate_t fr_mm_s/*=feedrate_mm_s*/) { * - Extrude the specified length regardless of flow percentage. */ void _internal_move_to_destination(const_feedRate_t fr_mm_s/*=0.0f*/ - #if IS_KINEMATIC - , const bool is_fast/*=false*/ - #endif + OPTARG(IS_KINEMATIC, const bool is_fast/*=false*/) ) { const feedRate_t old_feedrate = feedrate_mm_s; if (fr_mm_s) feedrate_mm_s = fr_mm_s; @@ -433,28 +467,30 @@ void _internal_move_to_destination(const_feedRate_t fr_mm_s/*=0.0f*/ feedrate_mm_s = old_feedrate; feedrate_percentage = old_pct; - #if HAS_EXTRUDERS - planner.e_factor[active_extruder] = old_fac; - #endif + TERN_(HAS_EXTRUDERS, planner.e_factor[active_extruder] = old_fac); } /** - * Plan a move to (X, Y, Z) with separation of the XY and Z components. + * Plan a move to (X, Y, Z, [I, [J, [K]]]) and set the current_position + * Plan a move to (X, Y, Z) with separation of Z from other components. * - * - If Z is moving up, the Z move is done before XY. - * - If Z is moving down, the Z move is done after XY. + * - If Z is moving up, the Z move is done before XY, etc. + * - If Z is moving down, the Z move is done after XY, etc. * - Delta may lower Z first to get into the free motion zone. * - Before returning, wait for the planner buffer to empty. */ -void do_blocking_move_to(const float rx, const float ry, const float rz, const_feedRate_t fr_mm_s/*=0.0*/) { +void do_blocking_move_to(LINEAR_AXIS_ARGS(const float), const_feedRate_t fr_mm_s/*=0.0f*/) { DEBUG_SECTION(log_move, "do_blocking_move_to", DEBUGGING(LEVELING)); - if (DEBUGGING(LEVELING)) DEBUG_XYZ("> ", rx, ry, rz); + if (DEBUGGING(LEVELING)) DEBUG_XYZ("> ", LINEAR_AXIS_ARGS()); + + const feedRate_t xy_feedrate = fr_mm_s ?: feedRate_t(XY_PROBE_FEEDRATE_MM_S); - const feedRate_t z_feedrate = fr_mm_s ?: homing_feedrate(Z_AXIS), - xy_feedrate = fr_mm_s ?: feedRate_t(XY_PROBE_FEEDRATE_MM_S); + #if HAS_Z_AXIS + const feedRate_t z_feedrate = fr_mm_s ?: homing_feedrate(Z_AXIS); + #endif #if EITHER(DELTA, IS_SCARA) - if (!position_is_reachable(rx, ry)) return; + if (!position_is_reachable(x, y)) return; destination = current_position; // sync destination at the start #endif @@ -466,8 +502,8 @@ void do_blocking_move_to(const float rx, const float ry, const float rz, const_f // when in the danger zone 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) + if (z > delta_clip_start_height) { // staying in the danger zone + destination.set(x, y, z); // 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; @@ -477,18 +513,18 @@ void do_blocking_move_to(const float rx, const float ry, const float rz, const_f if (DEBUGGING(LEVELING)) DEBUG_POS("zone border move", current_position); } - if (rz > current_position.z) { // raising? - destination.z = rz; + if (z > current_position.z) { // raising? + destination.z = z; prepare_internal_fast_move_to_destination(z_feedrate); // set current_position from destination if (DEBUGGING(LEVELING)) DEBUG_POS("z raise move", current_position); } - destination.set(rx, ry); + destination.set(x, y); prepare_internal_move_to_destination(); // set current_position from destination if (DEBUGGING(LEVELING)) DEBUG_POS("xy move", current_position); - if (rz < current_position.z) { // lowering? - destination.z = rz; + if (z < current_position.z) { // lowering? + destination.z = z; prepare_internal_fast_move_to_destination(z_feedrate); // set current_position from destination if (DEBUGGING(LEVELING)) DEBUG_POS("z lower move", current_position); } @@ -496,36 +532,40 @@ void do_blocking_move_to(const float rx, const float ry, const float rz, const_f #elif IS_SCARA // If Z needs to raise, do it before moving XY - if (destination.z < rz) { - destination.z = rz; + if (destination.z < z) { + destination.z = z; prepare_internal_fast_move_to_destination(z_feedrate); } - destination.set(rx, ry); + destination.set(x, y); prepare_internal_fast_move_to_destination(xy_feedrate); // If Z needs to lower, do it after moving XY - if (destination.z > rz) { - destination.z = rz; + if (destination.z > z) { + destination.z = z; prepare_internal_fast_move_to_destination(z_feedrate); } #else - // If Z needs to raise, do it before moving XY - if (current_position.z < rz) { - current_position.z = rz; - line_to_current_position(z_feedrate); - } + #if HAS_Z_AXIS + // If Z needs to raise, do it before moving XY + if (current_position.z < z) { + current_position.z = z; + line_to_current_position(z_feedrate); + } + #endif - current_position.set(rx, ry); + current_position.set(x, y); line_to_current_position(xy_feedrate); - // If Z needs to lower, do it after moving XY - if (current_position.z > rz) { - current_position.z = rz; - line_to_current_position(z_feedrate); - } + #if HAS_Z_AXIS + // If Z needs to lower, do it after moving XY + if (current_position.z > z) { + current_position.z = z; + line_to_current_position(z_feedrate); + } + #endif #endif @@ -533,41 +573,97 @@ void do_blocking_move_to(const float rx, const float ry, const float rz, const_f } 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); + do_blocking_move_to(LINEAR_AXIS_LIST(raw.x, raw.y, current_position.z, current_position.i, current_position.j, current_position.k), fr_mm_s); } 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); + do_blocking_move_to(LINEAR_AXIS_ELEM(raw), fr_mm_s); } 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); + do_blocking_move_to(LINEAR_AXIS_ELEM(raw), fr_mm_s); } - void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s/*=0.0*/) { - do_blocking_move_to(rx, current_position.y, current_position.z, fr_mm_s); -} -void do_blocking_move_to_y(const_float_t ry, const_feedRate_t fr_mm_s/*=0.0*/) { - do_blocking_move_to(current_position.x, ry, current_position.z, fr_mm_s); -} -void do_blocking_move_to_z(const_float_t rz, const_feedRate_t fr_mm_s/*=0.0*/) { - do_blocking_move_to_xy_z(current_position, rz, fr_mm_s); + do_blocking_move_to( + LINEAR_AXIS_LIST(rx, current_position.y, current_position.z, current_position.i, current_position.j, current_position.k), + fr_mm_s + ); } -void do_blocking_move_to_xy(const_float_t rx, const_float_t ry, const_feedRate_t fr_mm_s/*=0.0*/) { - do_blocking_move_to(rx, ry, current_position.z, fr_mm_s); -} -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); -} +#if HAS_Y_AXIS + void do_blocking_move_to_y(const_float_t ry, const_feedRate_t fr_mm_s/*=0.0*/) { + do_blocking_move_to( + LINEAR_AXIS_LIST(current_position.x, ry, current_position.z, current_position.i, current_position.j, current_position.k), + fr_mm_s + ); + } +#endif -void do_blocking_move_to_xy_z(const xy_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s/*=0.0f*/) { - do_blocking_move_to(raw.x, raw.y, z, fr_mm_s); -} +#if HAS_Z_AXIS + void do_blocking_move_to_z(const_float_t rz, const_feedRate_t fr_mm_s/*=0.0*/) { + do_blocking_move_to_xy_z(current_position, rz, fr_mm_s); + } +#endif -void do_z_clearance(const_float_t zclear, const bool lower_allowed/*=false*/) { - float zdest = zclear; - if (!lower_allowed) NOLESS(zdest, current_position.z); - do_blocking_move_to_z(_MIN(zdest, Z_MAX_POS), TERN(HAS_BED_PROBE, z_probe_fast_mm_s, homing_feedrate(Z_AXIS))); -} +#if LINEAR_AXES >= 4 + void do_blocking_move_to_i(const_float_t ri, const_feedRate_t fr_mm_s/*=0.0*/) { + do_blocking_move_to_xyz_i(current_position, ri, fr_mm_s); + } + void do_blocking_move_to_xyz_i(const xyze_pos_t &raw, const_float_t i, const_feedRate_t fr_mm_s/*=0.0f*/) { + do_blocking_move_to( + LINEAR_AXIS_LIST(raw.x, raw.y, raw.z, i, raw.j, raw.k), + fr_mm_s + ); + } +#endif + +#if LINEAR_AXES >= 5 + void do_blocking_move_to_j(const_float_t rj, const_feedRate_t fr_mm_s/*=0.0*/) { + do_blocking_move_to_xyzi_j(current_position, rj, fr_mm_s); + } + void do_blocking_move_to_xyzi_j(const xyze_pos_t &raw, const_float_t j, const_feedRate_t fr_mm_s/*=0.0f*/) { + do_blocking_move_to( + LINEAR_AXIS_LIST(raw.x, raw.y, raw.z, raw.i, j, raw.k), + fr_mm_s + ); + } +#endif + +#if LINEAR_AXES >= 6 + void do_blocking_move_to_k(const_float_t rk, const_feedRate_t fr_mm_s/*=0.0*/) { + do_blocking_move_to_xyzij_k(current_position, rk, fr_mm_s); + } + void do_blocking_move_to_xyzij_k(const xyze_pos_t &raw, const_float_t k, const_feedRate_t fr_mm_s/*=0.0f*/) { + do_blocking_move_to( + LINEAR_AXIS_LIST(raw.x, raw.y, raw.z, raw.i, raw.j, k), + fr_mm_s + ); + } +#endif + +#if HAS_Y_AXIS + void do_blocking_move_to_xy(const_float_t rx, const_float_t ry, const_feedRate_t fr_mm_s/*=0.0*/) { + do_blocking_move_to( + LINEAR_AXIS_LIST(rx, ry, current_position.z, current_position.i, current_position.j, current_position.k), + fr_mm_s + ); + } + 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); + } +#endif + +#if HAS_Z_AXIS + void do_blocking_move_to_xy_z(const xy_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s/*=0.0f*/) { + do_blocking_move_to( + LINEAR_AXIS_LIST(raw.x, raw.y, z, current_position.i, current_position.j, current_position.k), + fr_mm_s + ); + } + void do_z_clearance(const_float_t zclear, const bool lower_allowed/*=false*/) { + float zdest = zclear; + if (!lower_allowed) NOLESS(zdest, current_position.z); + do_blocking_move_to_z(_MIN(zdest, Z_MAX_POS), TERN(HAS_BED_PROBE, z_probe_fast_mm_s, homing_feedrate(Z_AXIS))); + } +#endif // // Prepare to do endstop or probe moves with custom feedrates. @@ -593,8 +689,8 @@ void restore_feedrate_and_scaling() { // Software Endstops are based on the configured limits. soft_endstops_t soft_endstop = { true, false, - { X_MIN_POS, Y_MIN_POS, Z_MIN_POS }, - { X_MAX_POS, Y_MAX_POS, Z_MAX_POS } + LINEAR_AXIS_ARRAY(X_MIN_POS, Y_MIN_POS, Z_MIN_POS, I_MIN_POS, J_MIN_POS, K_MIN_POS), + LINEAR_AXIS_ARRAY(X_MAX_BED, Y_MAX_BED, Z_MAX_POS, I_MAX_POS, J_MAX_POS, K_MAX_POS) }; /** @@ -607,10 +703,8 @@ void restore_feedrate_and_scaling() { * at the same positions relative to the machine. */ 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*/ - #endif + OPTARG(HAS_HOTEND_OFFSET, const uint8_t old_tool_index/*=0*/) + OPTARG(HAS_HOTEND_OFFSET, const uint8_t new_tool_index/*=0*/) ) { #if ENABLED(DUAL_X_CARRIAGE) @@ -723,25 +817,59 @@ void restore_feedrate_and_scaling() { #endif } - if (axis_was_homed(Y_AXIS)) { - #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_Y) - NOLESS(target.y, soft_endstop.min.y); + #if HAS_Y_AXIS + if (axis_was_homed(Y_AXIS)) { + #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_Y) + NOLESS(target.y, soft_endstop.min.y); + #endif + #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_Y) + NOMORE(target.y, soft_endstop.max.y); + #endif + } + #endif + + #endif + + #if HAS_Z_AXIS + if (axis_was_homed(Z_AXIS)) { + #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_Z) + NOLESS(target.z, soft_endstop.min.z); #endif - #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_Y) - NOMORE(target.y, soft_endstop.max.y); + #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_Z) + NOMORE(target.z, soft_endstop.max.z); + #endif + } + #endif + #if LINEAR_AXES >= 4 + if (axis_was_homed(I_AXIS)) { + #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_I) + NOLESS(target.i, soft_endstop.min.i); + #endif + #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_I) + NOMORE(target.i, soft_endstop.max.i); + #endif + } + #endif + #if LINEAR_AXES >= 5 + if (axis_was_homed(J_AXIS)) { + #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_J) + NOLESS(target.j, soft_endstop.min.j); + #endif + #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_J) + NOMORE(target.j, soft_endstop.max.j); + #endif + } + #endif + #if LINEAR_AXES >= 6 + if (axis_was_homed(K_AXIS)) { + #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_K) + NOLESS(target.k, soft_endstop.min.k); + #endif + #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_K) + NOMORE(target.k, soft_endstop.max.k); #endif } - #endif - - if (axis_was_homed(Z_AXIS)) { - #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_Z) - NOLESS(target.z, soft_endstop.min.z); - #endif - #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_Z) - NOMORE(target.z, soft_endstop.max.z); - #endif - } } #else // !HAS_SOFTWARE_ENDSTOPS @@ -801,7 +929,7 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { // If the move is only in Z/E don't split up the move if (!diff.x && !diff.y) { - planner.buffer_line(destination, scaled_fr_mm_s, active_extruder); + planner.buffer_line(destination, scaled_fr_mm_s); return false; // caller will update current_position } @@ -812,7 +940,7 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { float cartesian_mm = diff.magnitude(); // If the move is very short, check the E move distance - if (UNEAR_ZERO(cartesian_mm)) cartesian_mm = ABS(diff.e); + TERN_(HAS_EXTRUDERS, if (UNEAR_ZERO(cartesian_mm)) cartesian_mm = ABS(diff.e)); // No E move either? Game over. if (UNEAR_ZERO(cartesian_mm)) return true; @@ -857,19 +985,11 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { while (--segments) { segment_idle(next_idle_ms); raw += segment_distance; - if (!planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, cartesian_segment_mm - #if ENABLED(SCARA_FEEDRATE_SCALING) - , inv_duration - #endif - )) break; + if (!planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, cartesian_segment_mm OPTARG(SCARA_FEEDRATE_SCALING, inv_duration))) break; } // Ensure last segment arrives at target location. - planner.buffer_line(destination, scaled_fr_mm_s, active_extruder, cartesian_segment_mm - #if ENABLED(SCARA_FEEDRATE_SCALING) - , inv_duration - #endif - ); + planner.buffer_line(destination, scaled_fr_mm_s, active_extruder, cartesian_segment_mm OPTARG(SCARA_FEEDRATE_SCALING, inv_duration)); return false; // caller will update current_position } @@ -891,7 +1011,7 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { // If the move is only in Z/E don't split up the move if (!diff.x && !diff.y) { - planner.buffer_line(destination, fr_mm_s, active_extruder); + planner.buffer_line(destination, fr_mm_s); return; } @@ -899,7 +1019,7 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { // If the move is very short, check the E move distance // No E move either? Game over. float cartesian_mm = diff.magnitude(); - if (UNEAR_ZERO(cartesian_mm)) cartesian_mm = ABS(diff.e); + TERN_(HAS_EXTRUDERS, if (UNEAR_ZERO(cartesian_mm)) cartesian_mm = ABS(diff.e)); if (UNEAR_ZERO(cartesian_mm)) return; // The length divided by the segment size @@ -928,20 +1048,12 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { while (--segments) { segment_idle(next_idle_ms); raw += segment_distance; - if (!planner.buffer_line(raw, fr_mm_s, active_extruder, cartesian_segment_mm - #if ENABLED(SCARA_FEEDRATE_SCALING) - , inv_duration - #endif - )) break; + if (!planner.buffer_line(raw, fr_mm_s, active_extruder, cartesian_segment_mm OPTARG(SCARA_FEEDRATE_SCALING, inv_duration))) break; } // Since segment_distance is only approximate, // the final move must be to the exact destination. - planner.buffer_line(destination, fr_mm_s, active_extruder, cartesian_segment_mm - #if ENABLED(SCARA_FEEDRATE_SCALING) - , inv_duration - #endif - ); + planner.buffer_line(destination, fr_mm_s, active_extruder, cartesian_segment_mm OPTARG(SCARA_FEEDRATE_SCALING, inv_duration)); } #endif // SEGMENT_LEVELED_MOVES @@ -981,7 +1093,7 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { } #endif // HAS_MESH - planner.buffer_line(destination, scaled_fr_mm_s, active_extruder); + planner.buffer_line(destination, scaled_fr_mm_s); return false; // caller will update current_position } @@ -1063,12 +1175,12 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { // Un-park the active extruder // const feedRate_t fr_zfast = planner.settings.max_feedrate_mm_s[Z_AXIS]; - #define CURPOS current_position - #define RAISED raised_parked_position // 1. Move to the raised parked XYZ. Presumably the tool is already at XY. - if (planner.buffer_line(RAISED.x, RAISED.y, RAISED.z, CURPOS.e, fr_zfast, active_extruder)) { + xyze_pos_t raised = raised_parked_position; raised.e = current_position.e; + if (planner.buffer_line(raised, fr_zfast)) { // 2. Move to the current native XY and raised Z. Presumably this is a null move. - if (planner.buffer_line(CURPOS.x, CURPOS.y, RAISED.z, CURPOS.e, PLANNER_XY_FEEDRATE(), active_extruder)) { + xyze_pos_t curpos = current_position; curpos.z = raised_parked_position.z; + if (planner.buffer_line(curpos, PLANNER_XY_FEEDRATE())) { // 3. Lower Z back down line_to_current_position(fr_zfast); } @@ -1082,21 +1194,24 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) { case DXC_MIRRORED_MODE: case DXC_DUPLICATION_MODE: if (active_extruder == 0) { - xyze_pos_t new_pos = current_position; + // Restore planner to parked head (T1) X position + xyze_pos_t pos_now = current_position; + pos_now.x = inactive_extruder_x; + planner.set_position_mm(pos_now); + + // Keep the same X or add the duplication X offset + xyze_pos_t new_pos = pos_now; if (dual_x_carriage_mode == DXC_DUPLICATION_MODE) new_pos.x += duplicate_extruder_x_offset; - else - new_pos.x = inactive_extruder_x; - // Move duplicate extruder into correct duplication position. + + // Move duplicate extruder into the correct position if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Set planner X", inactive_extruder_x, " ... Line to X", new_pos.x); - planner.set_position_mm(inactive_extruder_x, 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(); - set_duplication_enabled(true); - idex_set_parked(false); + sync_plan_position(); // Extra sync for good measure + set_duplication_enabled(true); // Enable Duplication + idex_set_parked(false); // No longer parked if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("set_duplication_enabled(true)\nidex_set_parked(false)"); } else if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Active extruder not 0"); @@ -1188,9 +1303,11 @@ void prepare_line_to_destination() { if (TEST(b, a) && TERN(HOME_AFTER_DEACTIVATE, axis_is_trusted, axis_was_homed)(a)) CBI(b, a); }; - set_should(axis_bits, X_AXIS); // Clear test bits that are trusted - set_should(axis_bits, Y_AXIS); - set_should(axis_bits, Z_AXIS); + // Clear test bits that are trusted + LINEAR_AXIS_CODE( + set_should(axis_bits, X_AXIS), set_should(axis_bits, Y_AXIS), set_should(axis_bits, Z_AXIS), + set_should(axis_bits, I_AXIS), set_should(axis_bits, J_AXIS), set_should(axis_bits, K_AXIS) + ); return axis_bits; } @@ -1199,9 +1316,14 @@ void prepare_line_to_destination() { PGM_P home_first = GET_TEXT(MSG_HOME_FIRST); char msg[strlen_P(home_first)+1]; sprintf_P(msg, home_first, - TEST(axis_bits, X_AXIS) ? "X" : "", - TEST(axis_bits, Y_AXIS) ? "Y" : "", - TEST(axis_bits, Z_AXIS) ? "Z" : "" + LINEAR_AXIS_LIST( + TEST(axis_bits, X_AXIS) ? "X" : "", + TEST(axis_bits, Y_AXIS) ? "Y" : "", + TEST(axis_bits, Z_AXIS) ? "Z" : "", + TEST(axis_bits, I_AXIS) ? AXIS4_STR : "", + TEST(axis_bits, J_AXIS) ? AXIS5_STR : "", + TEST(axis_bits, K_AXIS) ? AXIS6_STR : "" + ) ); SERIAL_ECHO_START(); SERIAL_ECHOLN(msg); @@ -1286,8 +1408,21 @@ void prepare_line_to_destination() { #if ENABLED(SPI_ENDSTOPS) switch (axis) { case X_AXIS: if (ENABLED(X_SPI_SENSORLESS)) endstops.tmc_spi_homing.x = true; break; - case Y_AXIS: if (ENABLED(Y_SPI_SENSORLESS)) endstops.tmc_spi_homing.y = true; break; - case Z_AXIS: if (ENABLED(Z_SPI_SENSORLESS)) endstops.tmc_spi_homing.z = true; break; + #if HAS_Y_AXIS + case Y_AXIS: if (ENABLED(Y_SPI_SENSORLESS)) endstops.tmc_spi_homing.y = true; break; + #endif + #if HAS_Z_AXIS + case Z_AXIS: if (ENABLED(Z_SPI_SENSORLESS)) endstops.tmc_spi_homing.z = true; break; + #endif + #if LINEAR_AXES >= 4 + case I_AXIS: if (ENABLED(I_SPI_SENSORLESS)) endstops.tmc_spi_homing.i = true; break; + #endif + #if LINEAR_AXES >= 5 + case J_AXIS: if (ENABLED(J_SPI_SENSORLESS)) endstops.tmc_spi_homing.j = true; break; + #endif + #if LINEAR_AXES >= 6 + case K_AXIS: if (ENABLED(K_SPI_SENSORLESS)) endstops.tmc_spi_homing.k = true; break; + #endif default: break; } #endif @@ -1350,8 +1485,21 @@ void prepare_line_to_destination() { #if ENABLED(SPI_ENDSTOPS) switch (axis) { case X_AXIS: if (ENABLED(X_SPI_SENSORLESS)) endstops.tmc_spi_homing.x = false; break; - case Y_AXIS: if (ENABLED(Y_SPI_SENSORLESS)) endstops.tmc_spi_homing.y = false; break; - case Z_AXIS: if (ENABLED(Z_SPI_SENSORLESS)) endstops.tmc_spi_homing.z = false; break; + #if HAS_Y_AXIS + case Y_AXIS: if (ENABLED(Y_SPI_SENSORLESS)) endstops.tmc_spi_homing.y = false; break; + #endif + #if HAS_Z_AXIS + case Z_AXIS: if (ENABLED(Z_SPI_SENSORLESS)) endstops.tmc_spi_homing.z = false; break; + #endif + #if LINEAR_AXES >= 4 + case I_AXIS: if (ENABLED(I_SPI_SENSORLESS)) endstops.tmc_spi_homing.i = false; break; + #endif + #if LINEAR_AXES >= 5 + case J_AXIS: if (ENABLED(J_SPI_SENSORLESS)) endstops.tmc_spi_homing.j = false; break; + #endif + #if LINEAR_AXES >= 6 + case K_AXIS: if (ENABLED(K_SPI_SENSORLESS)) endstops.tmc_spi_homing.k = false; break; + #endif default: break; } #endif @@ -1368,7 +1516,7 @@ void prepare_line_to_destination() { const feedRate_t home_fr_mm_s = fr_mm_s ?: homing_feedrate(axis); if (DEBUGGING(LEVELING)) { - DEBUG_ECHOPAIR("...(", AS_CHAR(axis_codes[axis]), ", ", distance, ", "); + DEBUG_ECHOPAIR("...(", AS_CHAR(AXIS_CHAR(axis)), ", ", distance, ", "); if (fr_mm_s) DEBUG_ECHO(fr_mm_s); else @@ -1424,12 +1572,7 @@ void prepare_line_to_destination() { // Set delta/cartesian axes directly target[axis] = distance; // The move will be towards the endstop - planner.buffer_segment(target - #if HAS_DIST_MM_ARG - , cart_dist_mm - #endif - , home_fr_mm_s, active_extruder - ); + planner.buffer_segment(target OPTARG(HAS_DIST_MM_ARG, cart_dist_mm), home_fr_mm_s, active_extruder); #endif planner.synchronize(); @@ -1453,12 +1596,12 @@ void prepare_line_to_destination() { * "trusted" position). */ void set_axis_never_homed(const AxisEnum axis) { - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(">>> set_axis_never_homed(", AS_CHAR(axis_codes[axis]), ")"); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(">>> set_axis_never_homed(", AS_CHAR(AXIS_CHAR(axis)), ")"); set_axis_untrusted(axis); set_axis_unhomed(axis); - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("<<< set_axis_never_homed(", AS_CHAR(axis_codes[axis]), ")"); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("<<< set_axis_never_homed(", AS_CHAR(AXIS_CHAR(axis)), ")"); TERN_(I2C_POSITION_ENCODERS, I2CPEM.unhomed(axis)); } @@ -1509,6 +1652,30 @@ void prepare_line_to_destination() { stepperBackoutDir = INVERT_Z_DIR ? effectorBackoutDir : -effectorBackoutDir; break; #endif + #ifdef I_MICROSTEPS + case I_AXIS: + phasePerUStep = PHASE_PER_MICROSTEP(I); + phaseCurrent = stepperI.get_microstep_counter(); + effectorBackoutDir = -I_HOME_DIR; + stepperBackoutDir = INVERT_I_DIR ? effectorBackoutDir : -effectorBackoutDir; + break; + #endif + #ifdef J_MICROSTEPS + case J_AXIS: + phasePerUStep = PHASE_PER_MICROSTEP(J); + phaseCurrent = stepperJ.get_microstep_counter(); + effectorBackoutDir = -J_HOME_DIR; + stepperBackoutDir = INVERT_J_DIR ? effectorBackoutDir : -effectorBackoutDir; + break; + #endif + #ifdef K_MICROSTEPS + case K_AXIS: + phasePerUStep = PHASE_PER_MICROSTEP(K); + phaseCurrent = stepperK.get_microstep_counter(); + effectorBackoutDir = -K_HOME_DIR; + stepperBackoutDir = INVERT_K_DIR ? effectorBackoutDir : -effectorBackoutDir; + break; + #endif default: return; } @@ -1519,7 +1686,7 @@ void prepare_line_to_destination() { if (ABS(phaseDelta) * planner.steps_to_mm[axis] / phasePerUStep < 0.05f) SERIAL_ECHOLNPAIR("Selected home phase ", home_phase[axis], " too close to endstop trigger phase ", phaseCurrent, - ". Pick a different phase for ", AS_CHAR(axis_codes[axis])); + ". Pick a different phase for ", AS_CHAR(AXIS_CHAR(axis))); // Skip to next if target position is behind current. So it only moves away from endstop. if (phaseDelta < 0) phaseDelta += 1024; @@ -1530,7 +1697,7 @@ void prepare_line_to_destination() { // Optional debug messages if (DEBUGGING(LEVELING)) { DEBUG_ECHOLNPAIR( - "Endstop ", AS_CHAR(axis_codes[axis]), " hit at Phase:", phaseCurrent, + "Endstop ", AS_CHAR(AXIS_CHAR(axis)), " hit at Phase:", phaseCurrent, " Delta:", phaseDelta, " Distance:", mmDelta ); } @@ -1561,14 +1728,21 @@ void prepare_line_to_destination() { #else #define _CAN_HOME(A) (axis == _AXIS(A) && ( \ ENABLED(A##_SPI_SENSORLESS) \ - || (_AXIS(A) == Z_AXIS && ENABLED(HOMING_Z_WITH_PROBE)) \ + || TERN0(HAS_Z_AXIS, TERN0(HOMING_Z_WITH_PROBE, _AXIS(A) == Z_AXIS)) \ || TERN0(A##_HOME_TO_MIN, A##_MIN_PIN > -1) \ || TERN0(A##_HOME_TO_MAX, A##_MAX_PIN > -1) \ )) - if (!_CAN_HOME(X) && !_CAN_HOME(Y) && !_CAN_HOME(Z)) return; + if (LINEAR_AXIS_GANG( + !_CAN_HOME(X), + && !_CAN_HOME(Y), + && !_CAN_HOME(Z), + && !_CAN_HOME(I), + && !_CAN_HOME(J), + && !_CAN_HOME(K)) + ) return; #endif - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(">>> homeaxis(", AS_CHAR(axis_codes[axis]), ")"); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(">>> homeaxis(", AS_CHAR(AXIS_CHAR(axis)), ")"); const int axis_home_dir = TERN0(DUAL_X_CARRIAGE, axis == X_AXIS) ? TOOL_X_HOME_DIR(active_extruder) : home_dir(axis); @@ -1601,11 +1775,11 @@ void prepare_line_to_destination() { #endif // - // Back away to prevent an early X/Y sensorless trigger + // Back away to prevent an early sensorless trigger // #if DISABLED(DELTA) && defined(SENSORLESS_BACKOFF_MM) - const xy_float_t backoff = SENSORLESS_BACKOFF_MM; - if ((TERN0(X_SENSORLESS, axis == X_AXIS) || TERN0(Y_SENSORLESS, axis == Y_AXIS)) && backoff[axis]) { + const xyz_float_t backoff = SENSORLESS_BACKOFF_MM; + if ((TERN0(X_SENSORLESS, axis == X_AXIS) || TERN0(Y_SENSORLESS, axis == Y_AXIS) || TERN0(Z_SENSORLESS, axis == Z_AXIS) || TERN0(I_SENSORLESS, axis == I_AXIS) || TERN0(J_SENSORLESS, axis == J_AXIS) || TERN0(K_SENSORLESS, axis == K_AXIS)) && backoff[axis]) { const float backoff_length = -ABS(backoff[axis]) * axis_home_dir; if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Sensorless backoff: ", backoff_length, "mm"); do_homing_move(axis, backoff_length, homing_feedrate(axis)); @@ -1614,9 +1788,9 @@ void prepare_line_to_destination() { // Determine if a homing bump will be done and the bumps distance // When homing Z with probe respect probe clearance - const bool use_probe_bump = TERN0(HOMING_Z_WITH_PROBE, axis == Z_AXIS && home_bump_mm(Z_AXIS)); + const bool use_probe_bump = TERN0(HOMING_Z_WITH_PROBE, axis == Z_AXIS && home_bump_mm(axis)); const float bump = axis_home_dir * ( - use_probe_bump ? _MAX(TERN0(HOMING_Z_WITH_PROBE, Z_CLEARANCE_BETWEEN_PROBES), home_bump_mm(Z_AXIS)) : home_bump_mm(axis) + use_probe_bump ? _MAX(TERN0(HOMING_Z_WITH_PROBE, Z_CLEARANCE_BETWEEN_PROBES), home_bump_mm(axis)) : home_bump_mm(axis) ); // @@ -1644,9 +1818,18 @@ void prepare_line_to_destination() { case X_AXIS: es = X_ENDSTOP; break; case Y_AXIS: es = Y_ENDSTOP; break; case Z_AXIS: es = Z_ENDSTOP; break; + #if LINEAR_AXES >= 4 + case I_AXIS: es = I_ENDSTOP; break; + #endif + #if LINEAR_AXES >= 5 + case J_AXIS: es = J_ENDSTOP; break; + #endif + #if LINEAR_AXES >= 6 + case K_AXIS: es = K_ENDSTOP; break; + #endif } if (TEST(endstops.state(), es)) { - SERIAL_ECHO_MSG("Bad ", AS_CHAR(axis_codes[axis]), " Endstop?"); + SERIAL_ECHO_MSG("Bad ", AS_CHAR(AXIS_CHAR(axis)), " Endstop?"); kill(GET_TEXT(MSG_KILL_HOMING_FAILED)); } #endif @@ -1868,7 +2051,7 @@ void prepare_line_to_destination() { if (axis == Z_AXIS) fwretract.current_hop = 0.0; #endif - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("<<< homeaxis(", AS_CHAR(axis_codes[axis]), ")"); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("<<< homeaxis(", AS_CHAR(AXIS_CHAR(axis)), ")"); } // homeaxis() @@ -1893,7 +2076,7 @@ void prepare_line_to_destination() { * Callers must sync the planner position after calling this! */ void set_axis_is_at_home(const AxisEnum axis) { - if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(">>> set_axis_is_at_home(", AS_CHAR(axis_codes[axis]), ")"); + if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(">>> set_axis_is_at_home(", AS_CHAR(AXIS_CHAR(axis)), ")"); set_axis_trusted(axis); set_axis_homed(axis); @@ -1943,10 +2126,10 @@ void set_axis_is_at_home(const AxisEnum axis) { if (DEBUGGING(LEVELING)) { #if HAS_HOME_OFFSET - DEBUG_ECHOLNPAIR("> home_offset[", AS_CHAR(axis_codes[axis]), "] = ", home_offset[axis]); + DEBUG_ECHOLNPAIR("> home_offset[", AS_CHAR(AXIS_CHAR(axis)), "] = ", home_offset[axis]); #endif DEBUG_POS("", current_position); - DEBUG_ECHOLNPAIR("<<< set_axis_is_at_home(", AS_CHAR(axis_codes[axis]), ")"); + DEBUG_ECHOLNPAIR("<<< set_axis_is_at_home(", AS_CHAR(AXIS_CHAR(axis)), ")"); } } diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index a43af6446b2dc..c41738a5ab677 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -44,7 +44,7 @@ extern xyze_pos_t current_position, // High-level current tool position // G60/G61 Position Save and Return #if SAVED_POSITIONS - extern uint8_t saved_slots[(SAVED_POSITIONS + 7) >> 3]; + extern uint8_t saved_slots[(SAVED_POSITIONS + 7) >> 3]; // TODO: Add support for LINEAR_AXES >= 4 extern xyze_pos_t stored_position[SAVED_POSITIONS]; #endif @@ -53,7 +53,7 @@ extern xyz_pos_t cartes; // Until kinematics.cpp is created, declare this here #if IS_KINEMATIC - extern abc_pos_t delta; + extern abce_pos_t delta; #endif #if HAS_ABL_NOT_UBL @@ -75,16 +75,16 @@ extern xyz_pos_t cartes; */ constexpr xyz_feedrate_t homing_feedrate_mm_m = HOMING_FEEDRATE_MM_M; FORCE_INLINE feedRate_t homing_feedrate(const AxisEnum a) { - float v; - #if ENABLED(DELTA) - v = homing_feedrate_mm_m.z; - #else - switch (a) { - case X_AXIS: v = homing_feedrate_mm_m.x; break; - case Y_AXIS: v = homing_feedrate_mm_m.y; break; - case Z_AXIS: - default: v = homing_feedrate_mm_m.z; - } + float v = TERN0(HAS_Z_AXIS, homing_feedrate_mm_m.z); + #if DISABLED(DELTA) + LINEAR_AXIS_CODE( + if (a == X_AXIS) v = homing_feedrate_mm_m.x, + else if (a == Y_AXIS) v = homing_feedrate_mm_m.y, + else if (a == Z_AXIS) v = homing_feedrate_mm_m.z, + else if (a == I_AXIS) v = homing_feedrate_mm_m.i, + else if (a == J_AXIS) v = homing_feedrate_mm_m.j, + else if (a == K_AXIS) v = homing_feedrate_mm_m.k + ); #endif return MMM_TO_MMS(v); } @@ -124,7 +124,7 @@ inline int8_t pgm_read_any(const int8_t *p) { return TERN(__IMXRT1062__, *p, pgm #define XYZ_DEFS(T, NAME, OPT) \ inline T NAME(const AxisEnum axis) { \ - static const XYZval NAME##_P DEFS_PROGMEM = { X_##OPT, Y_##OPT, Z_##OPT }; \ + static const XYZval NAME##_P DEFS_PROGMEM = LINEAR_AXIS_ARRAY(X_##OPT, Y_##OPT, Z_##OPT, I_##OPT, J_##OPT, K_##OPT); \ return pgm_read_any(&NAME##_P[axis]); \ } XYZ_DEFS(float, base_min_pos, MIN_POS); @@ -168,13 +168,36 @@ inline float home_bump_mm(const AxisEnum axis) { TERN_(MIN_SOFTWARE_ENDSTOP_X, amin = min.x); TERN_(MAX_SOFTWARE_ENDSTOP_X, amax = max.x); break; - case Y_AXIS: - TERN_(MIN_SOFTWARE_ENDSTOP_Y, amin = min.y); - TERN_(MAX_SOFTWARE_ENDSTOP_Y, amax = max.y); - break; - case Z_AXIS: - TERN_(MIN_SOFTWARE_ENDSTOP_Z, amin = min.z); - TERN_(MAX_SOFTWARE_ENDSTOP_Z, amax = max.z); + #if HAS_Y_AXIS + case Y_AXIS: + TERN_(MIN_SOFTWARE_ENDSTOP_Y, amin = min.y); + TERN_(MAX_SOFTWARE_ENDSTOP_Y, amax = max.y); + break; + #endif + #if HAS_Z_AXIS + case Z_AXIS: + TERN_(MIN_SOFTWARE_ENDSTOP_Z, amin = min.z); + TERN_(MAX_SOFTWARE_ENDSTOP_Z, amax = max.z); + break; + #endif + #if LINEAR_AXES >= 4 + case I_AXIS: + TERN_(MIN_SOFTWARE_ENDSTOP_I, amin = min.i); + TERN_(MIN_SOFTWARE_ENDSTOP_I, amax = max.i); + break; + #endif + #if LINEAR_AXES >= 5 + case J_AXIS: + TERN_(MIN_SOFTWARE_ENDSTOP_J, amin = min.j); + TERN_(MIN_SOFTWARE_ENDSTOP_J, amax = max.j); + break; + #endif + #if LINEAR_AXES >= 6 + case K_AXIS: + TERN_(MIN_SOFTWARE_ENDSTOP_K, amin = min.k); + TERN_(MIN_SOFTWARE_ENDSTOP_K, amax = max.k); + break; + #endif default: break; } #endif @@ -264,7 +287,10 @@ void quickstop_stepper(); * no kinematic translation. Used for homing axes and cartesian/core syncing. */ void sync_plan_position(); -void sync_plan_position_e(); + +#if HAS_EXTRUDERS + void sync_plan_position_e(); +#endif /** * Move the planner to the current position from wherever it last moved @@ -278,11 +304,7 @@ void line_to_current_position(const_feedRate_t fr_mm_s=feedrate_mm_s); void prepare_line_to_destination(); -void _internal_move_to_destination(const_feedRate_t fr_mm_s=0.0f - #if IS_KINEMATIC - , const bool is_fast=false - #endif -); +void _internal_move_to_destination(const_feedRate_t fr_mm_s=0.0f OPTARG(IS_KINEMATIC, const bool is_fast=false)); inline void prepare_internal_move_to_destination(const_feedRate_t fr_mm_s=0.0f) { _internal_move_to_destination(fr_mm_s); @@ -299,34 +321,58 @@ inline void prepare_internal_move_to_destination(const_feedRate_t fr_mm_s=0.0f) /** * Blocking movement and shorthand functions */ -void do_blocking_move_to(const float rx, const float ry, const float rz, const_feedRate_t fr_mm_s=0.0f); +void do_blocking_move_to(LINEAR_AXIS_ARGS(const float), const_feedRate_t fr_mm_s=0.0f); void do_blocking_move_to(const xy_pos_t &raw, const_feedRate_t fr_mm_s=0.0f); void do_blocking_move_to(const xyz_pos_t &raw, const_feedRate_t fr_mm_s=0.0f); void do_blocking_move_to(const xyze_pos_t &raw, const_feedRate_t fr_mm_s=0.0f); void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s=0.0f); -void do_blocking_move_to_y(const_float_t ry, const_feedRate_t fr_mm_s=0.0f); -void do_blocking_move_to_z(const_float_t rz, const_feedRate_t fr_mm_s=0.0f); +#if HAS_Y_AXIS + void do_blocking_move_to_y(const_float_t ry, const_feedRate_t fr_mm_s=0.0f); +#endif +#if HAS_Z_AXIS + void do_blocking_move_to_z(const_float_t rz, const_feedRate_t fr_mm_s=0.0f); +#endif +#if LINEAR_AXES >= 4 + void do_blocking_move_to_i(const_float_t ri, const_feedRate_t fr_mm_s=0.0f); + void do_blocking_move_to_xyz_i(const xyze_pos_t &raw, const_float_t i, const_feedRate_t fr_mm_s=0.0f); +#endif +#if LINEAR_AXES >= 5 + void do_blocking_move_to_j(const_float_t rj, const_feedRate_t fr_mm_s=0.0f); + void do_blocking_move_to_xyzi_j(const xyze_pos_t &raw, const_float_t j, const_feedRate_t fr_mm_s=0.0f); +#endif +#if LINEAR_AXES >= 6 + void do_blocking_move_to_k(const_float_t rk, const_feedRate_t fr_mm_s=0.0f); + void do_blocking_move_to_xyzij_k(const xyze_pos_t &raw, const_float_t k, const_feedRate_t fr_mm_s=0.0f); +#endif -void do_blocking_move_to_xy(const_float_t rx, const_float_t ry, const_feedRate_t fr_mm_s=0.0f); -void do_blocking_move_to_xy(const xy_pos_t &raw, const_feedRate_t fr_mm_s=0.0f); -FORCE_INLINE void do_blocking_move_to_xy(const xyz_pos_t &raw, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy(xy_pos_t(raw), fr_mm_s); } -FORCE_INLINE void do_blocking_move_to_xy(const xyze_pos_t &raw, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy(xy_pos_t(raw), fr_mm_s); } +#if HAS_Y_AXIS + void do_blocking_move_to_xy(const_float_t rx, const_float_t ry, const_feedRate_t fr_mm_s=0.0f); + void do_blocking_move_to_xy(const xy_pos_t &raw, const_feedRate_t fr_mm_s=0.0f); + FORCE_INLINE void do_blocking_move_to_xy(const xyz_pos_t &raw, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy(xy_pos_t(raw), fr_mm_s); } + FORCE_INLINE void do_blocking_move_to_xy(const xyze_pos_t &raw, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy(xy_pos_t(raw), fr_mm_s); } +#endif -void do_blocking_move_to_xy_z(const xy_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s=0.0f); -FORCE_INLINE void do_blocking_move_to_xy_z(const xyz_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy_z(xy_pos_t(raw), z, fr_mm_s); } -FORCE_INLINE void do_blocking_move_to_xy_z(const xyze_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy_z(xy_pos_t(raw), z, fr_mm_s); } +#if HAS_Z_AXIS + void do_blocking_move_to_xy_z(const xy_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s=0.0f); + FORCE_INLINE void do_blocking_move_to_xy_z(const xyz_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy_z(xy_pos_t(raw), z, fr_mm_s); } + FORCE_INLINE void do_blocking_move_to_xy_z(const xyze_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy_z(xy_pos_t(raw), z, fr_mm_s); } +#endif void remember_feedrate_and_scaling(); void remember_feedrate_scaling_off(); void restore_feedrate_and_scaling(); -void do_z_clearance(const_float_t zclear, const bool lower_allowed=false); +#if HAS_Z_AXIS + void do_z_clearance(const_float_t zclear, const bool lower_allowed=false); +#else + inline void do_z_clearance(float, bool=false) {} +#endif /** * Homing and Trusted Axes */ -typedef IF<(LINEAR_AXES>8), uint16_t, uint8_t>::type linear_axis_bits_t; +typedef IF<(LINEAR_AXES > 8), uint16_t, uint8_t>::type linear_axis_bits_t; constexpr linear_axis_bits_t linear_bits = _BV(LINEAR_AXES) - 1; void set_axis_is_at_home(const AxisEnum axis); @@ -346,33 +392,35 @@ void set_axis_is_at_home(const AxisEnum axis); void set_axis_never_homed(const AxisEnum axis); linear_axis_bits_t axes_should_home(linear_axis_bits_t axis_bits=linear_bits); bool homing_needed_error(linear_axis_bits_t axis_bits=linear_bits); - FORCE_INLINE void set_axis_unhomed(const AxisEnum axis) { CBI(axis_homed, axis); } - FORCE_INLINE void set_axis_untrusted(const AxisEnum axis) { CBI(axis_trusted, axis); } - FORCE_INLINE void set_all_unhomed() { axis_homed = axis_trusted = 0; } - FORCE_INLINE void set_axis_homed(const AxisEnum axis) { SBI(axis_homed, axis); } - FORCE_INLINE void set_axis_trusted(const AxisEnum axis) { SBI(axis_trusted, axis); } - FORCE_INLINE void set_all_homed() { axis_homed = axis_trusted = linear_bits; } + inline void set_axis_unhomed(const AxisEnum axis) { CBI(axis_homed, axis); } + inline void set_axis_untrusted(const AxisEnum axis) { CBI(axis_trusted, axis); } + inline void set_all_unhomed() { axis_homed = axis_trusted = 0; } + inline void set_axis_homed(const AxisEnum axis) { SBI(axis_homed, axis); } + inline void set_axis_trusted(const AxisEnum axis) { SBI(axis_trusted, axis); } + inline void set_all_homed() { axis_homed = axis_trusted = linear_bits; } #else constexpr linear_axis_bits_t axis_homed = linear_bits, axis_trusted = linear_bits; // Zero-endstop machines are always homed and trusted - FORCE_INLINE void homeaxis(const AxisEnum axis) {} - FORCE_INLINE void set_axis_never_homed(const AxisEnum) {} - FORCE_INLINE linear_axis_bits_t axes_should_home(linear_axis_bits_t=linear_bits) { return false; } - FORCE_INLINE bool homing_needed_error(linear_axis_bits_t=linear_bits) { return false; } - FORCE_INLINE void set_axis_unhomed(const AxisEnum axis) {} - FORCE_INLINE void set_axis_untrusted(const AxisEnum axis) {} - FORCE_INLINE void set_all_unhomed() {} - FORCE_INLINE void set_axis_homed(const AxisEnum axis) {} - FORCE_INLINE void set_axis_trusted(const AxisEnum axis) {} - FORCE_INLINE void set_all_homed() {} -#endif - -FORCE_INLINE bool axis_was_homed(const AxisEnum axis) { return TEST(axis_homed, axis); } -FORCE_INLINE bool axis_is_trusted(const AxisEnum axis) { return TEST(axis_trusted, axis); } -FORCE_INLINE bool axis_should_home(const AxisEnum axis) { return (axes_should_home() & _BV(axis)) != 0; } -FORCE_INLINE bool no_axes_homed() { return !axis_homed; } -FORCE_INLINE bool all_axes_homed() { return linear_bits == (axis_homed & linear_bits); } -FORCE_INLINE bool homing_needed() { return !all_axes_homed(); } -FORCE_INLINE bool all_axes_trusted() { return linear_bits == (axis_trusted & linear_bits); } + inline void homeaxis(const AxisEnum axis) {} + inline void set_axis_never_homed(const AxisEnum) {} + inline linear_axis_bits_t axes_should_home(linear_axis_bits_t=linear_bits) { return false; } + inline bool homing_needed_error(linear_axis_bits_t=linear_bits) { return false; } + inline void set_axis_unhomed(const AxisEnum axis) {} + inline void set_axis_untrusted(const AxisEnum axis) {} + inline void set_all_unhomed() {} + inline void set_axis_homed(const AxisEnum axis) {} + inline void set_axis_trusted(const AxisEnum axis) {} + inline void set_all_homed() {} +#endif + +inline bool axis_was_homed(const AxisEnum axis) { return TEST(axis_homed, axis); } +inline bool axis_is_trusted(const AxisEnum axis) { return TEST(axis_trusted, axis); } +inline bool axis_should_home(const AxisEnum axis) { return (axes_should_home() & _BV(axis)) != 0; } +inline bool no_axes_homed() { return !axis_homed; } +inline bool all_axes_homed() { return linear_bits == (axis_homed & linear_bits); } +inline bool homing_needed() { return !all_axes_homed(); } +inline bool all_axes_trusted() { return linear_bits == (axis_trusted & linear_bits); } + +void home_if_needed(const bool keeplev=false); #if ENABLED(NO_MOTION_BEFORE_HOMING) #define MOTION_CONDITIONS (IsRunning() && !homing_needed_error()) @@ -419,11 +467,27 @@ FORCE_INLINE bool all_axes_trusted() { return linear_bits FORCE_INLINE void toNative(xyze_pos_t&) {} #endif #define LOGICAL_X_POSITION(POS) NATIVE_TO_LOGICAL(POS, X_AXIS) -#define LOGICAL_Y_POSITION(POS) NATIVE_TO_LOGICAL(POS, Y_AXIS) -#define LOGICAL_Z_POSITION(POS) NATIVE_TO_LOGICAL(POS, Z_AXIS) #define RAW_X_POSITION(POS) LOGICAL_TO_NATIVE(POS, X_AXIS) -#define RAW_Y_POSITION(POS) LOGICAL_TO_NATIVE(POS, Y_AXIS) -#define RAW_Z_POSITION(POS) LOGICAL_TO_NATIVE(POS, Z_AXIS) +#if HAS_Y_AXIS + #define LOGICAL_Y_POSITION(POS) NATIVE_TO_LOGICAL(POS, Y_AXIS) + #define RAW_Y_POSITION(POS) LOGICAL_TO_NATIVE(POS, Y_AXIS) +#endif +#if HAS_Z_AXIS + #define LOGICAL_Z_POSITION(POS) NATIVE_TO_LOGICAL(POS, Z_AXIS) + #define RAW_Z_POSITION(POS) LOGICAL_TO_NATIVE(POS, Z_AXIS) +#endif +#if LINEAR_AXES >= 4 + #define LOGICAL_I_POSITION(POS) NATIVE_TO_LOGICAL(POS, I_AXIS) + #define RAW_I_POSITION(POS) LOGICAL_TO_NATIVE(POS, I_AXIS) +#endif +#if LINEAR_AXES >= 5 + #define LOGICAL_J_POSITION(POS) NATIVE_TO_LOGICAL(POS, J_AXIS) + #define RAW_J_POSITION(POS) LOGICAL_TO_NATIVE(POS, J_AXIS) +#endif +#if LINEAR_AXES >= 6 + #define LOGICAL_K_POSITION(POS) NATIVE_TO_LOGICAL(POS, K_AXIS) + #define RAW_K_POSITION(POS) LOGICAL_TO_NATIVE(POS, K_AXIS) +#endif /** * position_is_reachable family of functions diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 714be8019e206..49b2d60b20b8f 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -213,7 +213,7 @@ xyze_float_t Planner::previous_speed; float Planner::previous_nominal_speed_sqr; #if ENABLED(DISABLE_INACTIVE_EXTRUDER) - last_move_t Planner::g_uc_extruder_last_move[EXTRUDERS] = { 0 }; + last_move_t Planner::g_uc_extruder_last_move[E_STEPPERS] = { 0 }; #endif #ifdef XY_FREQUENCY_LIMIT @@ -1310,7 +1310,7 @@ void Planner::recalculate() { */ void Planner::check_axes_activity() { - #if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z, DISABLE_E) + #if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z , DISABLE_I , DISABLE_J , DISABLE_K, DISABLE_E) xyze_bool_t axis_active = { false }; #endif @@ -1342,13 +1342,18 @@ void Planner::check_axes_activity() { TERN_(HAS_HEATER_2, tail_e_to_p_pressure = block->e_to_p_pressure); #endif - #if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z, DISABLE_E) + #if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z, DISABLE_I, DISABLE_J, DISABLE_K, DISABLE_E) for (uint8_t b = block_buffer_tail; b != block_buffer_head; b = next_block_index(b)) { block_t *block = &block_buffer[b]; - if (ENABLED(DISABLE_X) && block->steps.x) axis_active.x = true; - if (ENABLED(DISABLE_Y) && block->steps.y) axis_active.y = true; - if (ENABLED(DISABLE_Z) && block->steps.z) axis_active.z = true; - if (ENABLED(DISABLE_E) && block->steps.e) axis_active.e = true; + LOGICAL_AXIS_CODE( + if (TERN0(DISABLE_E, block->steps.e)) axis_active.e = true, + if (TERN0(DISABLE_X, block->steps.x)) axis_active.x = true, + if (TERN0(DISABLE_Y, block->steps.y)) axis_active.y = true, + if (TERN0(DISABLE_Z, block->steps.z)) axis_active.z = true, + if (TERN0(DISABLE_I, block->steps.i)) axis_active.i = true, + if (TERN0(DISABLE_J, block->steps.j)) axis_active.j = true, + if (TERN0(DISABLE_K, block->steps.k)) axis_active.k = true + ); } #endif } @@ -1369,10 +1374,15 @@ void Planner::check_axes_activity() { // // Disable inactive axes // - if (TERN0(DISABLE_X, !axis_active.x)) DISABLE_AXIS_X(); - if (TERN0(DISABLE_Y, !axis_active.y)) DISABLE_AXIS_Y(); - if (TERN0(DISABLE_Z, !axis_active.z)) DISABLE_AXIS_Z(); - if (TERN0(DISABLE_E, !axis_active.e)) disable_e_steppers(); + LOGICAL_AXIS_CODE( + if (TERN0(DISABLE_E, !axis_active.e)) disable_e_steppers(), + if (TERN0(DISABLE_X, !axis_active.x)) DISABLE_AXIS_X(), + if (TERN0(DISABLE_Y, !axis_active.y)) DISABLE_AXIS_Y(), + if (TERN0(DISABLE_Z, !axis_active.z)) DISABLE_AXIS_Z(), + if (TERN0(DISABLE_I, !axis_active.i)) DISABLE_AXIS_I(), + if (TERN0(DISABLE_J, !axis_active.j)) DISABLE_AXIS_J(), + if (TERN0(DISABLE_K, !axis_active.k)) DISABLE_AXIS_K() + ); // // Update Fan speeds @@ -1441,7 +1451,7 @@ void Planner::check_axes_activity() { 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 || block->steps.y || block->steps.z) { + if (LINEAR_AXIS_GANG(block->steps.x, || block->steps.y, || block->steps.z, || block->steps.i, || block->steps.j, || block->steps.k)) { const float se = (float)block->steps.e / block->step_event_count * SQRT(block->nominal_speed_sqr); // mm/sec; NOLESS(high, se); } @@ -1757,12 +1767,8 @@ void Planner::synchronize() { * Returns true if movement was properly queued, false otherwise (if cleaning) */ bool Planner::_buffer_steps(const xyze_long_t &target - #if HAS_POSITION_FLOAT - , const xyze_pos_t &target_float - #endif - #if HAS_DIST_MM_ARG - , const xyze_float_t &cart_dist_mm - #endif + OPTARG(HAS_POSITION_FLOAT, const xyze_pos_t &target_float) + OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm) , feedRate_t fr_mm_s, const uint8_t extruder, const_float_t millimeters ) { @@ -1823,24 +1829,19 @@ bool Planner::_buffer_steps(const xyze_long_t &target */ bool Planner::_populate_block(block_t * const block, bool split_move, const abce_long_t &target - #if HAS_POSITION_FLOAT - , const xyze_pos_t &target_float - #endif - #if HAS_DIST_MM_ARG - , const xyze_float_t &cart_dist_mm - #endif + OPTARG(HAS_POSITION_FLOAT, const xyze_pos_t &target_float) + OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm) , feedRate_t fr_mm_s, const uint8_t extruder, const_float_t millimeters/*=0.0*/ ) { - - const int32_t da = target.a - position.a, - db = target.b - position.b, - dc = target.c - position.c; - - #if HAS_EXTRUDERS - int32_t de = target.e - position.e; - #else - constexpr int32_t de = 0; - #endif + int32_t LOGICAL_AXIS_LIST( + de = target.e - position.e, + da = target.a - position.a, + db = target.b - position.b, + dc = target.c - position.c, + di = target.i - position.i, + dj = target.j - position.j, + dk = target.k - position.k + ); /* <-- add a slash to enable SERIAL_ECHOLNPAIR( @@ -1891,35 +1892,42 @@ bool Planner::_populate_block(block_t * const block, bool split_move, // Compute direction bit-mask for this block uint8_t dm = 0; #if CORE_IS_XY - if (da < 0) SBI(dm, X_HEAD); // Save the real Extruder (head) direction in X Axis + if (da < 0) SBI(dm, X_HEAD); // Save the toolhead's true direction in X if (db < 0) SBI(dm, Y_HEAD); // ...and Y if (dc < 0) SBI(dm, Z_AXIS); if (da + db < 0) SBI(dm, A_AXIS); // Motor A direction if (CORESIGN(da - db) < 0) SBI(dm, B_AXIS); // Motor B direction #elif CORE_IS_XZ - if (da < 0) SBI(dm, X_HEAD); // Save the real Extruder (head) direction in X Axis + if (da < 0) SBI(dm, X_HEAD); // Save the toolhead's true direction in X if (db < 0) SBI(dm, Y_AXIS); if (dc < 0) SBI(dm, Z_HEAD); // ...and Z if (da + dc < 0) SBI(dm, A_AXIS); // Motor A direction if (CORESIGN(da - dc) < 0) SBI(dm, C_AXIS); // Motor C direction #elif CORE_IS_YZ if (da < 0) SBI(dm, X_AXIS); - if (db < 0) SBI(dm, Y_HEAD); // Save the real Extruder (head) direction in Y Axis + if (db < 0) SBI(dm, Y_HEAD); // Save the toolhead's true direction in Y if (dc < 0) SBI(dm, Z_HEAD); // ...and Z if (db + dc < 0) SBI(dm, B_AXIS); // Motor B direction if (CORESIGN(db - dc) < 0) SBI(dm, C_AXIS); // Motor C direction #elif ENABLED(MARKFORGED_XY) - if (da < 0) SBI(dm, X_HEAD); // Save the real Extruder (head) direction in X Axis + if (da < 0) SBI(dm, X_HEAD); // Save the toolhead's true direction in X if (db < 0) SBI(dm, Y_HEAD); // ...and Y if (dc < 0) SBI(dm, Z_AXIS); if (da + db < 0) SBI(dm, A_AXIS); // Motor A direction if (db < 0) SBI(dm, B_AXIS); // Motor B direction #else - if (da < 0) SBI(dm, X_AXIS); - if (db < 0) SBI(dm, Y_AXIS); - if (dc < 0) SBI(dm, Z_AXIS); + LINEAR_AXIS_CODE( + if (da < 0) SBI(dm, X_AXIS), + if (db < 0) SBI(dm, Y_AXIS), + if (dc < 0) SBI(dm, Z_AXIS), + if (di < 0) SBI(dm, I_AXIS), + if (dj < 0) SBI(dm, J_AXIS), + if (dk < 0) SBI(dm, K_AXIS) + ); + #endif + #if HAS_EXTRUDERS + if (de < 0) SBI(dm, E_AXIS); #endif - if (de < 0) SBI(dm, E_AXIS); #if HAS_EXTRUDERS const float esteps_float = de * e_factor[extruder]; @@ -1955,7 +1963,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, block->steps.set(ABS(da), ABS(db), ABS(dc)); #else // default non-h-bot planning - block->steps.set(ABS(da), ABS(db), ABS(dc)); + block->steps.set(LINEAR_AXIS_LIST(ABS(da), ABS(db), ABS(dc), ABS(di), ABS(dj), ABS(dk))); #endif /** @@ -1998,41 +2006,68 @@ bool Planner::_populate_block(block_t * const block, bool split_move, steps_dist_mm.a = (da - db) * steps_to_mm[A_AXIS]; steps_dist_mm.b = db * steps_to_mm[B_AXIS]; #else - steps_dist_mm.a = da * steps_to_mm[A_AXIS]; - steps_dist_mm.b = db * steps_to_mm[B_AXIS]; - steps_dist_mm.c = dc * steps_to_mm[C_AXIS]; + LINEAR_AXIS_CODE( + steps_dist_mm.a = da * steps_to_mm[A_AXIS], + steps_dist_mm.b = db * steps_to_mm[B_AXIS], + steps_dist_mm.c = dc * steps_to_mm[C_AXIS], + steps_dist_mm.i = di * steps_to_mm[I_AXIS], + steps_dist_mm.j = dj * steps_to_mm[J_AXIS], + steps_dist_mm.k = dk * steps_to_mm[K_AXIS] + ); #endif #if HAS_EXTRUDERS steps_dist_mm.e = esteps_float * steps_to_mm[E_AXIS_N(extruder)]; - #else - steps_dist_mm.e = 0.0f; #endif TERN_(LCD_SHOW_E_TOTAL, e_move_accumulator += steps_dist_mm.e); - 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 HAS_EXTRUDERS - + ABS(steps_dist_mm.e) - #endif - ); + if (true LINEAR_AXIS_GANG( + && block->steps.a < MIN_STEPS_PER_SEGMENT, + && block->steps.b < MIN_STEPS_PER_SEGMENT, + && block->steps.c < MIN_STEPS_PER_SEGMENT, + && block->steps.i < MIN_STEPS_PER_SEGMENT, + && block->steps.j < MIN_STEPS_PER_SEGMENT, + && block->steps.k < MIN_STEPS_PER_SEGMENT + ) + ) { + block->millimeters = TERN0(HAS_EXTRUDERS, ABS(steps_dist_mm.e)); } else { if (millimeters) block->millimeters = millimeters; - else + else { block->millimeters = SQRT( #if EITHER(CORE_IS_XY, MARKFORGED_XY) - sq(steps_dist_mm.head.x) + sq(steps_dist_mm.head.y) + sq(steps_dist_mm.z) + LINEAR_AXIS_GANG( + sq(steps_dist_mm.head.x), + sq(steps_dist_mm.head.y), + sq(steps_dist_mm.z), + + sq(steps_dist_mm.i), + sq(steps_dist_mm.j), + sq(steps_dist_mm.k) + ) #elif CORE_IS_XZ - sq(steps_dist_mm.head.x) + sq(steps_dist_mm.y) + sq(steps_dist_mm.head.z) + LINEAR_AXIS_GANG( + sq(steps_dist_mm.head.x), + sq(steps_dist_mm.y), + sq(steps_dist_mm.head.z), + + sq(steps_dist_mm.i), + sq(steps_dist_mm.j), + sq(steps_dist_mm.k) + ) #elif CORE_IS_YZ - sq(steps_dist_mm.x) + sq(steps_dist_mm.head.y) + sq(steps_dist_mm.head.z) + LINEAR_AXIS_GANG( + sq(steps_dist_mm.x) + sq(steps_dist_mm.head.y) + sq(steps_dist_mm.head.z) + + sq(steps_dist_mm.i), + sq(steps_dist_mm.j), + sq(steps_dist_mm.k) + ) + #elif ENABLED(FOAMCUTTER_XYUV) + // Return the largest distance move from either X/Y or I/J plane + #if LINEAR_AXES >= 5 + _MAX(sq(steps_dist_mm.x) + sq(steps_dist_mm.y), sq(steps_dist_mm.i) + sq(steps_dist_mm.j)) + #else + sq(steps_dist_mm.x) + sq(steps_dist_mm.y) + #endif #else - sq(steps_dist_mm.x) + sq(steps_dist_mm.y) + sq(steps_dist_mm.z) + LINEAR_AXIS_GANG( + sq(steps_dist_mm.x), + sq(steps_dist_mm.y), + sq(steps_dist_mm.z), + + sq(steps_dist_mm.i), + sq(steps_dist_mm.j), + sq(steps_dist_mm.k) + ) #endif ); + } /** * At this point at least one of the axes has more steps than @@ -2046,11 +2081,11 @@ bool Planner::_populate_block(block_t * const block, bool split_move, TERN_(BACKLASH_COMPENSATION, backlash.add_correction_steps(da, db, dc, dm, block)); } - #if HAS_EXTRUDERS - block->steps.e = esteps; - #endif + TERN_(HAS_EXTRUDERS, block->steps.e = esteps); - block->step_event_count = _MAX(block->steps.a, block->steps.b, block->steps.c, esteps); + block->step_event_count = _MAX(LOGICAL_AXIS_LIST( + esteps, block->steps.a, block->steps.b, block->steps.c, block->steps.i, block->steps.j, block->steps.k + )); // Bail if this is a zero-length block if (block->step_event_count < MIN_STEPS_PER_SEGMENT) return false; @@ -2073,8 +2108,14 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #endif #if ENABLED(AUTO_POWER_CONTROL) - if (block->steps.x || block->steps.y || block->steps.z) - powerManager.power_on(); + if (LINEAR_AXIS_GANG( + block->steps.x, + || block->steps.y, + || block->steps.z, + || block->steps.i, + || block->steps.j, + || block->steps.k + )) powerManager.power_on(); #endif // Enable active axes @@ -2099,11 +2140,14 @@ bool Planner::_populate_block(block_t * const block, bool split_move, } if (block->steps.x) ENABLE_AXIS_X(); #else - if (block->steps.x) ENABLE_AXIS_X(); - if (block->steps.y) ENABLE_AXIS_Y(); - #if DISABLED(Z_LATE_ENABLE) - if (block->steps.z) ENABLE_AXIS_Z(); - #endif + LINEAR_AXIS_CODE( + if (block->steps.x) ENABLE_AXIS_X(), + if (block->steps.y) ENABLE_AXIS_Y(), + if (TERN(Z_LATE_ENABLE, 0, block->steps.z)) ENABLE_AXIS_Z(), + if (block->steps.i) ENABLE_AXIS_I(), + if (block->steps.j) ENABLE_AXIS_J(), + if (block->steps.k) ENABLE_AXIS_K() + ); #endif // Enable extruder(s) @@ -2113,11 +2157,13 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #if ENABLED(DISABLE_INACTIVE_EXTRUDER) // Enable only the selected extruder - LOOP_L_N(i, EXTRUDERS) + LOOP_L_N(i, E_STEPPERS) if (g_uc_extruder_last_move[i]) g_uc_extruder_last_move[i]--; + #define E_STEPPER_INDEX(E) TERN(SWITCHING_EXTRUDER, (E) / 2, E) + #define ENABLE_ONE_E(N) do{ \ - if (extruder == N) { \ + if (E_STEPPER_INDEX(extruder) == N) { \ ENABLE_AXIS_E##N(); \ g_uc_extruder_last_move[N] = (BLOCK_BUFFER_SIZE) * 2; \ if ((N) == 0 && TERN0(HAS_DUPLICATION_MODE, extruder_duplication_enabled)) \ @@ -2136,7 +2182,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #endif - REPEAT(EXTRUDERS, ENABLE_ONE_E); // (ENABLE_ONE_E must end with semicolon) + REPEAT(E_STEPPERS, ENABLE_ONE_E); // (ENABLE_ONE_E must end with semicolon) } #endif // EXTRUDERS @@ -2289,7 +2335,10 @@ 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 && !block->steps.b && !block->steps.c) { // Is this a retract / recover move? + if (LINEAR_AXIS_GANG( + !block->steps.a, && !block->steps.b, && !block->steps.c, + && !block->steps.i, && !block->steps.j, && !block->steps.k) + ) { // Is this a retract / recover move? accel = CEIL(settings.retract_acceleration * steps_per_mm); // Convert to: acceleration steps/sec^2 TERN_(LIN_ADVANCE, block->use_advance_lead = false); // No linear advance for simple retract/recover } @@ -2354,16 +2403,26 @@ bool Planner::_populate_block(block_t * const block, bool split_move, // Limit acceleration per axis if (block->step_event_count <= acceleration_long_cutoff) { - LIMIT_ACCEL_LONG(A_AXIS, 0); - LIMIT_ACCEL_LONG(B_AXIS, 0); - LIMIT_ACCEL_LONG(C_AXIS, 0); - LIMIT_ACCEL_LONG(E_AXIS, E_INDEX_N(extruder)); + LOGICAL_AXIS_CODE( + LIMIT_ACCEL_LONG(E_AXIS, E_INDEX_N(extruder)), + LIMIT_ACCEL_LONG(A_AXIS, 0), + LIMIT_ACCEL_LONG(B_AXIS, 0), + LIMIT_ACCEL_LONG(C_AXIS, 0), + LIMIT_ACCEL_LONG(I_AXIS, 0), + LIMIT_ACCEL_LONG(J_AXIS, 0), + LIMIT_ACCEL_LONG(K_AXIS, 0) + ); } else { - LIMIT_ACCEL_FLOAT(A_AXIS, 0); - LIMIT_ACCEL_FLOAT(B_AXIS, 0); - LIMIT_ACCEL_FLOAT(C_AXIS, 0); - LIMIT_ACCEL_FLOAT(E_AXIS, E_INDEX_N(extruder)); + LOGICAL_AXIS_CODE( + LIMIT_ACCEL_FLOAT(E_AXIS, E_INDEX_N(extruder)), + LIMIT_ACCEL_FLOAT(A_AXIS, 0), + LIMIT_ACCEL_FLOAT(B_AXIS, 0), + LIMIT_ACCEL_FLOAT(C_AXIS, 0), + LIMIT_ACCEL_FLOAT(I_AXIS, 0), + LIMIT_ACCEL_FLOAT(J_AXIS, 0), + LIMIT_ACCEL_FLOAT(K_AXIS, 0) + ); } } block->acceleration_steps_per_s2 = accel; @@ -2427,7 +2486,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move, #if HAS_DIST_MM_ARG cart_dist_mm #else - { steps_dist_mm.x, steps_dist_mm.y, steps_dist_mm.z, steps_dist_mm.e } + LOGICAL_AXIS_ARRAY(steps_dist_mm.e, steps_dist_mm.x, steps_dist_mm.y, steps_dist_mm.z, steps_dist_mm.i, steps_dist_mm.j, steps_dist_mm.k) #endif ; @@ -2446,8 +2505,15 @@ 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 = (-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); + float junction_cos_theta = LOGICAL_AXIS_GANG( + + (-prev_unit_vec.e * unit_vec.e), + (-prev_unit_vec.x * unit_vec.x), + + (-prev_unit_vec.y * unit_vec.y), + + (-prev_unit_vec.z * unit_vec.z), + + (-prev_unit_vec.i * unit_vec.i), + + (-prev_unit_vec.j * unit_vec.j), + + (-prev_unit_vec.k * unit_vec.k) + ); // NOTE: Computed without any expensive trig, sin() or acos(), by trig half angle identity of cos(theta). if (junction_cos_theta > 0.999999f) { @@ -2762,11 +2828,9 @@ void Planner::buffer_sync_block(TERN_(LASER_SYNCHRONOUS_M106_M107, uint8_t sync_ * * Return 'false' if no segment was queued due to cleaning, cold extrusion, full queue, etc. */ -bool Planner::buffer_segment(const_float_t a, const_float_t b, const_float_t c, const_float_t e - #if HAS_DIST_MM_ARG - , const xyze_float_t &cart_dist_mm - #endif - , const_feedRate_t fr_mm_s, const uint8_t extruder, const_float_t millimeters/*=0.0*/ +bool Planner::buffer_segment(const abce_pos_t &abce + OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm) + , const_feedRate_t fr_mm_s, const uint8_t extruder/*=active_extruder*/, const_float_t millimeters/*=0.0*/ ) { // If we are cleaning, do not accept queuing of movements @@ -2783,51 +2847,71 @@ bool Planner::buffer_segment(const_float_t a, const_float_t b, const_float_t c, // The target position of the tool in absolute steps // Calculate target position in absolute steps 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])), - int32_t(LROUND(e * settings.axis_steps_per_mm[E_AXIS_N(extruder)])) + LOGICAL_AXIS_LIST( + int32_t(LROUND(abce.e * settings.axis_steps_per_mm[E_AXIS_N(extruder)])), + int32_t(LROUND(abce.a * settings.axis_steps_per_mm[A_AXIS])), + int32_t(LROUND(abce.b * settings.axis_steps_per_mm[B_AXIS])), + int32_t(LROUND(abce.c * settings.axis_steps_per_mm[C_AXIS])), + int32_t(LROUND(abce.i * settings.axis_steps_per_mm[I_AXIS])), + int32_t(LROUND(abce.j * settings.axis_steps_per_mm[J_AXIS])), + int32_t(LROUND(abce.k * settings.axis_steps_per_mm[K_AXIS])) + ) }; #if HAS_POSITION_FLOAT - const xyze_pos_t target_float = { a, b, c, e }; + const xyze_pos_t target_float = abce; #endif - // DRYRUN prevents E moves from taking place - if (DEBUGGING(DRYRUN) || TERN0(CANCEL_OBJECTS, cancelable.skipping)) { - position.e = target.e; - TERN_(HAS_POSITION_FLOAT, position_float.e = e); - } + #if HAS_EXTRUDERS + // DRYRUN prevents E moves from taking place + if (DEBUGGING(DRYRUN) || TERN0(CANCEL_OBJECTS, cancelable.skipping)) { + position.e = target.e; + TERN_(HAS_POSITION_FLOAT, position_float.e = abce.e); + } + #endif /* <-- add a slash to enable SERIAL_ECHOPAIR(" buffer_segment FR:", fr_mm_s); #if IS_KINEMATIC - SERIAL_ECHOPAIR(" A:", a); - SERIAL_ECHOPAIR(" (", position.a); - SERIAL_ECHOPAIR("->", target.a); - SERIAL_ECHOPAIR(") B:", b); + SERIAL_ECHOPAIR(" A:", abce.a, " (", position.a, "->", target.a, ") B:", abce.b); #else - SERIAL_ECHOPAIR_P(SP_X_LBL, a); - SERIAL_ECHOPAIR(" (", position.x); - SERIAL_ECHOPAIR("->", target.x); + SERIAL_ECHOPAIR_P(SP_X_LBL, abce.a); + SERIAL_ECHOPAIR(" (", position.x, "->", target.x); SERIAL_CHAR(')'); - SERIAL_ECHOPAIR_P(SP_Y_LBL, b); + SERIAL_ECHOPAIR_P(SP_Y_LBL, abce.b); #endif - SERIAL_ECHOPAIR(" (", position.y); - SERIAL_ECHOPAIR("->", target.y); - #if ENABLED(DELTA) - SERIAL_ECHOPAIR(") C:", c); - #else + SERIAL_ECHOPAIR(" (", position.y, "->", target.y); + #if LINEAR_AXES >= ABC + #if ENABLED(DELTA) + SERIAL_ECHOPAIR(") C:", abce.c); + #else + SERIAL_CHAR(')'); + SERIAL_ECHOPAIR_P(SP_Z_LBL, abce.c); + #endif + SERIAL_ECHOPAIR(" (", position.z, "->", target.z); + SERIAL_CHAR(')'); + #endif + #if LINEAR_AXES >= 4 + SERIAL_ECHOPAIR_P(SP_I_LBL, abce.i); + SERIAL_ECHOPAIR(" (", position.i, "->", target.i); + SERIAL_CHAR(')'); + #endif + #if LINEAR_AXES >= 5 + SERIAL_ECHOPAIR_P(SP_J_LBL, abce.j); + SERIAL_ECHOPAIR(" (", position.j, "->", target.j); + SERIAL_CHAR(')'); + #endif + #if LINEAR_AXES >= 6 + SERIAL_ECHOPAIR_P(SP_K_LBL, abce.k); + SERIAL_ECHOPAIR(" (", position.k, "->", target.k); SERIAL_CHAR(')'); - SERIAL_ECHOPAIR_P(SP_Z_LBL, c); #endif - SERIAL_ECHOPAIR(" (", position.z); - SERIAL_ECHOPAIR("->", target.z); - SERIAL_CHAR(')'); - SERIAL_ECHOPAIR_P(SP_E_LBL, e); - SERIAL_ECHOPAIR(" (", position.e); - SERIAL_ECHOPAIR("->", target.e); - SERIAL_ECHOLNPGM(")"); + #if HAS_EXTRUDERS + SERIAL_ECHOPAIR_P(SP_E_LBL, abce.e); + SERIAL_ECHOLNPAIR(" (", position.e, "->", target.e, ")"); + #else + SERIAL_EOL(); + #endif //*/ // Queue the movement. Return 'false' if the move was not queued. @@ -2850,34 +2934,34 @@ bool Planner::buffer_segment(const_float_t a, const_float_t b, const_float_t c, * The target is cartesian. It's translated to * delta/scara if needed. * - * rx,ry,rz,e - target position in mm or degrees - * fr_mm_s - (target) speed of the move (mm/s) - * extruder - target extruder - * millimeters - the length of the movement, if known - * inv_duration - the reciprocal if the duration of the movement, if known (kinematic only if feeedrate scaling is enabled) + * cart - target position in mm or degrees + * fr_mm_s - (target) speed of the move (mm/s) + * extruder - target extruder + * millimeters - the length of the movement, if known + * inv_duration - the reciprocal if the duration of the movement, if known (kinematic only if feeedrate scaling is enabled) */ -bool Planner::buffer_line(const_float_t rx, const_float_t ry, const_float_t rz, const_float_t e, const_feedRate_t fr_mm_s, const uint8_t extruder, const float millimeters - #if ENABLED(SCARA_FEEDRATE_SCALING) - , const_float_t inv_duration - #endif +bool Planner::buffer_line(const xyze_pos_t &cart, const_feedRate_t fr_mm_s, const uint8_t extruder/*=active_extruder*/, const float millimeters/*=0.0*/ + OPTARG(SCARA_FEEDRATE_SCALING, const_float_t inv_duration/*=0.0*/) ) { - xyze_pos_t machine = { rx, ry, rz, e }; + xyze_pos_t machine = cart; TERN_(HAS_POSITION_MODIFIERS, apply_modifiers(machine)); #if IS_KINEMATIC #if HAS_JUNCTION_DEVIATION - const xyze_pos_t cart_dist_mm = { - rx - position_cart.x, ry - position_cart.y, - rz - position_cart.z, e - position_cart.e - }; + const xyze_pos_t cart_dist_mm = LOGICAL_AXIS_ARRAY( + cart.e - position_cart.e, + cart.x - position_cart.x, cart.y - position_cart.y, cart.z - position_cart.z, + cart.i - position_cart.i, cart.j - position_cart.j, cart.j - position_cart.k + ); #else - const xyz_pos_t cart_dist_mm = { rx - position_cart.x, ry - position_cart.y, rz - position_cart.z }; + const xyz_pos_t cart_dist_mm = LINEAR_AXIS_ARRAY( + cart.x - position_cart.x, cart.y - position_cart.y, cart.z - position_cart.z, + cart.i - position_cart.i, cart.j - position_cart.j, cart.j - position_cart.k + ); #endif - float mm = millimeters; - if (mm == 0.0) - mm = (cart_dist_mm.x != 0.0 || cart_dist_mm.y != 0.0) ? cart_dist_mm.magnitude() : ABS(cart_dist_mm.z); + const float mm = millimeters ?: (cart_dist_mm.x || cart_dist_mm.y) ? cart_dist_mm.magnitude() : TERN0(HAS_Z_AXIS, ABS(cart_dist_mm.z)); // Cartesian XYZ to kinematic ABC, stored in global 'delta' inverse_kinematics(machine); @@ -2891,17 +2975,12 @@ bool Planner::buffer_line(const_float_t rx, const_float_t ry, const_float_t rz, #else const feedRate_t feedrate = fr_mm_s; #endif - if (buffer_segment(delta.a, delta.b, delta.c, machine.e - #if HAS_JUNCTION_DEVIATION - , cart_dist_mm - #endif - , feedrate, extruder, mm - )) { - position_cart.set(rx, ry, rz, e); + delta.e = machine.e; + if (buffer_segment(delta OPTARG(HAS_DIST_MM_ARG, cart_dist_mm), feedrate, extruder, mm)) { + position_cart = cart; return true; } - else - return false; + return false; #else return buffer_segment(machine, fr_mm_s, extruder, millimeters); #endif @@ -2924,16 +3003,12 @@ bool Planner::buffer_line(const_float_t rx, const_float_t ry, const_float_t rz, FANS_LOOP(i) block->fan_speed[i] = thermalManager.fan_speed[i]; #endif - #if HAS_MULTI_EXTRUDER - block->extruder = extruder; - #endif + TERN_(HAS_MULTI_EXTRUDER, block->extruder = extruder); block->page_idx = page_idx; block->step_event_count = num_steps; - block->initial_rate = - block->final_rate = - block->nominal_rate = last_page_step_rate; // steps/s + block->initial_rate = block->final_rate = block->nominal_rate = last_page_step_rate; // steps/s block->accelerate_until = 0; block->decelerate_after = block->step_event_count; @@ -2971,19 +3046,25 @@ bool Planner::buffer_line(const_float_t rx, const_float_t ry, const_float_t rz, #endif // DIRECT_STEPPING /** - * Directly set the planner ABC position (and stepper positions) + * Directly set the planner ABCE position (and stepper positions) * converting mm (or angles for SCARA) into steps. * - * The provided ABC position is in machine units. + * The provided ABCE position is in machine units. */ - -void Planner::set_machine_position_mm(const_float_t a, const_float_t b, const_float_t c, const_float_t e) { +void Planner::set_machine_position_mm(const abce_pos_t &abce) { TERN_(DISTINCT_E_FACTORS, last_extruder = active_extruder); - TERN_(HAS_POSITION_FLOAT, position_float.set(a, b, c, e)); - 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)])); + TERN_(HAS_POSITION_FLOAT, position_float = abce); + position.set( + LOGICAL_AXIS_LIST( + LROUND(abce.e * settings.axis_steps_per_mm[E_AXIS_N(active_extruder)]), + LROUND(abce.a * settings.axis_steps_per_mm[A_AXIS]), + LROUND(abce.b * settings.axis_steps_per_mm[B_AXIS]), + LROUND(abce.c * settings.axis_steps_per_mm[C_AXIS]), + LROUND(abce.i * settings.axis_steps_per_mm[I_AXIS]), + LROUND(abce.j * settings.axis_steps_per_mm[J_AXIS]), + LROUND(abce.k * settings.axis_steps_per_mm[K_AXIS]) + ) + ); if (has_blocks_queued()) { //previous_nominal_speed_sqr = 0.0; // Reset planner junction speeds. Assume start from rest. //previous_speed.reset(); @@ -2993,49 +3074,48 @@ void Planner::set_machine_position_mm(const_float_t a, const_float_t b, const_fl stepper.set_position(position); } -void Planner::set_position_mm(const_float_t rx, const_float_t ry, const_float_t rz, const_float_t e) { - xyze_pos_t machine = { rx, ry, rz, e }; - #if HAS_POSITION_MODIFIERS - apply_modifiers(machine, true); - #endif +void Planner::set_position_mm(const xyze_pos_t &xyze) { + xyze_pos_t machine = xyze; + TERN_(HAS_POSITION_MODIFIERS, apply_modifiers(machine, true)); #if IS_KINEMATIC - position_cart.set(rx, ry, rz, e); + position_cart = xyze; inverse_kinematics(machine); - set_machine_position_mm(delta.a, delta.b, delta.c, machine.e); + delta.e = machine.e; + set_machine_position_mm(delta); #else set_machine_position_mm(machine); #endif } -/** - * Setters for planner position (also setting stepper position). - */ -void Planner::set_e_position_mm(const_float_t e) { - const uint8_t axis_index = E_AXIS_N(active_extruder); - TERN_(DISTINCT_E_FACTORS, last_extruder = active_extruder); +#if HAS_EXTRUDERS - const float e_new = DIFF_TERN(FWRETRACT, e, fwretract.current_retract[active_extruder]); - position.e = LROUND(settings.axis_steps_per_mm[axis_index] * e_new); - TERN_(HAS_POSITION_FLOAT, position_float.e = e_new); - TERN_(IS_KINEMATIC, position_cart.e = e); + /** + * Setters for planner position (also setting stepper position). + */ + void Planner::set_e_position_mm(const_float_t e) { + const uint8_t axis_index = E_AXIS_N(active_extruder); + TERN_(DISTINCT_E_FACTORS, last_extruder = active_extruder); - if (has_blocks_queued()) - buffer_sync_block(); - else - stepper.set_axis_position(E_AXIS, position.e); -} + const float e_new = DIFF_TERN(FWRETRACT, e, fwretract.current_retract[active_extruder]); + position.e = LROUND(settings.axis_steps_per_mm[axis_index] * e_new); + TERN_(HAS_POSITION_FLOAT, position_float.e = e_new); + TERN_(IS_KINEMATIC, TERN_(HAS_EXTRUDERS, position_cart.e = e)); + + if (has_blocks_queued()) + buffer_sync_block(); + else + stepper.set_axis_position(E_AXIS, position.e); + } + +#endif // Recalculate the steps/s^2 acceleration rates, based on the mm/s^2 void Planner::reset_acceleration_rates() { - #if ENABLED(DISTINCT_E_FACTORS) - #define AXIS_CONDITION (i < E_AXIS || i == E_AXIS_N(active_extruder)) - #else - #define AXIS_CONDITION true - #endif uint32_t highest_rate = 1; LOOP_DISTINCT_AXES(i) { max_acceleration_steps_per_s2[i] = settings.max_acceleration_mm_per_s2[i] * settings.axis_steps_per_mm[i]; - if (AXIS_CONDITION) NOLESS(highest_rate, max_acceleration_steps_per_s2[i]); + if (TERN1(DISTINCT_E_FACTORS, i < E_AXIS || i == E_AXIS_N(active_extruder))) + NOLESS(highest_rate, max_acceleration_steps_per_s2[i]); } acceleration_long_cutoff = 4294967295UL / highest_rate; // 0xFFFFFFFFUL TERN_(HAS_LINEAR_E_JERK, recalculate_max_e_jerk()); @@ -3053,11 +3133,11 @@ void Planner::refresh_positioning() { // Apply limits to a variable and give a warning if the value was out of range inline void limit_and_warn(float &val, const uint8_t axis, PGM_P const setting_name, const xyze_float_t &max_limit) { - const uint8_t lim_axis = axis > E_AXIS ? E_AXIS : axis; + const uint8_t lim_axis = TERN_(HAS_EXTRUDERS, axis > E_AXIS ? E_AXIS :) axis; const float before = val; LIMIT(val, 0.1, max_limit[lim_axis]); if (before != val) { - SERIAL_CHAR(axis_codes[lim_axis]); + SERIAL_CHAR(AXIS_CHAR(lim_axis)); SERIAL_ECHOPGM(" Max "); SERIAL_ECHOPGM_P(setting_name); SERIAL_ECHOLNPAIR(" limited to ", val); diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 66e98f4a5704b..10114ebfc6379 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -76,7 +76,9 @@ // Feedrate for manual moves #ifdef MANUAL_FEEDRATE constexpr xyze_feedrate_t _mf = MANUAL_FEEDRATE, - manual_feedrate_mm_s { _mf.x / 60.0f, _mf.y / 60.0f, _mf.z / 60.0f, _mf.e / 60.0f }; + manual_feedrate_mm_s = LOGICAL_AXIS_ARRAY(_mf.e / 60.0f, + _mf.x / 60.0f, _mf.y / 60.0f, _mf.z / 60.0f, + _mf.i / 60.0f, _mf.j / 60.0f, _mf.k / 60.0f); #endif #if IS_KINEMATIC && HAS_JUNCTION_DEVIATION @@ -450,8 +452,8 @@ class Planner { #endif #if ENABLED(DISABLE_INACTIVE_EXTRUDER) - // Counters to manage disabling inactive extruders - static last_move_t g_uc_extruder_last_move[EXTRUDERS]; + // Counters to manage disabling inactive extruder steppers + static last_move_t g_uc_extruder_last_move[E_STEPPERS]; #endif #if HAS_WIRED_LCD @@ -707,12 +709,8 @@ class Planner { * Returns true if movement was buffered, false otherwise */ static bool _buffer_steps(const xyze_long_t &target - #if HAS_POSITION_FLOAT - , const xyze_pos_t &target_float - #endif - #if HAS_DIST_MM_ARG - , const xyze_float_t &cart_dist_mm - #endif + OPTARG(HAS_POSITION_FLOAT, const xyze_pos_t &target_float) + OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm) , feedRate_t fr_mm_s, const uint8_t extruder, const_float_t millimeters=0.0 ); @@ -728,14 +726,9 @@ class Planner { * * Returns true is movement is acceptable, false otherwise */ - static bool _populate_block(block_t * const block, bool split_move, - const xyze_long_t &target - #if HAS_POSITION_FLOAT - , const xyze_pos_t &target_float - #endif - #if HAS_DIST_MM_ARG - , const xyze_float_t &cart_dist_mm - #endif + static bool _populate_block(block_t * const block, bool split_move, const xyze_long_t &target + OPTARG(HAS_POSITION_FLOAT, const xyze_pos_t &target_float) + OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm) , feedRate_t fr_mm_s, const uint8_t extruder, const_float_t millimeters=0.0 ); @@ -767,26 +760,11 @@ class Planner { * extruder - target extruder * millimeters - the length of the movement, if known */ - static bool buffer_segment(const_float_t a, const_float_t b, const_float_t c, const_float_t e - #if HAS_DIST_MM_ARG - , const xyze_float_t &cart_dist_mm - #endif - , const_feedRate_t fr_mm_s, const uint8_t extruder, const_float_t millimeters=0.0 + static bool buffer_segment(const abce_pos_t &abce + OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm) + , const_feedRate_t fr_mm_s, const uint8_t extruder=active_extruder, const_float_t millimeters=0.0 ); - FORCE_INLINE static bool buffer_segment(abce_pos_t &abce - #if HAS_DIST_MM_ARG - , const xyze_float_t &cart_dist_mm - #endif - , const_feedRate_t fr_mm_s, const uint8_t extruder, const_float_t millimeters=0.0 - ) { - return buffer_segment(abce.a, abce.b, abce.c, abce.e - #if HAS_DIST_MM_ARG - , cart_dist_mm - #endif - , fr_mm_s, extruder, millimeters); - } - public: /** @@ -794,30 +772,16 @@ class Planner { * The target is cartesian. It's translated to * delta/scara if needed. * - * rx,ry,rz,e - target position in mm or degrees + * cart - target position in mm or degrees * fr_mm_s - (target) speed of the move (mm/s) * extruder - target extruder * millimeters - the length of the movement, if known * inv_duration - the reciprocal if the duration of the movement, if known (kinematic only if feeedrate scaling is enabled) */ - static bool buffer_line(const_float_t rx, const_float_t ry, const_float_t rz, const_float_t e, const_feedRate_t fr_mm_s, const uint8_t extruder, const float millimeters=0.0 - #if ENABLED(SCARA_FEEDRATE_SCALING) - , const_float_t inv_duration=0.0 - #endif + static bool buffer_line(const xyze_pos_t &cart, const_feedRate_t fr_mm_s, const uint8_t extruder=active_extruder, const float millimeters=0.0 + OPTARG(SCARA_FEEDRATE_SCALING, const_float_t inv_duration=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_t inv_duration=0.0 - #endif - ) { - return buffer_line(cart.x, cart.y, cart.z, cart.e, fr_mm_s, extruder, millimeters - #if ENABLED(SCARA_FEEDRATE_SCALING) - , inv_duration - #endif - ); - } - #if ENABLED(DIRECT_STEPPING) static void buffer_page(const page_idx_t page_idx, const uint8_t extruder, const uint16_t num_steps); #endif @@ -835,9 +799,11 @@ class Planner { * * Clears previous speed values. */ - static void set_position_mm(const_float_t rx, const_float_t ry, const_float_t rz, const_float_t e); - 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_t e); + static void set_position_mm(const xyze_pos_t &xyze); + + #if HAS_EXTRUDERS + static void set_e_position_mm(const_float_t e); + #endif /** * Set the planner.position and individual stepper positions. @@ -845,8 +811,7 @@ class Planner { * The supplied position is in machine space, and no additional * conversions are applied. */ - static void set_machine_position_mm(const_float_t a, const_float_t b, const_float_t c, const_float_t e); - 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); } + static void set_machine_position_mm(const abce_pos_t &abce); /** * Get an axis position according to stepper position(s) @@ -855,12 +820,11 @@ class Planner { static float get_axis_position_mm(const AxisEnum axis); static inline abce_pos_t get_axis_positions_mm() { - const abce_pos_t out = { - get_axis_position_mm(A_AXIS), - get_axis_position_mm(B_AXIS), - get_axis_position_mm(C_AXIS), - get_axis_position_mm(E_AXIS) - }; + const abce_pos_t out = LOGICAL_AXIS_ARRAY( + get_axis_position_mm(E_AXIS), + get_axis_position_mm(A_AXIS), get_axis_position_mm(B_AXIS), get_axis_position_mm(C_AXIS), + get_axis_position_mm(I_AXIS), get_axis_position_mm(J_AXIS), get_axis_position_mm(K_AXIS) + ); return out; } diff --git a/Marlin/src/module/planner_bezier.cpp b/Marlin/src/module/planner_bezier.cpp index be5ce4bbb4615..848906705fa25 100644 --- a/Marlin/src/module/planner_bezier.cpp +++ b/Marlin/src/module/planner_bezier.cpp @@ -181,11 +181,15 @@ void cubic_b_spline( t = new_t; // Compute and send new position - 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. - }; + xyze_pos_t new_bez = LOGICAL_AXIS_ARRAY( + interp(position.e, target.e, t), // FIXME. Wrong, since t is not linear in the distance. + new_pos0, + new_pos1, + interp(position.z, target.z, t), // FIXME. Wrong, since t is not linear in the distance. + interp(position.i, target.i, t), // FIXME. Wrong, since t is not linear in the distance. + interp(position.j, target.j, t), // FIXME. Wrong, since t is not linear in the distance. + interp(position.k, target.k, t) // FIXME. Wrong, since t is not linear in the distance. + ); apply_motion_limits(new_bez); bez_target = new_bez; diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index 0042302fc7902..dae25feea3ebf 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -245,6 +245,7 @@ xyz_pos_t Probe::offset; // Initialized by settings.load() void Probe::set_probing_paused(const bool dopause) { TERN_(PROBING_HEATERS_OFF, thermalManager.pause_heaters(dopause)); TERN_(PROBING_FANS_OFF, thermalManager.set_fans_paused(dopause)); + TERN_(PROBING_ESTEPPERS_OFF, if (dopause) disable_e_steppers()); #if ENABLED(PROBING_STEPPERS_OFF) IF_DISABLED(DELTA, static uint8_t old_trusted); if (dopause) { @@ -253,7 +254,7 @@ xyz_pos_t Probe::offset; // Initialized by settings.load() DISABLE_AXIS_X(); DISABLE_AXIS_Y(); #endif - disable_e_steppers(); + IF_DISABLED(PROBING_ESTEPPERS_OFF, disable_e_steppers()); } else { #if DISABLED(DELTA) @@ -384,7 +385,7 @@ FORCE_INLINE void probe_specific_action(const bool deploy) { DEBUG_EOL(); TERN_(WAIT_FOR_NOZZLE_HEAT, if (hotend_temp > thermalManager.wholeDegHotend(0) + (TEMP_WINDOW)) thermalManager.wait_for_hotend(0)); - TERN_(WAIT_FOR_BED_HEAT, if (bed_temp > thermalManager.wholeDegBed() + (TEMP_BED_WINDOW)) thermalManager.wait_for_bed_heating()); + TERN_(WAIT_FOR_BED_HEAT, if (bed_temp > thermalManager.wholeDegBed() + (TEMP_BED_WINDOW)) thermalManager.wait_for_bed_heating()); } #endif diff --git a/Marlin/src/module/probe.h b/Marlin/src/module/probe.h index 7438a56614ad1..da46c830f6994 100644 --- a/Marlin/src/module/probe.h +++ b/Marlin/src/module/probe.h @@ -110,7 +110,7 @@ class Probe { #else - static constexpr xyz_pos_t offset = xyz_pos_t({ 0, 0, 0 }); // See #16767 + static constexpr xyz_pos_t offset = xyz_pos_t(LINEAR_AXIS_ARRAY(0, 0, 0, 0, 0, 0)); // See #16767 static bool set_deployed(const bool) { return false; } @@ -222,20 +222,20 @@ class Probe { #define VALIDATE_PROBE_PT(N) static_assert(Probe::build_time::can_reach(xy_pos_t{PROBE_PT_##N##_X, PROBE_PT_##N##_Y}), \ "PROBE_PT_" STRINGIFY(N) "_(X|Y) is unreachable using default NOZZLE_TO_PROBE_OFFSET and PROBING_MARGIN"); VALIDATE_PROBE_PT(1); VALIDATE_PROBE_PT(2); VALIDATE_PROBE_PT(3); - points[0].set(PROBE_PT_1_X, PROBE_PT_1_Y); - points[1].set(PROBE_PT_2_X, PROBE_PT_2_Y); - points[2].set(PROBE_PT_3_X, PROBE_PT_3_Y); + points[0] = xy_float_t({ PROBE_PT_1_X, PROBE_PT_1_Y }); + points[1] = xy_float_t({ PROBE_PT_2_X, PROBE_PT_2_Y }); + points[2] = xy_float_t({ PROBE_PT_3_X, PROBE_PT_3_Y }); #else #if IS_KINEMATIC constexpr float SIN0 = 0.0, SIN120 = 0.866025, SIN240 = -0.866025, COS0 = 1.0, COS120 = -0.5 , COS240 = -0.5; - points[0].set((X_CENTER) + probe_radius() * COS0, (Y_CENTER) + probe_radius() * SIN0); - points[1].set((X_CENTER) + probe_radius() * COS120, (Y_CENTER) + probe_radius() * SIN120); - points[2].set((X_CENTER) + probe_radius() * COS240, (Y_CENTER) + probe_radius() * SIN240); + points[0] = xy_float_t({ (X_CENTER) + probe_radius() * COS0, (Y_CENTER) + probe_radius() * SIN0 }); + points[1] = xy_float_t({ (X_CENTER) + probe_radius() * COS120, (Y_CENTER) + probe_radius() * SIN120 }); + points[2] = xy_float_t({ (X_CENTER) + probe_radius() * COS240, (Y_CENTER) + probe_radius() * SIN240 }); #else - points[0].set(min_x(), min_y()); - points[1].set(max_x(), min_y()); - points[2].set((min_x() + max_x()) / 2, max_y()); + points[0] = xy_float_t({ min_x(), min_y() }); + points[1] = xy_float_t({ max_x(), min_y() }); + points[2] = xy_float_t({ (min_x() + max_x()) / 2, max_y() }); #endif #endif } diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index eae4728793fef..27ba7cbc75b31 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -168,10 +168,14 @@ void M554_report(); #endif -typedef struct { uint16_t X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7; } tmc_stepper_current_t; -typedef struct { uint32_t X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7; } tmc_hybrid_threshold_t; -typedef struct { int16_t X, Y, Z, X2, Y2, Z2, Z3, Z4; } tmc_sgt_t; -typedef struct { bool X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7; } tmc_stealth_enabled_t; +#define _EN_ITEM(N) , E##N + +typedef struct { uint16_t LINEAR_AXIS_LIST(X, Y, Z, I, J, K), X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM); } tmc_stepper_current_t; +typedef struct { uint32_t LINEAR_AXIS_LIST(X, Y, Z, I, J, K), X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM); } tmc_hybrid_threshold_t; +typedef struct { int16_t LINEAR_AXIS_LIST(X, Y, Z, I, J, K), X2, Y2, Z2, Z3, Z4; } tmc_sgt_t; +typedef struct { bool LINEAR_AXIS_LIST(X, Y, Z, I, J, K), X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM); } tmc_stealth_enabled_t; + +#undef _EN_ITEM // Limit an index to an array size #define ALIM(I,ARR) _MIN(I, (signed)COUNT(ARR) - 1) @@ -387,7 +391,7 @@ typedef struct SettingsDataStruct { #ifndef MOTOR_CURRENT_COUNT #define MOTOR_CURRENT_COUNT LINEAR_AXES #endif - uint32_t motor_current_setting[MOTOR_CURRENT_COUNT]; // M907 X Z E + uint32_t motor_current_setting[MOTOR_CURRENT_COUNT]; // M907 X Z E ... // // CNC_COORDINATE_SYSTEMS @@ -654,7 +658,7 @@ void MarlinSettings::postprocess() { EEPROM_WRITE(dummyf); #endif #else - const xyze_pos_t planner_max_jerk = { 10, 10, 0.4, float(DEFAULT_EJERK) }; + const xyze_pos_t planner_max_jerk = LOGICAL_AXIS_ARRAY(float(DEFAULT_EJERK), 10, 10, 0.4, 0.4, 0.4, 0.4); EEPROM_WRITE(planner_max_jerk); #endif @@ -1087,6 +1091,15 @@ void MarlinSettings::postprocess() { #if AXIS_IS_TMC(Z) tmc_stepper_current.Z = stepperZ.getMilliamps(); #endif + #if AXIS_IS_TMC(I) + tmc_stepper_current.I = stepperI.getMilliamps(); + #endif + #if AXIS_IS_TMC(J) + tmc_stepper_current.J = stepperJ.getMilliamps(); + #endif + #if AXIS_IS_TMC(K) + tmc_stepper_current.K = stepperK.getMilliamps(); + #endif #if AXIS_IS_TMC(X2) tmc_stepper_current.X2 = stepperX2.getMilliamps(); #endif @@ -1138,61 +1151,33 @@ void MarlinSettings::postprocess() { #if ENABLED(HYBRID_THRESHOLD) tmc_hybrid_threshold_t tmc_hybrid_threshold{0}; - #if AXIS_HAS_STEALTHCHOP(X) - tmc_hybrid_threshold.X = stepperX.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - tmc_hybrid_threshold.Y = stepperY.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - tmc_hybrid_threshold.Z = stepperZ.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(X2) - tmc_hybrid_threshold.X2 = stepperX2.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - tmc_hybrid_threshold.Y2 = stepperY2.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - tmc_hybrid_threshold.Z2 = stepperZ2.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(Z3) - tmc_hybrid_threshold.Z3 = stepperZ3.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(Z4) - tmc_hybrid_threshold.Z4 = stepperZ4.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(E0) - tmc_hybrid_threshold.E0 = stepperE0.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(E1) - tmc_hybrid_threshold.E1 = stepperE1.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(E2) - tmc_hybrid_threshold.E2 = stepperE2.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(E3) - tmc_hybrid_threshold.E3 = stepperE3.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(E4) - tmc_hybrid_threshold.E4 = stepperE4.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(E5) - tmc_hybrid_threshold.E5 = stepperE5.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(E6) - tmc_hybrid_threshold.E6 = stepperE6.get_pwm_thrs(); - #endif - #if AXIS_HAS_STEALTHCHOP(E7) - tmc_hybrid_threshold.E7 = stepperE7.get_pwm_thrs(); - #endif + TERN_(X_HAS_STEALTHCHOP, tmc_hybrid_threshold.X = stepperX.get_pwm_thrs()); + TERN_(Y_HAS_STEALTHCHOP, tmc_hybrid_threshold.Y = stepperY.get_pwm_thrs()); + TERN_(Z_HAS_STEALTHCHOP, tmc_hybrid_threshold.Z = stepperZ.get_pwm_thrs()); + TERN_(I_HAS_STEALTHCHOP, tmc_hybrid_threshold.I = stepperI.get_pwm_thrs()); + TERN_(J_HAS_STEALTHCHOP, tmc_hybrid_threshold.J = stepperJ.get_pwm_thrs()); + TERN_(K_HAS_STEALTHCHOP, tmc_hybrid_threshold.K = stepperK.get_pwm_thrs()); + TERN_(X2_HAS_STEALTHCHOP, tmc_hybrid_threshold.X2 = stepperX2.get_pwm_thrs()); + TERN_(Y2_HAS_STEALTHCHOP, tmc_hybrid_threshold.Y2 = stepperY2.get_pwm_thrs()); + TERN_(Z2_HAS_STEALTHCHOP, tmc_hybrid_threshold.Z2 = stepperZ2.get_pwm_thrs()); + TERN_(Z3_HAS_STEALTHCHOP, tmc_hybrid_threshold.Z3 = stepperZ3.get_pwm_thrs()); + TERN_(Z4_HAS_STEALTHCHOP, tmc_hybrid_threshold.Z4 = stepperZ4.get_pwm_thrs()); + TERN_(E0_HAS_STEALTHCHOP, tmc_hybrid_threshold.E0 = stepperE0.get_pwm_thrs()); + TERN_(E1_HAS_STEALTHCHOP, tmc_hybrid_threshold.E1 = stepperE1.get_pwm_thrs()); + TERN_(E2_HAS_STEALTHCHOP, tmc_hybrid_threshold.E2 = stepperE2.get_pwm_thrs()); + TERN_(E3_HAS_STEALTHCHOP, tmc_hybrid_threshold.E3 = stepperE3.get_pwm_thrs()); + TERN_(E4_HAS_STEALTHCHOP, tmc_hybrid_threshold.E4 = stepperE4.get_pwm_thrs()); + TERN_(E5_HAS_STEALTHCHOP, tmc_hybrid_threshold.E5 = stepperE5.get_pwm_thrs()); + TERN_(E6_HAS_STEALTHCHOP, tmc_hybrid_threshold.E6 = stepperE6.get_pwm_thrs()); + TERN_(E7_HAS_STEALTHCHOP, tmc_hybrid_threshold.E7 = stepperE7.get_pwm_thrs()); #else + #define _EN_ITEM(N) , .E##N = 30 const tmc_hybrid_threshold_t tmc_hybrid_threshold = { - .X = 100, .Y = 100, .Z = 3, - .X2 = 100, .Y2 = 100, .Z2 = 3, .Z3 = 3, .Z4 = 3, - .E0 = 30, .E1 = 30, .E2 = 30, - .E3 = 30, .E4 = 30, .E5 = 30 + LINEAR_AXIS_LIST(.X = 100, .Y = 100, .Z = 3, .I = 3, .J = 3, .K = 3), + .X2 = 100, .Y2 = 100, .Z2 = 3, .Z3 = 3, .Z4 = 3 + REPEAT(E_STEPPERS, _EN_ITEM) }; + #undef _EN_ITEM #endif EEPROM_WRITE(tmc_hybrid_threshold); } @@ -1203,11 +1188,16 @@ void MarlinSettings::postprocess() { { tmc_sgt_t tmc_sgt{0}; #if USE_SENSORLESS - TERN_(X_SENSORLESS, tmc_sgt.X = stepperX.homing_threshold()); + LINEAR_AXIS_CODE( + TERN_(X_SENSORLESS, tmc_sgt.X = stepperX.homing_threshold()), + TERN_(Y_SENSORLESS, tmc_sgt.Y = stepperY.homing_threshold()), + TERN_(Z_SENSORLESS, tmc_sgt.Z = stepperZ.homing_threshold()), + TERN_(I_SENSORLESS, tmc_sgt.I = stepperI.homing_threshold()), + TERN_(J_SENSORLESS, tmc_sgt.J = stepperJ.homing_threshold()), + TERN_(K_SENSORLESS, tmc_sgt.K = stepperK.homing_threshold()) + ); TERN_(X2_SENSORLESS, tmc_sgt.X2 = stepperX2.homing_threshold()); - TERN_(Y_SENSORLESS, tmc_sgt.Y = stepperY.homing_threshold()); TERN_(Y2_SENSORLESS, tmc_sgt.Y2 = stepperY2.homing_threshold()); - TERN_(Z_SENSORLESS, tmc_sgt.Z = stepperZ.homing_threshold()); TERN_(Z2_SENSORLESS, tmc_sgt.Z2 = stepperZ2.homing_threshold()); TERN_(Z3_SENSORLESS, tmc_sgt.Z3 = stepperZ3.homing_threshold()); TERN_(Z4_SENSORLESS, tmc_sgt.Z4 = stepperZ4.homing_threshold()); @@ -1222,54 +1212,25 @@ void MarlinSettings::postprocess() { _FIELD_TEST(tmc_stealth_enabled); tmc_stealth_enabled_t tmc_stealth_enabled = { false }; - #if AXIS_HAS_STEALTHCHOP(X) - tmc_stealth_enabled.X = stepperX.get_stored_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - tmc_stealth_enabled.Y = stepperY.get_stored_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - tmc_stealth_enabled.Z = stepperZ.get_stored_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(X2) - tmc_stealth_enabled.X2 = stepperX2.get_stored_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - tmc_stealth_enabled.Y2 = stepperY2.get_stored_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - tmc_stealth_enabled.Z2 = stepperZ2.get_stored_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(Z3) - tmc_stealth_enabled.Z3 = stepperZ3.get_stored_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(Z4) - tmc_stealth_enabled.Z4 = stepperZ4.get_stored_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(E0) - tmc_stealth_enabled.E0 = stepperE0.get_stored_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(E1) - tmc_stealth_enabled.E1 = stepperE1.get_stored_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(E2) - tmc_stealth_enabled.E2 = stepperE2.get_stored_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(E3) - tmc_stealth_enabled.E3 = stepperE3.get_stored_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(E4) - tmc_stealth_enabled.E4 = stepperE4.get_stored_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(E5) - tmc_stealth_enabled.E5 = stepperE5.get_stored_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(E6) - tmc_stealth_enabled.E6 = stepperE6.get_stored_stealthChop(); - #endif - #if AXIS_HAS_STEALTHCHOP(E7) - tmc_stealth_enabled.E7 = stepperE7.get_stored_stealthChop(); - #endif + TERN_(X_HAS_STEALTHCHOP, tmc_stealth_enabled.X = stepperX.get_stored_stealthChop()); + TERN_(Y_HAS_STEALTHCHOP, tmc_stealth_enabled.Y = stepperY.get_stored_stealthChop()); + TERN_(Z_HAS_STEALTHCHOP, tmc_stealth_enabled.Z = stepperZ.get_stored_stealthChop()); + TERN_(I_HAS_STEALTHCHOP, tmc_stealth_enabled.I = stepperI.get_stored_stealthChop()); + TERN_(J_HAS_STEALTHCHOP, tmc_stealth_enabled.J = stepperJ.get_stored_stealthChop()); + TERN_(K_HAS_STEALTHCHOP, tmc_stealth_enabled.K = stepperK.get_stored_stealthChop()); + TERN_(X2_HAS_STEALTHCHOP, tmc_stealth_enabled.X2 = stepperX2.get_stored_stealthChop()); + TERN_(Y2_HAS_STEALTHCHOP, tmc_stealth_enabled.Y2 = stepperY2.get_stored_stealthChop()); + TERN_(Z2_HAS_STEALTHCHOP, tmc_stealth_enabled.Z2 = stepperZ2.get_stored_stealthChop()); + TERN_(Z3_HAS_STEALTHCHOP, tmc_stealth_enabled.Z3 = stepperZ3.get_stored_stealthChop()); + TERN_(Z4_HAS_STEALTHCHOP, tmc_stealth_enabled.Z4 = stepperZ4.get_stored_stealthChop()); + TERN_(E0_HAS_STEALTHCHOP, tmc_stealth_enabled.E0 = stepperE0.get_stored_stealthChop()); + TERN_(E1_HAS_STEALTHCHOP, tmc_stealth_enabled.E1 = stepperE1.get_stored_stealthChop()); + TERN_(E2_HAS_STEALTHCHOP, tmc_stealth_enabled.E2 = stepperE2.get_stored_stealthChop()); + TERN_(E3_HAS_STEALTHCHOP, tmc_stealth_enabled.E3 = stepperE3.get_stored_stealthChop()); + TERN_(E4_HAS_STEALTHCHOP, tmc_stealth_enabled.E4 = stepperE4.get_stored_stealthChop()); + TERN_(E5_HAS_STEALTHCHOP, tmc_stealth_enabled.E5 = stepperE5.get_stored_stealthChop()); + TERN_(E6_HAS_STEALTHCHOP, tmc_stealth_enabled.E6 = stepperE6.get_stored_stealthChop()); + TERN_(E7_HAS_STEALTHCHOP, tmc_stealth_enabled.E7 = stepperE7.get_stored_stealthChop()); EEPROM_WRITE(tmc_stealth_enabled); } @@ -1992,6 +1953,15 @@ void MarlinSettings::postprocess() { #if AXIS_IS_TMC(Z4) SET_CURR(Z4); #endif + #if AXIS_IS_TMC(I) + SET_CURR(I); + #endif + #if AXIS_IS_TMC(J) + SET_CURR(J); + #endif + #if AXIS_IS_TMC(K) + SET_CURR(K); + #endif #if AXIS_IS_TMC(E0) SET_CURR(E0); #endif @@ -2028,54 +1998,25 @@ void MarlinSettings::postprocess() { #if ENABLED(HYBRID_THRESHOLD) if (!validating) { - #if AXIS_HAS_STEALTHCHOP(X) - stepperX.set_pwm_thrs(tmc_hybrid_threshold.X); - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - stepperY.set_pwm_thrs(tmc_hybrid_threshold.Y); - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - stepperZ.set_pwm_thrs(tmc_hybrid_threshold.Z); - #endif - #if AXIS_HAS_STEALTHCHOP(X2) - stepperX2.set_pwm_thrs(tmc_hybrid_threshold.X2); - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - stepperY2.set_pwm_thrs(tmc_hybrid_threshold.Y2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - stepperZ2.set_pwm_thrs(tmc_hybrid_threshold.Z2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z3) - stepperZ3.set_pwm_thrs(tmc_hybrid_threshold.Z3); - #endif - #if AXIS_HAS_STEALTHCHOP(Z4) - stepperZ4.set_pwm_thrs(tmc_hybrid_threshold.Z4); - #endif - #if AXIS_HAS_STEALTHCHOP(E0) - stepperE0.set_pwm_thrs(tmc_hybrid_threshold.E0); - #endif - #if AXIS_HAS_STEALTHCHOP(E1) - stepperE1.set_pwm_thrs(tmc_hybrid_threshold.E1); - #endif - #if AXIS_HAS_STEALTHCHOP(E2) - stepperE2.set_pwm_thrs(tmc_hybrid_threshold.E2); - #endif - #if AXIS_HAS_STEALTHCHOP(E3) - stepperE3.set_pwm_thrs(tmc_hybrid_threshold.E3); - #endif - #if AXIS_HAS_STEALTHCHOP(E4) - stepperE4.set_pwm_thrs(tmc_hybrid_threshold.E4); - #endif - #if AXIS_HAS_STEALTHCHOP(E5) - stepperE5.set_pwm_thrs(tmc_hybrid_threshold.E5); - #endif - #if AXIS_HAS_STEALTHCHOP(E6) - stepperE6.set_pwm_thrs(tmc_hybrid_threshold.E6); - #endif - #if AXIS_HAS_STEALTHCHOP(E7) - stepperE7.set_pwm_thrs(tmc_hybrid_threshold.E7); - #endif + TERN_(X_HAS_STEALTHCHOP, stepperX.set_pwm_thrs(tmc_hybrid_threshold.X)); + TERN_(Y_HAS_STEALTHCHOP, stepperY.set_pwm_thrs(tmc_hybrid_threshold.Y)); + TERN_(Z_HAS_STEALTHCHOP, stepperZ.set_pwm_thrs(tmc_hybrid_threshold.Z)); + TERN_(X2_HAS_STEALTHCHOP, stepperX2.set_pwm_thrs(tmc_hybrid_threshold.X2)); + TERN_(Y2_HAS_STEALTHCHOP, stepperY2.set_pwm_thrs(tmc_hybrid_threshold.Y2)); + TERN_(Z2_HAS_STEALTHCHOP, stepperZ2.set_pwm_thrs(tmc_hybrid_threshold.Z2)); + TERN_(Z3_HAS_STEALTHCHOP, stepperZ3.set_pwm_thrs(tmc_hybrid_threshold.Z3)); + TERN_(Z4_HAS_STEALTHCHOP, stepperZ4.set_pwm_thrs(tmc_hybrid_threshold.Z4)); + TERN_(I_HAS_STEALTHCHOP, stepperI.set_pwm_thrs(tmc_hybrid_threshold.I)); + TERN_(J_HAS_STEALTHCHOP, stepperJ.set_pwm_thrs(tmc_hybrid_threshold.J)); + TERN_(K_HAS_STEALTHCHOP, stepperK.set_pwm_thrs(tmc_hybrid_threshold.K)); + TERN_(E0_HAS_STEALTHCHOP, stepperE0.set_pwm_thrs(tmc_hybrid_threshold.E0)); + TERN_(E1_HAS_STEALTHCHOP, stepperE1.set_pwm_thrs(tmc_hybrid_threshold.E1)); + TERN_(E2_HAS_STEALTHCHOP, stepperE2.set_pwm_thrs(tmc_hybrid_threshold.E2)); + TERN_(E3_HAS_STEALTHCHOP, stepperE3.set_pwm_thrs(tmc_hybrid_threshold.E3)); + TERN_(E4_HAS_STEALTHCHOP, stepperE4.set_pwm_thrs(tmc_hybrid_threshold.E4)); + TERN_(E5_HAS_STEALTHCHOP, stepperE5.set_pwm_thrs(tmc_hybrid_threshold.E5)); + TERN_(E6_HAS_STEALTHCHOP, stepperE6.set_pwm_thrs(tmc_hybrid_threshold.E6)); + TERN_(E7_HAS_STEALTHCHOP, stepperE7.set_pwm_thrs(tmc_hybrid_threshold.E7)); } #endif } @@ -2089,11 +2030,16 @@ void MarlinSettings::postprocess() { EEPROM_READ(tmc_sgt); #if USE_SENSORLESS if (!validating) { - TERN_(X_SENSORLESS, stepperX.homing_threshold(tmc_sgt.X)); + LINEAR_AXIS_CODE( + TERN_(X_SENSORLESS, stepperX.homing_threshold(tmc_sgt.X)), + TERN_(Y_SENSORLESS, stepperY.homing_threshold(tmc_sgt.Y)), + TERN_(Z_SENSORLESS, stepperZ.homing_threshold(tmc_sgt.Z)), + TERN_(I_SENSORLESS, stepperI.homing_threshold(tmc_sgt.I)), + TERN_(J_SENSORLESS, stepperJ.homing_threshold(tmc_sgt.J)), + TERN_(K_SENSORLESS, stepperK.homing_threshold(tmc_sgt.K)) + ); TERN_(X2_SENSORLESS, stepperX2.homing_threshold(tmc_sgt.X2)); - TERN_(Y_SENSORLESS, stepperY.homing_threshold(tmc_sgt.Y)); TERN_(Y2_SENSORLESS, stepperY2.homing_threshold(tmc_sgt.Y2)); - TERN_(Z_SENSORLESS, stepperZ.homing_threshold(tmc_sgt.Z)); TERN_(Z2_SENSORLESS, stepperZ2.homing_threshold(tmc_sgt.Z2)); TERN_(Z3_SENSORLESS, stepperZ3.homing_threshold(tmc_sgt.Z3)); TERN_(Z4_SENSORLESS, stepperZ4.homing_threshold(tmc_sgt.Z4)); @@ -2112,54 +2058,25 @@ void MarlinSettings::postprocess() { #define SET_STEPPING_MODE(ST) stepper##ST.stored.stealthChop_enabled = tmc_stealth_enabled.ST; stepper##ST.refresh_stepping_mode(); if (!validating) { - #if AXIS_HAS_STEALTHCHOP(X) - SET_STEPPING_MODE(X); - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - SET_STEPPING_MODE(Y); - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - SET_STEPPING_MODE(Z); - #endif - #if AXIS_HAS_STEALTHCHOP(X2) - SET_STEPPING_MODE(X2); - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - SET_STEPPING_MODE(Y2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - SET_STEPPING_MODE(Z2); - #endif - #if AXIS_HAS_STEALTHCHOP(Z3) - SET_STEPPING_MODE(Z3); - #endif - #if AXIS_HAS_STEALTHCHOP(Z4) - SET_STEPPING_MODE(Z4); - #endif - #if AXIS_HAS_STEALTHCHOP(E0) - SET_STEPPING_MODE(E0); - #endif - #if AXIS_HAS_STEALTHCHOP(E1) - SET_STEPPING_MODE(E1); - #endif - #if AXIS_HAS_STEALTHCHOP(E2) - SET_STEPPING_MODE(E2); - #endif - #if AXIS_HAS_STEALTHCHOP(E3) - SET_STEPPING_MODE(E3); - #endif - #if AXIS_HAS_STEALTHCHOP(E4) - SET_STEPPING_MODE(E4); - #endif - #if AXIS_HAS_STEALTHCHOP(E5) - SET_STEPPING_MODE(E5); - #endif - #if AXIS_HAS_STEALTHCHOP(E6) - SET_STEPPING_MODE(E6); - #endif - #if AXIS_HAS_STEALTHCHOP(E7) - SET_STEPPING_MODE(E7); - #endif + TERN_(X_HAS_STEALTHCHOP, SET_STEPPING_MODE(X)); + TERN_(Y_HAS_STEALTHCHOP, SET_STEPPING_MODE(Y)); + TERN_(Z_HAS_STEALTHCHOP, SET_STEPPING_MODE(Z)); + TERN_(I_HAS_STEALTHCHOP, SET_STEPPING_MODE(I)); + TERN_(J_HAS_STEALTHCHOP, SET_STEPPING_MODE(J)); + TERN_(K_HAS_STEALTHCHOP, SET_STEPPING_MODE(K)); + TERN_(X2_HAS_STEALTHCHOP, SET_STEPPING_MODE(X2)); + TERN_(Y2_HAS_STEALTHCHOP, SET_STEPPING_MODE(Y2)); + TERN_(Z2_HAS_STEALTHCHOP, SET_STEPPING_MODE(Z2)); + TERN_(Z3_HAS_STEALTHCHOP, SET_STEPPING_MODE(Z3)); + TERN_(Z4_HAS_STEALTHCHOP, SET_STEPPING_MODE(Z4)); + TERN_(E0_HAS_STEALTHCHOP, SET_STEPPING_MODE(E0)); + TERN_(E1_HAS_STEALTHCHOP, SET_STEPPING_MODE(E1)); + TERN_(E2_HAS_STEALTHCHOP, SET_STEPPING_MODE(E2)); + TERN_(E3_HAS_STEALTHCHOP, SET_STEPPING_MODE(E3)); + TERN_(E4_HAS_STEALTHCHOP, SET_STEPPING_MODE(E4)); + TERN_(E5_HAS_STEALTHCHOP, SET_STEPPING_MODE(E5)); + TERN_(E6_HAS_STEALTHCHOP, SET_STEPPING_MODE(E6)); + TERN_(E7_HAS_STEALTHCHOP, SET_STEPPING_MODE(E7)); } #endif } @@ -2598,14 +2515,25 @@ void MarlinSettings::reset() { #ifndef DEFAULT_XJERK #define DEFAULT_XJERK 0 #endif - #ifndef DEFAULT_YJERK + #if HAS_Y_AXIS && !defined(DEFAULT_YJERK) #define DEFAULT_YJERK 0 #endif - #ifndef DEFAULT_ZJERK + #if HAS_Z_AXIS && !defined(DEFAULT_ZJERK) #define DEFAULT_ZJERK 0 #endif - planner.max_jerk.set(DEFAULT_XJERK, DEFAULT_YJERK, DEFAULT_ZJERK); - TERN_(HAS_CLASSIC_E_JERK, planner.max_jerk.e = DEFAULT_EJERK;); + #if LINEAR_AXES >= 4 && !defined(DEFAULT_IJERK) + #define DEFAULT_IJERK 0 + #endif + #if LINEAR_AXES >= 5 && !defined(DEFAULT_JJERK) + #define DEFAULT_JJERK 0 + #endif + #if LINEAR_AXES >= 6 && !defined(DEFAULT_KJERK) + #define DEFAULT_KJERK 0 + #endif + planner.max_jerk.set( + LINEAR_AXIS_LIST(DEFAULT_XJERK, DEFAULT_YJERK, DEFAULT_ZJERK, DEFAULT_IJERK, DEFAULT_JJERK, DEFAULT_KJERK) + ); + TERN_(HAS_CLASSIC_E_JERK, planner.max_jerk.e = DEFAULT_EJERK); #endif #if HAS_JUNCTION_DEVIATION @@ -2703,11 +2631,11 @@ void MarlinSettings::reset() { #if HAS_BED_PROBE constexpr float dpo[] = NOZZLE_TO_PROBE_OFFSET; - static_assert(COUNT(dpo) == 3, "NOZZLE_TO_PROBE_OFFSET must contain offsets for X, Y, and Z."); + static_assert(COUNT(dpo) == LINEAR_AXES, "NOZZLE_TO_PROBE_OFFSET must contain offsets for each linear axis X, Y, Z...."); #if HAS_PROBE_XY_OFFSET LOOP_LINEAR_AXES(a) probe.offset[a] = dpo[a]; #else - probe.offset.set(0, 0, dpo[Z_AXIS]); + probe.offset.set(LINEAR_AXIS_LIST(0, 0, dpo[Z_AXIS], 0, 0, 0)); #endif #endif @@ -3142,10 +3070,15 @@ void MarlinSettings::reset() { CONFIG_ECHO_HEADING("Maximum feedrates (units/s):"); CONFIG_ECHO_START(); SERIAL_ECHOLNPAIR_P( - PSTR(" M203 X"), LINEAR_UNIT(planner.settings.max_feedrate_mm_s[X_AXIS]) - , SP_Y_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Y_AXIS]) - , SP_Z_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Z_AXIS]) - #if DISABLED(DISTINCT_E_FACTORS) + LIST_N(DOUBLE(LINEAR_AXES), + PSTR(" M203 X"), LINEAR_UNIT(planner.settings.max_feedrate_mm_s[X_AXIS]), + SP_Y_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Y_AXIS]), + SP_Z_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Z_AXIS]), + SP_I_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[I_AXIS]), + SP_J_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[J_AXIS]), + SP_K_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[K_AXIS]) + ) + #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS) , SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_feedrate_mm_s[E_AXIS]) #endif ); @@ -3162,10 +3095,15 @@ void MarlinSettings::reset() { CONFIG_ECHO_HEADING("Maximum Acceleration (units/s2):"); CONFIG_ECHO_START(); SERIAL_ECHOLNPAIR_P( - PSTR(" M201 X"), LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[X_AXIS]) - , SP_Y_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Y_AXIS]) - , SP_Z_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Z_AXIS]) - #if DISABLED(DISTINCT_E_FACTORS) + LIST_N(DOUBLE(LINEAR_AXES), + PSTR(" M201 X"), LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[X_AXIS]), + SP_Y_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Y_AXIS]), + SP_Z_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Z_AXIS]), + SP_I_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[I_AXIS]), + SP_J_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[J_AXIS]), + SP_K_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[K_AXIS]) + ) + #if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS) , SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_acceleration_mm_per_s2[E_AXIS]) #endif ); @@ -3206,9 +3144,14 @@ void MarlinSettings::reset() { , PSTR(" J"), LINEAR_UNIT(planner.junction_deviation_mm) #endif #if HAS_CLASSIC_JERK - , SP_X_STR, LINEAR_UNIT(planner.max_jerk.x) - , SP_Y_STR, LINEAR_UNIT(planner.max_jerk.y) - , SP_Z_STR, LINEAR_UNIT(planner.max_jerk.z) + , LIST_N(DOUBLE(LINEAR_AXES), + SP_X_STR, LINEAR_UNIT(planner.max_jerk.x), + SP_Y_STR, LINEAR_UNIT(planner.max_jerk.y), + SP_Z_STR, LINEAR_UNIT(planner.max_jerk.z), + SP_I_STR, LINEAR_UNIT(planner.max_jerk.i), + SP_J_STR, LINEAR_UNIT(planner.max_jerk.j), + SP_K_STR, LINEAR_UNIT(planner.max_jerk.k) + ) #if HAS_CLASSIC_E_JERK , SP_E_STR, LINEAR_UNIT(planner.max_jerk.e) #endif @@ -3220,13 +3163,17 @@ void MarlinSettings::reset() { CONFIG_ECHO_START(); SERIAL_ECHOLNPAIR_P( #if IS_CARTESIAN - PSTR(" M206 X"), LINEAR_UNIT(home_offset.x) - , SP_Y_STR, LINEAR_UNIT(home_offset.y) - , SP_Z_STR + LIST_N(DOUBLE(LINEAR_AXES), + PSTR(" M206 X"), LINEAR_UNIT(home_offset.x), + SP_Y_STR, LINEAR_UNIT(home_offset.y), + SP_Z_STR, LINEAR_UNIT(home_offset.z), + SP_I_STR, LINEAR_UNIT(home_offset.i), + SP_J_STR, LINEAR_UNIT(home_offset.j), + SP_K_STR, LINEAR_UNIT(home_offset.k) + ) #else - PSTR(" M206 Z") + PSTR(" M206 Z"), LINEAR_UNIT(home_offset.z) #endif - , LINEAR_UNIT(home_offset.z) ); #endif @@ -3578,6 +3525,19 @@ void MarlinSettings::reset() { SERIAL_ECHOLNPAIR(" I3 Z", stepperZ4.getMilliamps()); #endif + #if AXIS_IS_TMC(I) + say_M906(forReplay); + SERIAL_ECHOLNPAIR_P(SP_I_STR, stepperI.getMilliamps()); + #endif + #if AXIS_IS_TMC(J) + say_M906(forReplay); + SERIAL_ECHOLNPAIR_P(SP_J_STR, stepperJ.getMilliamps()); + #endif + #if AXIS_IS_TMC(K) + say_M906(forReplay); + SERIAL_ECHOLNPAIR_P(SP_K_STR, stepperK.getMilliamps()); + #endif + #if AXIS_IS_TMC(E0) say_M906(forReplay); SERIAL_ECHOLNPAIR(" T0 E", stepperE0.getMilliamps()); @@ -3617,74 +3577,87 @@ void MarlinSettings::reset() { */ #if ENABLED(HYBRID_THRESHOLD) CONFIG_ECHO_HEADING("Hybrid Threshold:"); - #if AXIS_HAS_STEALTHCHOP(X) || AXIS_HAS_STEALTHCHOP(Y) || AXIS_HAS_STEALTHCHOP(Z) + #if X_HAS_STEALTHCHOP || Y_HAS_STEALTHCHOP || Z_HAS_STEALTHCHOP say_M913(forReplay); - #if AXIS_HAS_STEALTHCHOP(X) + #if X_HAS_STEALTHCHOP SERIAL_ECHOPAIR_P(SP_X_STR, stepperX.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(Y) + #if Y_HAS_STEALTHCHOP SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(Z) + #if Z_HAS_STEALTHCHOP SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ.get_pwm_thrs()); #endif SERIAL_EOL(); #endif - #if AXIS_HAS_STEALTHCHOP(X2) || AXIS_HAS_STEALTHCHOP(Y2) || AXIS_HAS_STEALTHCHOP(Z2) + #if X2_HAS_STEALTHCHOP || Y2_HAS_STEALTHCHOP || Z2_HAS_STEALTHCHOP say_M913(forReplay); SERIAL_ECHOPGM(" I1"); - #if AXIS_HAS_STEALTHCHOP(X2) + #if X2_HAS_STEALTHCHOP SERIAL_ECHOPAIR_P(SP_X_STR, stepperX2.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(Y2) + #if Y2_HAS_STEALTHCHOP SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY2.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(Z2) + #if Z2_HAS_STEALTHCHOP SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ2.get_pwm_thrs()); #endif SERIAL_EOL(); #endif - #if AXIS_HAS_STEALTHCHOP(Z3) + #if Z3_HAS_STEALTHCHOP say_M913(forReplay); SERIAL_ECHOLNPAIR(" I2 Z", stepperZ3.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(Z4) + #if Z4_HAS_STEALTHCHOP say_M913(forReplay); SERIAL_ECHOLNPAIR(" I3 Z", stepperZ4.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(E0) + #if I_HAS_STEALTHCHOP + say_M913(forReplay); + SERIAL_ECHOLNPAIR_P(SP_I_STR, stepperI.get_pwm_thrs()); + #endif + #if J_HAS_STEALTHCHOP + say_M913(forReplay); + SERIAL_ECHOLNPAIR_P(SP_J_STR, stepperJ.get_pwm_thrs()); + #endif + #if K_HAS_STEALTHCHOP + say_M913(forReplay); + SERIAL_ECHOLNPAIR_P(SP_K_STR, stepperK.get_pwm_thrs()); + #endif + + #if E0_HAS_STEALTHCHOP say_M913(forReplay); SERIAL_ECHOLNPAIR(" T0 E", stepperE0.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(E1) + #if E1_HAS_STEALTHCHOP say_M913(forReplay); SERIAL_ECHOLNPAIR(" T1 E", stepperE1.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(E2) + #if E2_HAS_STEALTHCHOP say_M913(forReplay); SERIAL_ECHOLNPAIR(" T2 E", stepperE2.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(E3) + #if E3_HAS_STEALTHCHOP say_M913(forReplay); SERIAL_ECHOLNPAIR(" T3 E", stepperE3.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(E4) + #if E4_HAS_STEALTHCHOP say_M913(forReplay); SERIAL_ECHOLNPAIR(" T4 E", stepperE4.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(E5) + #if E5_HAS_STEALTHCHOP say_M913(forReplay); SERIAL_ECHOLNPAIR(" T5 E", stepperE5.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(E6) + #if E6_HAS_STEALTHCHOP say_M913(forReplay); SERIAL_ECHOLNPAIR(" T6 E", stepperE6.get_pwm_thrs()); #endif - #if AXIS_HAS_STEALTHCHOP(E7) + #if E7_HAS_STEALTHCHOP say_M913(forReplay); SERIAL_ECHOLNPAIR(" T7 E", stepperE7.get_pwm_thrs()); #endif @@ -3739,6 +3712,22 @@ void MarlinSettings::reset() { SERIAL_ECHOLNPAIR(" I3 Z", stepperZ4.homing_threshold()); #endif + #if I_SENSORLESS + CONFIG_ECHO_START(); + say_M914(); + SERIAL_ECHOLNPAIR_P(SP_I_STR, stepperI.homing_threshold()); + #endif + #if J_SENSORLESS + CONFIG_ECHO_START(); + say_M914(); + SERIAL_ECHOLNPAIR_P(SP_J_STR, stepperJ.homing_threshold()); + #endif + #if K_SENSORLESS + CONFIG_ECHO_START(); + say_M914(); + SERIAL_ECHOLNPAIR_P(SP_K_STR, stepperK.homing_threshold()); + #endif + #endif // USE_SENSORLESS /** @@ -3746,45 +3735,29 @@ void MarlinSettings::reset() { */ #if HAS_STEALTHCHOP CONFIG_ECHO_HEADING("Driver stepping mode:"); - #if AXIS_HAS_STEALTHCHOP(X) - const bool chop_x = stepperX.get_stored_stealthChop(); - #else - constexpr bool chop_x = false; - #endif - #if AXIS_HAS_STEALTHCHOP(Y) - const bool chop_y = stepperY.get_stored_stealthChop(); - #else - constexpr bool chop_y = false; - #endif - #if AXIS_HAS_STEALTHCHOP(Z) - const bool chop_z = stepperZ.get_stored_stealthChop(); - #else - constexpr bool chop_z = false; - #endif - - if (chop_x || chop_y || chop_z) { + const bool chop_x = TERN0(X_HAS_STEALTHCHOP, stepperX.get_stored_stealthChop()), + chop_y = TERN0(Y_HAS_STEALTHCHOP, stepperY.get_stored_stealthChop()), + chop_z = TERN0(Z_HAS_STEALTHCHOP, stepperZ.get_stored_stealthChop()), + chop_i = TERN0(I_HAS_STEALTHCHOP, stepperI.get_stored_stealthChop()), + chop_j = TERN0(J_HAS_STEALTHCHOP, stepperJ.get_stored_stealthChop()), + chop_k = TERN0(K_HAS_STEALTHCHOP, stepperK.get_stored_stealthChop()); + + if (chop_x || chop_y || chop_z || chop_i || chop_j || chop_k) { say_M569(forReplay); - if (chop_x) SERIAL_ECHOPGM_P(SP_X_STR); - if (chop_y) SERIAL_ECHOPGM_P(SP_Y_STR); - if (chop_z) SERIAL_ECHOPGM_P(SP_Z_STR); + LINEAR_AXIS_CODE( + if (chop_x) SERIAL_ECHOPGM_P(SP_X_STR), + if (chop_y) SERIAL_ECHOPGM_P(SP_Y_STR), + if (chop_z) SERIAL_ECHOPGM_P(SP_Z_STR), + if (chop_i) SERIAL_ECHOPGM_P(SP_I_STR), + if (chop_j) SERIAL_ECHOPGM_P(SP_J_STR), + if (chop_k) SERIAL_ECHOPGM_P(SP_K_STR) + ); SERIAL_EOL(); } - #if AXIS_HAS_STEALTHCHOP(X2) - const bool chop_x2 = stepperX2.get_stored_stealthChop(); - #else - constexpr bool chop_x2 = false; - #endif - #if AXIS_HAS_STEALTHCHOP(Y2) - const bool chop_y2 = stepperY2.get_stored_stealthChop(); - #else - constexpr bool chop_y2 = false; - #endif - #if AXIS_HAS_STEALTHCHOP(Z2) - const bool chop_z2 = stepperZ2.get_stored_stealthChop(); - #else - constexpr bool chop_z2 = false; - #endif + const bool chop_x2 = TERN0(X2_HAS_STEALTHCHOP, stepperX2.get_stored_stealthChop()), + chop_y2 = TERN0(Y2_HAS_STEALTHCHOP, stepperY2.get_stored_stealthChop()), + chop_z2 = TERN0(Z2_HAS_STEALTHCHOP, stepperZ2.get_stored_stealthChop()); if (chop_x2 || chop_y2 || chop_z2) { say_M569(forReplay, PSTR("I1")); @@ -3794,38 +3767,21 @@ void MarlinSettings::reset() { SERIAL_EOL(); } - #if AXIS_HAS_STEALTHCHOP(Z3) - if (stepperZ3.get_stored_stealthChop()) { say_M569(forReplay, PSTR("I2 Z"), true); } - #endif + if (TERN0(Z3_HAS_STEALTHCHOP, stepperZ3.get_stored_stealthChop())) { say_M569(forReplay, PSTR("I2 Z"), true); } + if (TERN0(Z4_HAS_STEALTHCHOP, stepperZ4.get_stored_stealthChop())) { say_M569(forReplay, PSTR("I3 Z"), true); } - #if AXIS_HAS_STEALTHCHOP(Z4) - if (stepperZ4.get_stored_stealthChop()) { say_M569(forReplay, PSTR("I3 Z"), true); } - #endif + if (TERN0( I_HAS_STEALTHCHOP, stepperI.get_stored_stealthChop())) { say_M569(forReplay, SP_I_STR, true); } + if (TERN0( J_HAS_STEALTHCHOP, stepperJ.get_stored_stealthChop())) { say_M569(forReplay, SP_J_STR, true); } + if (TERN0( K_HAS_STEALTHCHOP, stepperK.get_stored_stealthChop())) { say_M569(forReplay, SP_K_STR, true); } - #if AXIS_HAS_STEALTHCHOP(E0) - if (stepperE0.get_stored_stealthChop()) { say_M569(forReplay, PSTR("T0 E"), true); } - #endif - #if AXIS_HAS_STEALTHCHOP(E1) - if (stepperE1.get_stored_stealthChop()) { say_M569(forReplay, PSTR("T1 E"), true); } - #endif - #if AXIS_HAS_STEALTHCHOP(E2) - if (stepperE2.get_stored_stealthChop()) { say_M569(forReplay, PSTR("T2 E"), true); } - #endif - #if AXIS_HAS_STEALTHCHOP(E3) - if (stepperE3.get_stored_stealthChop()) { say_M569(forReplay, PSTR("T3 E"), true); } - #endif - #if AXIS_HAS_STEALTHCHOP(E4) - if (stepperE4.get_stored_stealthChop()) { say_M569(forReplay, PSTR("T4 E"), true); } - #endif - #if AXIS_HAS_STEALTHCHOP(E5) - if (stepperE5.get_stored_stealthChop()) { say_M569(forReplay, PSTR("T5 E"), true); } - #endif - #if AXIS_HAS_STEALTHCHOP(E6) - if (stepperE6.get_stored_stealthChop()) { say_M569(forReplay, PSTR("T6 E"), true); } - #endif - #if AXIS_HAS_STEALTHCHOP(E7) - if (stepperE7.get_stored_stealthChop()) { say_M569(forReplay, PSTR("T7 E"), true); } - #endif + if (TERN0(E0_HAS_STEALTHCHOP, stepperE0.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T0 E"), true); } + if (TERN0(E1_HAS_STEALTHCHOP, stepperE1.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T1 E"), true); } + if (TERN0(E2_HAS_STEALTHCHOP, stepperE2.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T2 E"), true); } + if (TERN0(E3_HAS_STEALTHCHOP, stepperE3.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T3 E"), true); } + if (TERN0(E4_HAS_STEALTHCHOP, stepperE4.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T4 E"), true); } + if (TERN0(E5_HAS_STEALTHCHOP, stepperE5.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T5 E"), true); } + if (TERN0(E6_HAS_STEALTHCHOP, stepperE6.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T6 E"), true); } + if (TERN0(E7_HAS_STEALTHCHOP, stepperE7.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T7 E"), true); } #endif // HAS_STEALTHCHOP @@ -3855,7 +3811,7 @@ void MarlinSettings::reset() { ); #elif HAS_MOTOR_CURRENT_SPI SERIAL_ECHOPGM(" M907"); // SPI-based has 5 values: - LOOP_LOGICAL_AXES(q) { // X Y Z E (map to X Y Z E0 by default) + LOOP_LOGICAL_AXES(q) { // X Y Z (I J K) E (map to X Y Z (I J K) E0 by default) SERIAL_CHAR(' ', axis_codes[q]); SERIAL_ECHO(stepper.motor_current_setting[q]); } @@ -3865,7 +3821,7 @@ void MarlinSettings::reset() { #elif ENABLED(HAS_MOTOR_CURRENT_I2C) // i2c-based has any number of values // Values sent over i2c are not stored. // Indexes map directly to drivers, not axes. - #elif ENABLED(HAS_MOTOR_CURRENT_DAC) // DAC-based has 4 values, for X Y Z E + #elif ENABLED(HAS_MOTOR_CURRENT_DAC) // DAC-based has 4 values, for X Y Z (I J K) E // Values sent over i2c are not stored. Uses indirect mapping. #endif @@ -3894,9 +3850,14 @@ void MarlinSettings::reset() { CONFIG_ECHO_START(); SERIAL_ECHOLNPAIR_P( PSTR(" M425 F"), backlash.get_correction() - , SP_X_STR, LINEAR_UNIT(backlash.distance_mm.x) - , SP_Y_STR, LINEAR_UNIT(backlash.distance_mm.y) - , SP_Z_STR, LINEAR_UNIT(backlash.distance_mm.z) + , LIST_N(DOUBLE(LINEAR_AXES), + SP_X_STR, LINEAR_UNIT(backlash.distance_mm.x), + SP_Y_STR, LINEAR_UNIT(backlash.distance_mm.y), + SP_Z_STR, LINEAR_UNIT(backlash.distance_mm.z), + SP_I_STR, LINEAR_UNIT(backlash.distance_mm.i), + SP_J_STR, LINEAR_UNIT(backlash.distance_mm.j), + SP_K_STR, LINEAR_UNIT(backlash.distance_mm.k) + ) #ifdef BACKLASH_SMOOTHING_MM , PSTR(" S"), LINEAR_UNIT(backlash.smoothing_mm) #endif diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 2e2afaeb90b65..0ff909d7ccab3 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -259,7 +259,7 @@ xyze_int8_t Stepper::count_direction{0}; #define DUAL_ENDSTOP_APPLY_STEP(A,V) \ if (separate_multi_axis) { \ - if (A##_HOME_TO_MIN) { \ + if (ENABLED(A##_HOME_TO_MIN)) { \ if (TERN0(HAS_##A##_MIN, !(TEST(endstops.state(), A##_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##_motor)) A##_STEP_WRITE(V); \ if (TERN0(HAS_##A##2_MIN, !(TEST(endstops.state(), A##2_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##2_motor)) A##2_STEP_WRITE(V); \ } \ @@ -285,7 +285,7 @@ xyze_int8_t Stepper::count_direction{0}; #define TRIPLE_ENDSTOP_APPLY_STEP(A,V) \ if (separate_multi_axis) { \ - if (A##_HOME_TO_MIN) { \ + if (ENABLED(A##_HOME_TO_MIN)) { \ if (!(TEST(endstops.state(), A##_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##_motor) A##_STEP_WRITE(V); \ if (!(TEST(endstops.state(), A##2_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \ if (!(TEST(endstops.state(), A##3_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##3_motor) A##3_STEP_WRITE(V); \ @@ -314,26 +314,18 @@ xyze_int8_t Stepper::count_direction{0}; A##3_STEP_WRITE(V); \ } -#define QUAD_ENDSTOP_APPLY_STEP(A,V) \ - if (separate_multi_axis) { \ - if (A##_HOME_TO_MIN) { \ - if (!(TEST(endstops.state(), A##_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##_motor) A##_STEP_WRITE(V); \ - if (!(TEST(endstops.state(), A##2_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \ - if (!(TEST(endstops.state(), A##3_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##3_motor) A##3_STEP_WRITE(V); \ - if (!(TEST(endstops.state(), A##4_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##4_motor) A##4_STEP_WRITE(V); \ - } \ - else { \ - if (!(TEST(endstops.state(), A##_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##_motor) A##_STEP_WRITE(V); \ - if (!(TEST(endstops.state(), A##2_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \ - if (!(TEST(endstops.state(), A##3_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##3_motor) A##3_STEP_WRITE(V); \ - if (!(TEST(endstops.state(), A##4_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##4_motor) A##4_STEP_WRITE(V); \ - } \ - } \ - else { \ - A##_STEP_WRITE(V); \ - A##2_STEP_WRITE(V); \ - A##3_STEP_WRITE(V); \ - A##4_STEP_WRITE(V); \ +#define QUAD_ENDSTOP_APPLY_STEP(A,V) \ + if (separate_multi_axis) { \ + if (!(TEST(endstops.state(), (TERN(A##_HOME_TO_MIN, A##_MIN, A##_MAX))) && count_direction[_AXIS(A)] < 0) && !locked_##A##_motor) A##_STEP_WRITE(V); \ + if (!(TEST(endstops.state(), (TERN(A##_HOME_TO_MIN, A##2_MIN, A##2_MAX))) && count_direction[_AXIS(A)] < 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \ + if (!(TEST(endstops.state(), (TERN(A##_HOME_TO_MIN, A##3_MIN, A##3_MAX))) && count_direction[_AXIS(A)] < 0) && !locked_##A##3_motor) A##3_STEP_WRITE(V); \ + if (!(TEST(endstops.state(), (TERN(A##_HOME_TO_MIN, A##4_MIN, A##4_MAX))) && count_direction[_AXIS(A)] < 0) && !locked_##A##4_motor) A##4_STEP_WRITE(V); \ + } \ + else { \ + A##_STEP_WRITE(V); \ + A##2_STEP_WRITE(V); \ + A##3_STEP_WRITE(V); \ + A##4_STEP_WRITE(V); \ } #define QUAD_SEPARATE_APPLY_STEP(A,V) \ @@ -378,7 +370,7 @@ xyze_int8_t Stepper::count_direction{0}; #else #define Y_APPLY_STEP(v,Q) do{ Y_STEP_WRITE(v); Y2_STEP_WRITE(v); }while(0) #endif -#else +#elif HAS_Y_AXIS #define Y_APPLY_DIR(v,Q) Y_DIR_WRITE(v) #define Y_APPLY_STEP(v,Q) Y_STEP_WRITE(v) #endif @@ -415,11 +407,24 @@ xyze_int8_t Stepper::count_direction{0}; #else #define Z_APPLY_STEP(v,Q) do{ Z_STEP_WRITE(v); Z2_STEP_WRITE(v); }while(0) #endif -#else +#elif HAS_Z_AXIS #define Z_APPLY_DIR(v,Q) Z_DIR_WRITE(v) #define Z_APPLY_STEP(v,Q) Z_STEP_WRITE(v) #endif +#if LINEAR_AXES >= 4 + #define I_APPLY_DIR(v,Q) I_DIR_WRITE(v) + #define I_APPLY_STEP(v,Q) I_STEP_WRITE(v) +#endif +#if LINEAR_AXES >= 5 + #define J_APPLY_DIR(v,Q) J_DIR_WRITE(v) + #define J_APPLY_STEP(v,Q) J_STEP_WRITE(v) +#endif +#if LINEAR_AXES >= 6 + #define K_APPLY_DIR(v,Q) K_DIR_WRITE(v) + #define K_APPLY_STEP(v,Q) K_STEP_WRITE(v) +#endif + #if DISABLED(MIXING_EXTRUDER) #define E_APPLY_STEP(v,Q) E_STEP_WRITE(stepper_extruder, v) #endif @@ -486,6 +491,18 @@ void Stepper::set_directions() { SET_STEP_DIR(Z); // C #endif + #if HAS_I_DIR + SET_STEP_DIR(I); // I + #endif + + #if HAS_J_DIR + SET_STEP_DIR(J); // J + #endif + + #if HAS_K_DIR + SET_STEP_DIR(K); // K + #endif + #if DISABLED(LIN_ADVANCE) #if ENABLED(MIXING_EXTRUDER) // Because this is valid for the whole block we don't know @@ -498,7 +515,7 @@ void Stepper::set_directions() { MIXER_STEPPER_LOOP(j) NORM_E_DIR(j); count_direction.e = 1; } - #else + #elif HAS_EXTRUDERS if (motor_direction(E_AXIS)) { REV_E_DIR(stepper_extruder); count_direction.e = -1; @@ -1584,7 +1601,7 @@ void Stepper::pulse_phase_isr() { const bool is_page = IS_PAGE(current_block); #if ENABLED(DIRECT_STEPPING) - + // TODO (DerAndere): Add support for LINEAR_AXES >= 4 if (is_page) { #if STEPPER_PAGE_FORMAT == SP_4x4D_128 @@ -1627,7 +1644,7 @@ void Stepper::pulse_phase_isr() { PAGE_PULSE_PREP(X); PAGE_PULSE_PREP(Y); PAGE_PULSE_PREP(Z); - PAGE_PULSE_PREP(E); + TERN_(HAS_EXTRUDERS, PAGE_PULSE_PREP(E)); page_step_state.segment_steps++; @@ -1660,7 +1677,7 @@ void Stepper::pulse_phase_isr() { PAGE_PULSE_PREP(X); PAGE_PULSE_PREP(Y); PAGE_PULSE_PREP(Z); - PAGE_PULSE_PREP(E); + TERN_(HAS_EXTRUDERS, PAGE_PULSE_PREP(E)); page_step_state.segment_steps++; @@ -1700,6 +1717,15 @@ void Stepper::pulse_phase_isr() { #if HAS_Z_STEP PULSE_PREP(Z); #endif + #if HAS_I_STEP + PULSE_PREP(I); + #endif + #if HAS_J_STEP + PULSE_PREP(J); + #endif + #if HAS_K_STEP + PULSE_PREP(K); + #endif #if EITHER(LIN_ADVANCE, MIXING_EXTRUDER) delta_error.e += advance_dividend.e; @@ -1735,6 +1761,15 @@ void Stepper::pulse_phase_isr() { #if HAS_Z_STEP PULSE_START(Z); #endif + #if HAS_I_STEP + PULSE_START(I); + #endif + #if HAS_J_STEP + PULSE_START(J); + #endif + #if HAS_K_STEP + PULSE_START(K); + #endif #if DISABLED(LIN_ADVANCE) #if ENABLED(MIXING_EXTRUDER) @@ -1764,6 +1799,15 @@ void Stepper::pulse_phase_isr() { #if HAS_Z_STEP PULSE_STOP(Z); #endif + #if HAS_I_STEP + PULSE_STOP(I); + #endif + #if HAS_J_STEP + PULSE_STOP(J); + #endif + #if HAS_K_STEP + PULSE_STOP(K); + #endif #if DISABLED(LIN_ADVANCE) #if ENABLED(MIXING_EXTRUDER) @@ -1798,6 +1842,7 @@ uint32_t Stepper::block_phase_isr() { // If current block is finished, reset pointer and finalize state if (step_events_completed >= step_event_count) { #if ENABLED(DIRECT_STEPPING) + // TODO (DerAndere): Add support for LINEAR_AXES >= 4 #if STEPPER_PAGE_FORMAT == SP_4x4D_128 #define PAGE_SEGMENT_UPDATE_POS(AXIS) \ count_position[_AXIS(AXIS)] += page_step_state.bd[_AXIS(AXIS)] - 128 * 7; @@ -2103,13 +2148,18 @@ uint32_t Stepper::block_phase_isr() { #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) 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); + LINEAR_AXIS_CODE( + 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.i) SBI(axis_bits, I_AXIS), + if (current_block->steps.j) SBI(axis_bits, J_AXIS), + if (current_block->steps.k) SBI(axis_bits, K_AXIS) + ); + //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 @@ -2439,6 +2489,15 @@ void Stepper::init() { Z4_DIR_INIT(); #endif #endif + #if HAS_I_DIR + I_DIR_INIT(); + #endif + #if HAS_J_DIR + J_DIR_INIT(); + #endif + #if HAS_K_DIR + K_DIR_INIT(); + #endif #if HAS_E0_DIR E0_DIR_INIT(); #endif @@ -2497,6 +2556,18 @@ void Stepper::init() { if (!Z_ENABLE_ON) Z4_ENABLE_WRITE(HIGH); #endif #endif + #if HAS_I_ENABLE + I_ENABLE_INIT(); + if (!I_ENABLE_ON) I_ENABLE_WRITE(HIGH); + #endif + #if HAS_J_ENABLE + J_ENABLE_INIT(); + if (!J_ENABLE_ON) J_ENABLE_WRITE(HIGH); + #endif + #if HAS_K_ENABLE + K_ENABLE_INIT(); + if (!K_ENABLE_ON) K_ENABLE_WRITE(HIGH); + #endif #if HAS_E0_ENABLE E0_ENABLE_INIT(); if (!E_ENABLE_ON) E0_ENABLE_WRITE(HIGH); @@ -2573,6 +2644,15 @@ void Stepper::init() { #endif AXIS_INIT(Z, Z); #endif + #if HAS_I_STEP + AXIS_INIT(I, I); + #endif + #if HAS_J_STEP + AXIS_INIT(J, J); + #endif + #if HAS_K_STEP + AXIS_INIT(K, K); + #endif #if E_STEPPERS && HAS_E0_STEP E_AXIS_INIT(0); @@ -2606,9 +2686,16 @@ void Stepper::init() { #endif // Init direction bits for first moves - set_directions((INVERT_X_DIR ? _BV(X_AXIS) : 0) - | (INVERT_Y_DIR ? _BV(Y_AXIS) : 0) - | (INVERT_Z_DIR ? _BV(Z_AXIS) : 0)); + set_directions(0 + LINEAR_AXIS_GANG( + | TERN0(INVERT_X_DIR, _BV(X_AXIS)), + | TERN0(INVERT_Y_DIR, _BV(Y_AXIS)), + | TERN0(INVERT_Z_DIR, _BV(Z_AXIS)), + | TERN0(INVERT_I_DIR, _BV(I_AXIS)), + | TERN0(INVERT_J_DIR, _BV(J_AXIS)), + | TERN0(INVERT_K_DIR, _BV(K_AXIS)) + ) + ); #if HAS_MOTOR_CURRENT_SPI || HAS_MOTOR_CURRENT_PWM initialized = true; @@ -2619,30 +2706,32 @@ void Stepper::init() { /** * Set the stepper positions directly in steps * - * The input is based on the typical per-axis XYZ steps. + * The input is based on the typical per-axis XYZE steps. * For CORE machines XYZ needs to be translated to ABC. * * This allows get_axis_position_mm to correctly - * derive the current XYZ position later on. + * derive the current XYZE position later on. */ -void Stepper::_set_position(const int32_t &a, const int32_t &b, const int32_t &c, const int32_t &e) { - #if CORE_IS_XY - // corexy positioning - // these equations follow the form of the dA and dB equations on https://www.corexy.com/theory.html - count_position.set(a + b, CORESIGN(a - b), c); - #elif CORE_IS_XZ - // corexz planning - count_position.set(a + c, b, CORESIGN(a - c)); - #elif CORE_IS_YZ - // coreyz planning - count_position.set(a, b + c, CORESIGN(b - c)); - #elif ENABLED(MARKFORGED_XY) - count_position.set(a - b, b, c); +void Stepper::_set_position(const abce_long_t &spos) { + #if EITHER(IS_CORE, MARKFORGED_XY) + #if CORE_IS_XY + // corexy positioning + // these equations follow the form of the dA and dB equations on https://www.corexy.com/theory.html + count_position.set(spos.a + spos.b, CORESIGN(spos.a - spos.b), spos.c); + #elif CORE_IS_XZ + // corexz planning + count_position.set(spos.a + spos.c, spos.b, CORESIGN(spos.a - spos.c)); + #elif CORE_IS_YZ + // coreyz planning + count_position.set(spos.a, spos.b + spos.c, CORESIGN(spos.b - spos.c)); + #elif ENABLED(MARKFORGED_XY) + count_position.set(spos.a - spos.b, spos.b, spos.c); + #endif + TERN_(HAS_EXTRUDERS, count_position.e = spos.e); #else // default non-h-bot planning - count_position.set(a, b, c); + count_position = spos; #endif - count_position.e = e; } /** @@ -2665,10 +2754,10 @@ int32_t Stepper::position(const AxisEnum axis) { } // Set the current position in steps -void Stepper::set_position(const int32_t &a, const int32_t &b, const int32_t &c, const int32_t &e) { +void Stepper::set_position(const xyze_long_t &spos) { planner.synchronize(); const bool was_enabled = suspend(); - _set_position(a, b, c, e); + _set_position(spos); if (was_enabled) wake_up(); } @@ -2736,17 +2825,24 @@ int32_t Stepper::triggered_position(const AxisEnum axis) { return v; } +#if ANY(CORE_IS_XZ, CORE_IS_YZ, DELTA) + #define USES_ABC 1 +#endif +#if ANY(USES_ABC, MARKFORGED_XY, IS_SCARA) + #define USES_AB 1 +#endif + void Stepper::report_a_position(const xyz_long_t &pos) { - #if ANY(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY, DELTA, IS_SCARA) - SERIAL_ECHOPAIR(STR_COUNT_A, pos.x, " B:", pos.y); - #else - SERIAL_ECHOPAIR_P(PSTR(STR_COUNT_X), pos.x, SP_Y_LBL, pos.y); - #endif - #if ANY(CORE_IS_XZ, CORE_IS_YZ, DELTA) - SERIAL_ECHOLNPAIR(" C:", pos.z); - #else - SERIAL_ECHOLNPAIR_P(SP_Z_LBL, pos.z); - #endif + SERIAL_ECHOLNPAIR_P( + LIST_N(DOUBLE(LINEAR_AXES), + TERN(USES_AB, PSTR(STR_COUNT_A), PSTR(STR_COUNT_X)), pos.x, + TERN(USES_AB, PSTR("B:"), SP_Y_LBL), pos.y, + TERN(USES_ABC, PSTR("C:"), SP_Z_LBL), pos.z, + SP_I_LBL, pos.i, + SP_J_LBL, pos.j, + SP_K_LBL, pos.k + ) + ); } void Stepper::report_positions() { @@ -2854,9 +2950,7 @@ void Stepper::report_positions() { // No other ISR should ever interrupt this! void Stepper::do_babystep(const AxisEnum axis, const bool direction) { - #if DISABLED(INTEGRATED_BABYSTEPPING) - cli(); - #endif + IF_DISABLED(INTEGRATED_BABYSTEPPING, cli()); switch (axis) { @@ -2900,35 +2994,90 @@ void Stepper::report_positions() { ENABLE_AXIS_X(); ENABLE_AXIS_Y(); ENABLE_AXIS_Z(); + ENABLE_AXIS_I(); + ENABLE_AXIS_J(); + ENABLE_AXIS_K(); DIR_WAIT_BEFORE(); - const xyz_byte_t old_dir = { X_DIR_READ(), Y_DIR_READ(), Z_DIR_READ() }; + const xyz_byte_t old_dir = LINEAR_AXIS_ARRAY(X_DIR_READ(), Y_DIR_READ(), Z_DIR_READ(), I_DIR_READ(), J_DIR_READ(), K_DIR_READ()); X_DIR_WRITE(INVERT_X_DIR ^ z_direction); - Y_DIR_WRITE(INVERT_Y_DIR ^ z_direction); - Z_DIR_WRITE(INVERT_Z_DIR ^ z_direction); + #ifdef Y_DIR_WRITE + Y_DIR_WRITE(INVERT_Y_DIR ^ z_direction); + #endif + #ifdef Z_DIR_WRITE + Z_DIR_WRITE(INVERT_Z_DIR ^ z_direction); + #endif + #ifdef I_DIR_WRITE + I_DIR_WRITE(INVERT_I_DIR ^ z_direction); + #endif + #ifdef J_DIR_WRITE + J_DIR_WRITE(INVERT_J_DIR ^ z_direction); + #endif + #ifdef K_DIR_WRITE + K_DIR_WRITE(INVERT_K_DIR ^ z_direction); + #endif DIR_WAIT_AFTER(); _SAVE_START(); X_STEP_WRITE(!INVERT_X_STEP_PIN); - Y_STEP_WRITE(!INVERT_Y_STEP_PIN); - Z_STEP_WRITE(!INVERT_Z_STEP_PIN); + #ifdef Y_STEP_WRITE + Y_STEP_WRITE(!INVERT_Y_STEP_PIN); + #endif + #ifdef Z_STEP_WRITE + Z_STEP_WRITE(!INVERT_Z_STEP_PIN); + #endif + #ifdef I_STEP_WRITE + I_STEP_WRITE(!INVERT_I_STEP_PIN); + #endif + #ifdef J_STEP_WRITE + J_STEP_WRITE(!INVERT_J_STEP_PIN); + #endif + #ifdef K_STEP_WRITE + K_STEP_WRITE(!INVERT_K_STEP_PIN); + #endif _PULSE_WAIT(); X_STEP_WRITE(INVERT_X_STEP_PIN); - Y_STEP_WRITE(INVERT_Y_STEP_PIN); - Z_STEP_WRITE(INVERT_Z_STEP_PIN); + #ifdef Y_STEP_WRITE + Y_STEP_WRITE(INVERT_Y_STEP_PIN); + #endif + #ifdef Z_STEP_WRITE + Z_STEP_WRITE(INVERT_Z_STEP_PIN); + #endif + #ifdef I_STEP_WRITE + I_STEP_WRITE(INVERT_I_STEP_PIN); + #endif + #ifdef J_STEP_WRITE + J_STEP_WRITE(INVERT_J_STEP_PIN); + #endif + #ifdef K_STEP_WRITE + K_STEP_WRITE(INVERT_K_STEP_PIN); + #endif // Restore direction bits EXTRA_DIR_WAIT_BEFORE(); X_DIR_WRITE(old_dir.x); - Y_DIR_WRITE(old_dir.y); - Z_DIR_WRITE(old_dir.z); + #ifdef Y_DIR_WRITE + Y_DIR_WRITE(old_dir.y); + #endif + #ifdef Z_DIR_WRITE + Z_DIR_WRITE(old_dir.z); + #endif + #ifdef I_DIR_WRITE + I_DIR_WRITE(old_dir.i); + #endif + #ifdef J_DIR_WRITE + J_DIR_WRITE(old_dir.j); + #endif + #ifdef K_DIR_WRITE + K_DIR_WRITE(old_dir.k); + #endif EXTRA_DIR_WAIT_AFTER(); @@ -2936,12 +3085,20 @@ void Stepper::report_positions() { } break; + #if LINEAR_AXES >= 4 + case I_AXIS: BABYSTEP_AXIS(I, 0, direction); break; + #endif + #if LINEAR_AXES >= 5 + case J_AXIS: BABYSTEP_AXIS(J, 0, direction); break; + #endif + #if LINEAR_AXES >= 6 + case K_AXIS: BABYSTEP_AXIS(K, 0, direction); break; + #endif + default: break; } - #if DISABLED(INTEGRATED_BABYSTEPPING) - sei(); - #endif + IF_DISABLED(INTEGRATED_BABYSTEPPING, sei()); } #endif // BABYSTEPPING @@ -3276,6 +3433,15 @@ void Stepper::report_positions() { #if HAS_E7_MS_PINS case 10: WRITE(E7_MS1_PIN, ms1); break; #endif + #if HAS_I_MICROSTEPS + case 11: WRITE(I_MS1_PIN, ms1); break + #endif + #if HAS_J_MICROSTEPS + case 12: WRITE(J_MS1_PIN, ms1); break + #endif + #if HAS_K_MICROSTEPS + case 13: WRITE(K_MS1_PIN, ms1); break + #endif } if (ms2 >= 0) switch (driver) { #if HAS_X_MS_PINS || HAS_X2_MS_PINS @@ -3338,6 +3504,15 @@ void Stepper::report_positions() { #if HAS_E7_MS_PINS case 10: WRITE(E7_MS2_PIN, ms2); break; #endif + #if HAS_I_M_PINS + case 11: WRITE(I_MS2_PIN, ms2); break + #endif + #if HAS_J_M_PINS + case 12: WRITE(J_MS2_PIN, ms2); break + #endif + #if HAS_K_M_PINS + case 13: WRITE(K_MS2_PIN, ms2); break + #endif } if (ms3 >= 0) switch (driver) { #if HAS_X_MS_PINS || HAS_X2_MS_PINS @@ -3456,6 +3631,24 @@ void Stepper::report_positions() { PIN_CHAR(Z_MS3); #endif #endif + #if HAS_I_MS_PINS + MS_LINE(I); + #if PIN_EXISTS(I_MS3) + PIN_CHAR(I_MS3); + #endif + #endif + #if HAS_J_MS_PINS + MS_LINE(J); + #if PIN_EXISTS(J_MS3) + PIN_CHAR(J_MS3); + #endif + #endif + #if HAS_K_MS_PINS + MS_LINE(K); + #if PIN_EXISTS(K_MS3) + PIN_CHAR(K_MS3); + #endif + #endif #if HAS_E0_MS_PINS MS_LINE(E0); #if PIN_EXISTS(E0_MS3) diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index 020f72e9e6854..236ba5ee98471 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -133,36 +133,38 @@ #endif +// If linear advance is disabled, the loop also handles them +#if DISABLED(LIN_ADVANCE) && ENABLED(MIXING_EXTRUDER) + #define ISR_MIXING_STEPPER_CYCLES ((MIXING_STEPPERS) * (ISR_STEPPER_CYCLES)) +#else + #define ISR_MIXING_STEPPER_CYCLES 0UL +#endif + // Add time for each stepper #if HAS_X_STEP - #define ISR_X_STEPPER_CYCLES ISR_STEPPER_CYCLES -#else - #define ISR_X_STEPPER_CYCLES 0UL + #define ISR_X_STEPPER_CYCLES ISR_STEPPER_CYCLES #endif #if HAS_Y_STEP - #define ISR_Y_STEPPER_CYCLES ISR_STEPPER_CYCLES -#else - #define ISR_START_Y_STEPPER_CYCLES 0UL - #define ISR_Y_STEPPER_CYCLES 0UL + #define ISR_Y_STEPPER_CYCLES ISR_STEPPER_CYCLES #endif #if HAS_Z_STEP - #define ISR_Z_STEPPER_CYCLES ISR_STEPPER_CYCLES -#else - #define ISR_Z_STEPPER_CYCLES 0UL + #define ISR_Z_STEPPER_CYCLES ISR_STEPPER_CYCLES #endif - -// E is always interpolated, even for mixing extruders -#define ISR_E_STEPPER_CYCLES ISR_STEPPER_CYCLES - -// If linear advance is disabled, the loop also handles them -#if DISABLED(LIN_ADVANCE) && ENABLED(MIXING_EXTRUDER) - #define ISR_MIXING_STEPPER_CYCLES ((MIXING_STEPPERS) * (ISR_STEPPER_CYCLES)) -#else - #define ISR_MIXING_STEPPER_CYCLES 0UL +#if HAS_I_STEP + #define ISR_I_STEPPER_CYCLES ISR_STEPPER_CYCLES +#endif +#if HAS_J_STEP + #define ISR_J_STEPPER_CYCLES ISR_STEPPER_CYCLES +#endif +#if HAS_K_STEP + #define ISR_K_STEPPER_CYCLES ISR_STEPPER_CYCLES +#endif +#if HAS_EXTRUDERS + #define ISR_E_STEPPER_CYCLES ISR_STEPPER_CYCLES // E is always interpolated, even for mixing extruders #endif // And the total minimum loop time, not including the base -#define MIN_ISR_LOOP_CYCLES (ISR_X_STEPPER_CYCLES + ISR_Y_STEPPER_CYCLES + ISR_Z_STEPPER_CYCLES + ISR_E_STEPPER_CYCLES + ISR_MIXING_STEPPER_CYCLES) +#define MIN_ISR_LOOP_CYCLES (ISR_MIXING_STEPPER_CYCLES LOGICAL_AXIS_GANG(+ ISR_E_STEPPER_CYCLES, + ISR_X_STEPPER_CYCLES, + ISR_Y_STEPPER_CYCLES, + ISR_Z_STEPPER_CYCLES, + ISR_I_STEPPER_CYCLES, + ISR_J_STEPPER_CYCLES, + ISR_K_STEPPER_CYCLES)) // Calculate the minimum MPU cycles needed per pulse to enforce, limited to the max stepper rate #define _MIN_STEPPER_PULSE_CYCLES(N) _MAX(uint32_t((F_CPU) / (MAXIMUM_STEPPER_RATE)), ((F_CPU) / 500000UL) * (N)) @@ -433,8 +435,7 @@ class Stepper { static int32_t position(const AxisEnum axis); // 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); - static inline void set_position(const xyze_long_t &abce) { set_position(abce.a, abce.b, abce.c, abce.e); } + static void set_position(const xyze_long_t &spos); static void set_axis_position(const AxisEnum a, const int32_t &v); // Report the positions of the steppers, in steps @@ -530,8 +531,7 @@ class Stepper { private: // 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); } + static void _set_position(const abce_long_t &spos); FORCE_INLINE static uint32_t calc_timer_interval(uint32_t step_rate, uint8_t *loops) { uint32_t timer; diff --git a/Marlin/src/module/stepper/L64xx.cpp b/Marlin/src/module/stepper/L64xx.cpp index 004e17a3fdbed..27816fb4f7429 100644 --- a/Marlin/src/module/stepper/L64xx.cpp +++ b/Marlin/src/module/stepper/L64xx.cpp @@ -55,6 +55,15 @@ #if AXIS_IS_L64XX(Z4) L64XX_CLASS(Z4) stepperZ4(L6470_CHAIN_SS_PIN); #endif +#if AXIS_IS_L64XX(I) + L64XX_CLASS(I) stepperI(L6470_CHAIN_SS_PIN); +#endif +#if AXIS_IS_L64XX(J) + L64XX_CLASS(J) stepperJ(L6470_CHAIN_SS_PIN); +#endif +#if AXIS_IS_L64XX(K) + L64XX_CLASS(K) stepperK(L6470_CHAIN_SS_PIN); +#endif #if AXIS_IS_L64XX(E0) L64XX_CLASS(E0) stepperE0(L6470_CHAIN_SS_PIN); #endif @@ -199,6 +208,15 @@ void L64XX_Marlin::init_to_defaults() { #if AXIS_IS_L64XX(Z4) L6470_INIT_CHIP(Z4); #endif + #if AXIS_IS_L64XX(I) + L6470_INIT_CHIP(I); + #endif + #if AXIS_IS_L64XX(J) + L6470_INIT_CHIP(J); + #endif + #if AXIS_IS_L64XX(K) + L6470_INIT_CHIP(K); + #endif #if AXIS_IS_L64XX(E0) L6470_INIT_CHIP(E0); #endif diff --git a/Marlin/src/module/stepper/L64xx.h b/Marlin/src/module/stepper/L64xx.h index 9c8b0b1bddeee..9f7e6623b1400 100644 --- a/Marlin/src/module/stepper/L64xx.h +++ b/Marlin/src/module/stepper/L64xx.h @@ -206,6 +206,66 @@ #define DISABLE_STEPPER_Z4() stepperZ4.free() #endif +// I Stepper +#if AXIS_IS_L64XX(I) + extern L64XX_CLASS(I) stepperI; + #define I_ENABLE_INIT() NOOP + #define I_ENABLE_WRITE(STATE) (STATE ? stepperI.hardStop() : stepperI.free()) + #define I_ENABLE_READ() (stepperI.getStatus() & STATUS_HIZ) + #if AXIS_DRIVER_TYPE_I(L6474) + #define I_DIR_INIT() SET_OUTPUT(I_DIR_PIN) + #define I_DIR_WRITE(STATE) L6474_DIR_WRITE(I, STATE) + #define I_DIR_READ() READ(I_DIR_PIN) + #else + #define I_DIR_INIT() NOOP + #define I_DIR_WRITE(STATE) L64XX_DIR_WRITE(I, STATE) + #define I_DIR_READ() (stepper##I.getStatus() & STATUS_DIR); + #if AXIS_DRIVER_TYPE_I(L6470) + #define DISABLE_STEPPER_I() stepperI.free() + #endif + #endif +#endif + +// J Stepper +#if AXIS_IS_L64XX(J) + extern L64XX_CLASS(J) stepperJ; + #define J_ENABLE_INIT() NOOP + #define J_ENABLE_WRITE(STATE) (STATE ? stepperJ.hardStop() : stepperJ.free()) + #define J_ENABLE_READ() (stepperJ.getStatus() & STATUS_HIZ) + #if AXIS_DRIVER_TYPE_J(L6474) + #define J_DIR_INIT() SET_OUTPUT(J_DIR_PIN) + #define J_DIR_WRITE(STATE) L6474_DIR_WRITE(J, STATE) + #define J_DIR_READ() READ(J_DIR_PIN) + #else + #define J_DIR_INIT() NOOP + #define J_DIR_WRITE(STATE) L64XX_DIR_WRITE(J, STATE) + #define J_DIR_READ() (stepper##J.getStatus() & STATUS_DIR); + #if AXIS_DRIVER_TYPE_J(L6470) + #define DISABLE_STEPPER_J() stepperJ.free() + #endif + #endif +#endif + +// K Stepper +#if AXIS_IS_L64XX(K) + extern L64XX_CLASS(K) stepperK; + #define K_ENABLE_INIT() NOOP + #define K_ENABLE_WRITE(STATE) (STATE ? stepperK.hardStop() : stepperK.free()) + #define K_ENABLE_READ() (stepperK.getStatus() & STATUS_HIZ) + #if AXIS_DRIVER_TYPE_K(L6474) + #define K_DIR_INIT() SET_OUTPUT(K_DIR_PIN) + #define K_DIR_WRITE(STATE) L6474_DIR_WRITE(K, STATE) + #define K_DIR_READ() READ(K_DIR_PIN) + #else + #define K_DIR_INIT() NOOP + #define K_DIR_WRITE(STATE) L64XX_DIR_WRITE(K, STATE) + #define K_DIR_READ() (stepper##K.getStatus() & STATUS_DIR); + #if AXIS_DRIVER_TYPE_K(L6470) + #define DISABLE_STEPPER_K() stepperK.free() + #endif + #endif +#endif + // E0 Stepper #if AXIS_IS_L64XX(E0) extern L64XX_CLASS(E0) stepperE0; diff --git a/Marlin/src/module/stepper/TMC26X.cpp b/Marlin/src/module/stepper/TMC26X.cpp index 926f1a4e089f2..26f91bfeb9da1 100644 --- a/Marlin/src/module/stepper/TMC26X.cpp +++ b/Marlin/src/module/stepper/TMC26X.cpp @@ -60,6 +60,15 @@ #if AXIS_DRIVER_TYPE_Z4(TMC26X) _TMC26X_DEFINE(Z4); #endif +#if AXIS_DRIVER_TYPE_I(TMC26X) + _TMC26X_DEFINE(I); +#endif +#if AXIS_DRIVER_TYPE_J(TMC26X) + _TMC26X_DEFINE(J); +#endif +#if AXIS_DRIVER_TYPE_K(TMC26X) + _TMC26X_DEFINE(K); +#endif #if AXIS_DRIVER_TYPE_E0(TMC26X) _TMC26X_DEFINE(E0); #endif @@ -115,6 +124,15 @@ void tmc26x_init_to_defaults() { #if AXIS_DRIVER_TYPE_Z4(TMC26X) _TMC26X_INIT(Z4); #endif + #if AXIS_DRIVER_TYPE_I(TMC26X) + _TMC26X_INIT(I); + #endif + #if AXIS_DRIVER_TYPE_J(TMC26X) + _TMC26X_INIT(J); + #endif + #if AXIS_DRIVER_TYPE_K(TMC26X) + _TMC26X_INIT(K); + #endif #if AXIS_DRIVER_TYPE_E0(TMC26X) _TMC26X_INIT(E0); #endif diff --git a/Marlin/src/module/stepper/TMC26X.h b/Marlin/src/module/stepper/TMC26X.h index 547eb6521f19e..988bebe0f20f0 100644 --- a/Marlin/src/module/stepper/TMC26X.h +++ b/Marlin/src/module/stepper/TMC26X.h @@ -99,6 +99,30 @@ void tmc26x_init_to_defaults(); #define Z4_ENABLE_READ() stepperZ4.isEnabled() #endif +// I Stepper +#if HAS_I_ENABLE && AXIS_DRIVER_TYPE_I(TMC26X) + extern TMC26XStepper stepperI; + #define I_ENABLE_INIT() NOOP + #define I_ENABLE_WRITE(STATE) stepperI.setEnabled(STATE) + #define I_ENABLE_READ() stepperI.isEnabled() +#endif + +// J Stepper +#if HAS_J_ENABLE && AXIS_DRIVER_TYPE_J(TMC26X) + extern TMC26XStepper stepperJ; + #define J_ENABLE_INIT() NOOP + #define J_ENABLE_WRITE(STATE) stepperJ.setEnabled(STATE) + #define J_ENABLE_READ() stepperJ.isEnabled() +#endif + +// K Stepper +#if HAS_K_ENABLE && AXIS_DRIVER_TYPE_K(TMC26X) + extern TMC26XStepper stepperK; + #define K_ENABLE_INIT() NOOP + #define K_ENABLE_WRITE(STATE) stepperK.setEnabled(STATE) + #define K_ENABLE_READ() stepperK.isEnabled() +#endif + // E0 Stepper #if AXIS_DRIVER_TYPE_E0(TMC26X) extern TMC26XStepper stepperE0; diff --git a/Marlin/src/module/stepper/indirection.cpp b/Marlin/src/module/stepper/indirection.cpp index 6297d83366951..e44496d0224c6 100644 --- a/Marlin/src/module/stepper/indirection.cpp +++ b/Marlin/src/module/stepper/indirection.cpp @@ -37,9 +37,7 @@ void restore_stepper_drivers() { } void reset_stepper_drivers() { - #if HAS_DRIVER(TMC26X) - tmc26x_init_to_defaults(); - #endif + TERN_(HAS_TMC26X, tmc26x_init_to_defaults()); TERN_(HAS_L64XX, L64xxManager.init_to_defaults()); TERN_(HAS_TRINAMIC_CONFIG, reset_trinamic_drivers()); } diff --git a/Marlin/src/module/stepper/indirection.h b/Marlin/src/module/stepper/indirection.h index e72d793ca6bc9..08d0be0b3153e 100644 --- a/Marlin/src/module/stepper/indirection.h +++ b/Marlin/src/module/stepper/indirection.h @@ -36,7 +36,7 @@ #include "L64xx.h" #endif -#if HAS_DRIVER(TMC26X) +#if HAS_TMC26X #include "TMC26X.h" #endif @@ -65,38 +65,42 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #define X_STEP_READ() bool(READ(X_STEP_PIN)) // Y Stepper -#ifndef Y_ENABLE_INIT - #define Y_ENABLE_INIT() SET_OUTPUT(Y_ENABLE_PIN) - #define Y_ENABLE_WRITE(STATE) WRITE(Y_ENABLE_PIN,STATE) - #define Y_ENABLE_READ() bool(READ(Y_ENABLE_PIN)) -#endif -#ifndef Y_DIR_INIT - #define Y_DIR_INIT() SET_OUTPUT(Y_DIR_PIN) - #define Y_DIR_WRITE(STATE) WRITE(Y_DIR_PIN,STATE) - #define Y_DIR_READ() bool(READ(Y_DIR_PIN)) -#endif -#define Y_STEP_INIT() SET_OUTPUT(Y_STEP_PIN) -#ifndef Y_STEP_WRITE - #define Y_STEP_WRITE(STATE) WRITE(Y_STEP_PIN,STATE) +#if HAS_Y_AXIS + #ifndef Y_ENABLE_INIT + #define Y_ENABLE_INIT() SET_OUTPUT(Y_ENABLE_PIN) + #define Y_ENABLE_WRITE(STATE) WRITE(Y_ENABLE_PIN,STATE) + #define Y_ENABLE_READ() bool(READ(Y_ENABLE_PIN)) + #endif + #ifndef Y_DIR_INIT + #define Y_DIR_INIT() SET_OUTPUT(Y_DIR_PIN) + #define Y_DIR_WRITE(STATE) WRITE(Y_DIR_PIN,STATE) + #define Y_DIR_READ() bool(READ(Y_DIR_PIN)) + #endif + #define Y_STEP_INIT() SET_OUTPUT(Y_STEP_PIN) + #ifndef Y_STEP_WRITE + #define Y_STEP_WRITE(STATE) WRITE(Y_STEP_PIN,STATE) + #endif + #define Y_STEP_READ() bool(READ(Y_STEP_PIN)) #endif -#define Y_STEP_READ() bool(READ(Y_STEP_PIN)) // Z Stepper -#ifndef Z_ENABLE_INIT - #define Z_ENABLE_INIT() SET_OUTPUT(Z_ENABLE_PIN) - #define Z_ENABLE_WRITE(STATE) WRITE(Z_ENABLE_PIN,STATE) - #define Z_ENABLE_READ() bool(READ(Z_ENABLE_PIN)) -#endif -#ifndef Z_DIR_INIT - #define Z_DIR_INIT() SET_OUTPUT(Z_DIR_PIN) - #define Z_DIR_WRITE(STATE) WRITE(Z_DIR_PIN,STATE) - #define Z_DIR_READ() bool(READ(Z_DIR_PIN)) -#endif -#define Z_STEP_INIT() SET_OUTPUT(Z_STEP_PIN) -#ifndef Z_STEP_WRITE - #define Z_STEP_WRITE(STATE) WRITE(Z_STEP_PIN,STATE) +#if HAS_Z_AXIS + #ifndef Z_ENABLE_INIT + #define Z_ENABLE_INIT() SET_OUTPUT(Z_ENABLE_PIN) + #define Z_ENABLE_WRITE(STATE) WRITE(Z_ENABLE_PIN,STATE) + #define Z_ENABLE_READ() bool(READ(Z_ENABLE_PIN)) + #endif + #ifndef Z_DIR_INIT + #define Z_DIR_INIT() SET_OUTPUT(Z_DIR_PIN) + #define Z_DIR_WRITE(STATE) WRITE(Z_DIR_PIN,STATE) + #define Z_DIR_READ() bool(READ(Z_DIR_PIN)) + #endif + #define Z_STEP_INIT() SET_OUTPUT(Z_STEP_PIN) + #ifndef Z_STEP_WRITE + #define Z_STEP_WRITE(STATE) WRITE(Z_STEP_PIN,STATE) + #endif + #define Z_STEP_READ() bool(READ(Z_STEP_PIN)) #endif -#define Z_STEP_READ() bool(READ(Z_STEP_PIN)) // X2 Stepper #if HAS_X2_ENABLE @@ -201,6 +205,63 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #define Z4_DIR_WRITE(STATE) NOOP #endif +// I Stepper +#if LINEAR_AXES >= 4 + #ifndef I_ENABLE_INIT + #define I_ENABLE_INIT() SET_OUTPUT(I_ENABLE_PIN) + #define I_ENABLE_WRITE(STATE) WRITE(I_ENABLE_PIN,STATE) + #define I_ENABLE_READ() bool(READ(I_ENABLE_PIN)) + #endif + #ifndef I_DIR_INIT + #define I_DIR_INIT() SET_OUTPUT(I_DIR_PIN) + #define I_DIR_WRITE(STATE) WRITE(I_DIR_PIN,STATE) + #define I_DIR_READ() bool(READ(I_DIR_PIN)) + #endif + #define I_STEP_INIT() SET_OUTPUT(I_STEP_PIN) + #ifndef I_STEP_WRITE + #define I_STEP_WRITE(STATE) WRITE(I_STEP_PIN,STATE) + #endif + #define I_STEP_READ() bool(READ(I_STEP_PIN)) +#endif + +// J Stepper +#if LINEAR_AXES >= 5 + #ifndef J_ENABLE_INIT + #define J_ENABLE_INIT() SET_OUTPUT(J_ENABLE_PIN) + #define J_ENABLE_WRITE(STATE) WRITE(J_ENABLE_PIN,STATE) + #define J_ENABLE_READ() bool(READ(J_ENABLE_PIN)) + #endif + #ifndef J_DIR_INIT + #define J_DIR_INIT() SET_OUTPUT(J_DIR_PIN) + #define J_DIR_WRITE(STATE) WRITE(J_DIR_PIN,STATE) + #define J_DIR_READ() bool(READ(J_DIR_PIN)) + #endif + #define J_STEP_INIT() SET_OUTPUT(J_STEP_PIN) + #ifndef J_STEP_WRITE + #define J_STEP_WRITE(STATE) WRITE(J_STEP_PIN,STATE) + #endif + #define J_STEP_READ() bool(READ(J_STEP_PIN)) +#endif + +// K Stepper +#if LINEAR_AXES >= 6 + #ifndef K_ENABLE_INIT + #define K_ENABLE_INIT() SET_OUTPUT(K_ENABLE_PIN) + #define K_ENABLE_WRITE(STATE) WRITE(K_ENABLE_PIN,STATE) + #define K_ENABLE_READ() bool(READ(K_ENABLE_PIN)) + #endif + #ifndef K_DIR_INIT + #define K_DIR_INIT() SET_OUTPUT(K_DIR_PIN) + #define K_DIR_WRITE(STATE) WRITE(K_DIR_PIN,STATE) + #define K_DIR_READ() bool(READ(K_DIR_PIN)) + #endif + #define K_STEP_INIT() SET_OUTPUT(K_STEP_PIN) + #ifndef K_STEP_WRITE + #define K_STEP_WRITE(STATE) WRITE(K_STEP_PIN,STATE) + #endif + #define K_STEP_READ() bool(READ(K_STEP_PIN)) +#endif + // E0 Stepper #ifndef E0_ENABLE_INIT #define E0_ENABLE_INIT() SET_OUTPUT(E0_ENABLE_PIN) @@ -418,7 +479,7 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #define REV_E_DIR(E) do{ E0_DIR_WRITE(E ? !INVERT_E0_DIR : INVERT_E0_DIR); }while(0) #endif -#elif HAS_PRUSA_MMU2 +#elif HAS_PRUSA_MMU2 // One multiplexed stepper driver #define E_STEP_WRITE(E,V) E0_STEP_WRITE(V) #define NORM_E_DIR(E) E0_DIR_WRITE(!INVERT_E0_DIR) @@ -584,6 +645,11 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #endif +#elif ENABLED(E_DUAL_STEPPER_DRIVERS) + #define E_STEP_WRITE(E,V) do{ E0_STEP_WRITE(V); E1_STEP_WRITE(V); }while(0) + #define NORM_E_DIR(E) do{ E0_DIR_WRITE(!INVERT_E0_DIR); E1_DIR_WRITE(!INVERT_E0_DIR ^ ENABLED(INVERT_E1_VS_E0_DIR)); }while(0) + #define REV_E_DIR(E) do{ E0_DIR_WRITE( INVERT_E0_DIR); E1_DIR_WRITE( INVERT_E0_DIR ^ ENABLED(INVERT_E1_VS_E0_DIR)); }while(0) + #elif E_STEPPERS #define E_STEP_WRITE(E,V) E0_STEP_WRITE(V) #define NORM_E_DIR(E) E0_DIR_WRITE(!INVERT_E0_DIR) @@ -720,6 +786,51 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #endif #endif +#ifndef ENABLE_STEPPER_I + #if HAS_I_ENABLE + #define ENABLE_STEPPER_I() I_ENABLE_WRITE( I_ENABLE_ON) + #else + #define ENABLE_STEPPER_I() NOOP + #endif +#endif +#ifndef DISABLE_STEPPER_I + #if HAS_I_ENABLE + #define DISABLE_STEPPER_I() I_ENABLE_WRITE(!I_ENABLE_ON) + #else + #define DISABLE_STEPPER_I() NOOP + #endif +#endif + +#ifndef ENABLE_STEPPER_J + #if HAS_J_ENABLE + #define ENABLE_STEPPER_J() J_ENABLE_WRITE( J_ENABLE_ON) + #else + #define ENABLE_STEPPER_J() NOOP + #endif +#endif +#ifndef DISABLE_STEPPER_J + #if HAS_J_ENABLE + #define DISABLE_STEPPER_J() J_ENABLE_WRITE(!J_ENABLE_ON) + #else + #define DISABLE_STEPPER_J() NOOP + #endif +#endif + +#ifndef ENABLE_STEPPER_K + #if HAS_K_ENABLE + #define ENABLE_STEPPER_K() K_ENABLE_WRITE( K_ENABLE_ON) + #else + #define ENABLE_STEPPER_K() NOOP + #endif +#endif +#ifndef DISABLE_STEPPER_K + #if HAS_K_ENABLE + #define DISABLE_STEPPER_K() K_ENABLE_WRITE(!K_ENABLE_ON) + #else + #define DISABLE_STEPPER_K() NOOP + #endif +#endif + #ifndef ENABLE_STEPPER_E0 #if HAS_E0_ENABLE #define ENABLE_STEPPER_E0() E0_ENABLE_WRITE( E_ENABLE_ON) @@ -857,10 +968,22 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #define ENABLE_AXIS_X() if (SHOULD_ENABLE(x)) { ENABLE_STEPPER_X(); ENABLE_STEPPER_X2(); AFTER_CHANGE(x, true); } #define DISABLE_AXIS_X() if (SHOULD_DISABLE(x)) { DISABLE_STEPPER_X(); DISABLE_STEPPER_X2(); AFTER_CHANGE(x, false); set_axis_untrusted(X_AXIS); } -#define ENABLE_AXIS_Y() if (SHOULD_ENABLE(y)) { ENABLE_STEPPER_Y(); ENABLE_STEPPER_Y2(); AFTER_CHANGE(y, true); } -#define DISABLE_AXIS_Y() if (SHOULD_DISABLE(y)) { DISABLE_STEPPER_Y(); DISABLE_STEPPER_Y2(); AFTER_CHANGE(y, false); set_axis_untrusted(Y_AXIS); } -#define ENABLE_AXIS_Z() if (SHOULD_ENABLE(z)) { ENABLE_STEPPER_Z(); ENABLE_STEPPER_Z2(); ENABLE_STEPPER_Z3(); ENABLE_STEPPER_Z4(); AFTER_CHANGE(z, true); } -#define DISABLE_AXIS_Z() if (SHOULD_DISABLE(z)) { DISABLE_STEPPER_Z(); DISABLE_STEPPER_Z2(); DISABLE_STEPPER_Z3(); DISABLE_STEPPER_Z4(); AFTER_CHANGE(z, false); set_axis_untrusted(Z_AXIS); Z_RESET(); } + +#if HAS_Y_AXIS + #define ENABLE_AXIS_Y() if (SHOULD_ENABLE(y)) { ENABLE_STEPPER_Y(); ENABLE_STEPPER_Y2(); AFTER_CHANGE(y, true); } + #define DISABLE_AXIS_Y() if (SHOULD_DISABLE(y)) { DISABLE_STEPPER_Y(); DISABLE_STEPPER_Y2(); AFTER_CHANGE(y, false); set_axis_untrusted(Y_AXIS); } +#else + #define ENABLE_AXIS_Y() NOOP + #define DISABLE_AXIS_Y() NOOP +#endif + +#if HAS_Z_AXIS + #define ENABLE_AXIS_Z() if (SHOULD_ENABLE(z)) { ENABLE_STEPPER_Z(); ENABLE_STEPPER_Z2(); ENABLE_STEPPER_Z3(); ENABLE_STEPPER_Z4(); AFTER_CHANGE(z, true); } + #define DISABLE_AXIS_Z() if (SHOULD_DISABLE(z)) { DISABLE_STEPPER_Z(); DISABLE_STEPPER_Z2(); DISABLE_STEPPER_Z3(); DISABLE_STEPPER_Z4(); AFTER_CHANGE(z, false); set_axis_untrusted(Z_AXIS); Z_RESET(); } +#else + #define ENABLE_AXIS_Z() NOOP + #define DISABLE_AXIS_Z() NOOP +#endif #ifdef Z_IDLE_HEIGHT #define Z_RESET() do{ current_position.z = Z_IDLE_HEIGHT; sync_plan_position(); }while(0) @@ -868,11 +991,34 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #define Z_RESET() #endif +#if LINEAR_AXES >= 4 + #define ENABLE_AXIS_I() if (SHOULD_ENABLE(i)) { ENABLE_STEPPER_I(); AFTER_CHANGE(i, true); } + #define DISABLE_AXIS_I() if (SHOULD_DISABLE(i)) { DISABLE_STEPPER_I(); AFTER_CHANGE(i, false); set_axis_untrusted(I_AXIS); } +#else + #define ENABLE_AXIS_I() NOOP + #define DISABLE_AXIS_I() NOOP +#endif +#if LINEAR_AXES >= 5 + #define ENABLE_AXIS_J() if (SHOULD_ENABLE(j)) { ENABLE_STEPPER_J(); AFTER_CHANGE(j, true); } + #define DISABLE_AXIS_J() if (SHOULD_DISABLE(j)) { DISABLE_STEPPER_J(); AFTER_CHANGE(j, false); set_axis_untrusted(J_AXIS); } +#else + #define ENABLE_AXIS_J() NOOP + #define DISABLE_AXIS_J() NOOP +#endif +#if LINEAR_AXES >= 6 + #define ENABLE_AXIS_K() if (SHOULD_ENABLE(k)) { ENABLE_STEPPER_K(); AFTER_CHANGE(k, true); } + #define DISABLE_AXIS_K() if (SHOULD_DISABLE(k)) { DISABLE_STEPPER_K(); AFTER_CHANGE(k, false); set_axis_untrusted(K_AXIS); } +#else + #define ENABLE_AXIS_K() NOOP + #define DISABLE_AXIS_K() NOOP +#endif + // // Extruder steppers enable / disable macros // #if ENABLED(MIXING_EXTRUDER) + /** * Mixing steppers keep all their enable (and direction) states synchronized */ @@ -880,6 +1026,12 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #define _CALL_DIS_E(N) DISABLE_STEPPER_E##N () ; #define ENABLE_AXIS_E0() { RREPEAT(MIXING_STEPPERS, _CALL_ENA_E) } #define DISABLE_AXIS_E0() { RREPEAT(MIXING_STEPPERS, _CALL_DIS_E) } + +#elif ENABLED(E_DUAL_STEPPER_DRIVERS) + + #define ENABLE_AXIS_E0() do{ ENABLE_STEPPER_E0(); ENABLE_STEPPER_E1(); }while(0) + #define DISABLE_AXIS_E0() do{ DISABLE_STEPPER_E0(); DISABLE_STEPPER_E1(); }while(0) + #endif #ifndef ENABLE_AXIS_E0 diff --git a/Marlin/src/module/stepper/trinamic.cpp b/Marlin/src/module/stepper/trinamic.cpp index 8c943048ba96a..a5d7e5ad6b3db 100644 --- a/Marlin/src/module/stepper/trinamic.cpp +++ b/Marlin/src/module/stepper/trinamic.cpp @@ -35,7 +35,9 @@ #include #include -enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; +enum StealthIndex : uint8_t { + LOGICAL_AXIS_LIST(STEALTH_AXIS_E, STEALTH_AXIS_X, STEALTH_AXIS_Y, STEALTH_AXIS_Z, STEALTH_AXIS_I, STEALTH_AXIS_J, STEALTH_AXIS_K) +}; #define TMC_INIT(ST, STEALTH_INDEX) tmc_init(stepper##ST, ST##_CURRENT, ST##_MICROSTEPS, ST##_HYBRID_THRESHOLD, stealthchop_by_axis[STEALTH_INDEX], chopper_timing_##ST, ST##_INTERPOLATE) // IC = TMC model number @@ -95,6 +97,15 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; #if AXIS_HAS_SPI(Z4) TMC_SPI_DEFINE(Z4, Z); #endif +#if AXIS_HAS_SPI(I) + TMC_SPI_DEFINE(I, I); +#endif +#if AXIS_HAS_SPI(J) + TMC_SPI_DEFINE(J, J); +#endif +#if AXIS_HAS_SPI(K) + TMC_SPI_DEFINE(K, K); +#endif #if AXIS_HAS_SPI(E0) TMC_SPI_DEFINE_E(0); #endif @@ -129,6 +140,55 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; #define TMC_BAUD_RATE TERN(HAS_TMC_SW_SERIAL, 57600, 115200) #endif +#ifndef TMC_X_BAUD_RATE + #define TMC_X_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_X2_BAUD_RATE + #define TMC_X2_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_Y_BAUD_RATE + #define TMC_Y_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_Y2_BAUD_RATE + #define TMC_Y2_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_Z_BAUD_RATE + #define TMC_Z_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_Z2_BAUD_RATE + #define TMC_Z2_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_Z3_BAUD_RATE + #define TMC_Z3_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_Z4_BAUD_RATE + #define TMC_Z4_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_E0_BAUD_RATE + #define TMC_E0_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_E1_BAUD_RATE + #define TMC_E1_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_E2_BAUD_RATE + #define TMC_E2_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_E3_BAUD_RATE + #define TMC_E3_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_E4_BAUD_RATE + #define TMC_E4_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_E5_BAUD_RATE + #define TMC_E5_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_E6_BAUD_RATE + #define TMC_E6_BAUD_RATE TMC_BAUD_RATE +#endif +#ifndef TMC_E7_BAUD_RATE + #define TMC_E7_BAUD_RATE TMC_BAUD_RATE +#endif + #if HAS_DRIVER(TMC2130) template void tmc_init(TMCMarlin &st, const uint16_t mA, const uint16_t microsteps, const uint32_t hyb_thrs, const bool stealth, const chopper_timing_t &chop_init, const bool interpolate) { @@ -278,6 +338,34 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; #define Z4_HAS_SW_SERIAL 1 #endif #endif + #if AXIS_HAS_UART(I) + #ifdef I_HARDWARE_SERIAL + TMC_UART_DEFINE(HW, I, I); + #define I_HAS_HW_SERIAL 1 + #else + TMC_UART_DEFINE(SW, I, I); + #define I_HAS_SW_SERIAL 1 + #endif + #endif + #if AXIS_HAS_UART(J) + #ifdef J_HARDWARE_SERIAL + TMC_UART_DEFINE(HW, J, J); + #define J_HAS_HW_SERIAL 1 + #else + TMC_UART_DEFINE(SW, J, J); + #define J_HAS_SW_SERIAL 1 + #endif + #endif + #if AXIS_HAS_UART(K) + #ifdef K_HARDWARE_SERIAL + TMC_UART_DEFINE(HW, K, K); + #define K_HAS_HW_SERIAL 1 + #else + TMC_UART_DEFINE(SW, K, K); + #define K_HAS_SW_SERIAL 1 + #endif + #endif + #if AXIS_HAS_UART(E0) #ifdef E0_HARDWARE_SERIAL TMC_UART_DEFINE_E(HW, 0); @@ -351,7 +439,9 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; #endif #endif - enum TMCAxis : uint8_t { X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7, TOTAL }; + #define _EN_ITEM(N) , E##N + enum TMCAxis : uint8_t { LINEAR_AXIS_LIST(X, Y, Z, I, J, K), X2, Y2, Z2, Z3, Z4 REPEAT(EXTRUDERS, _EN_ITEM), TOTAL }; + #undef _EN_ITEM void tmc_serial_begin() { #if HAS_TMC_HW_SERIAL @@ -364,7 +454,7 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; } sp_helper; #define HW_SERIAL_BEGIN(A) do{ if (!sp_helper.began(TMCAxis::A, &A##_HARDWARE_SERIAL)) \ - A##_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); }while(0) + A##_HARDWARE_SERIAL.begin(TMC_##A##_BAUD_RATE); }while(0) #endif #if AXIS_HAS_UART(X) @@ -423,6 +513,27 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; stepperZ4.beginSerial(TMC_BAUD_RATE); #endif #endif + #if AXIS_HAS_UART(I) + #ifdef I_HARDWARE_SERIAL + HW_SERIAL_BEGIN(I); + #else + stepperI.beginSerial(TMC_BAUD_RATE); + #endif + #endif + #if AXIS_HAS_UART(J) + #ifdef J_HARDWARE_SERIAL + HW_SERIAL_BEGIN(J); + #else + stepperJ.beginSerial(TMC_BAUD_RATE); + #endif + #endif + #if AXIS_HAS_UART(K) + #ifdef K_HARDWARE_SERIAL + HW_SERIAL_BEGIN(K); + #else + stepperK.beginSerial(TMC_BAUD_RATE); + #endif + #endif #if AXIS_HAS_UART(E0) #ifdef E0_HARDWARE_SERIAL HW_SERIAL_BEGIN(E0); @@ -655,11 +766,7 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E }; pwmconf.pwm_ofs = 36; st.PWMCONF(pwmconf.sr); - #if ENABLED(HYBRID_THRESHOLD) - st.set_pwm_thrs(hyb_thrs); - #else - UNUSED(hyb_thrs); - #endif + TERN(HYBRID_THRESHOLD, st.set_pwm_thrs(hyb_thrs), UNUSED(hyb_thrs)); st.GSTAT(); // Clear GSTAT } #endif // TMC5160 @@ -689,6 +796,15 @@ void restore_trinamic_drivers() { #if AXIS_IS_TMC(Z4) stepperZ4.push(); #endif + #if AXIS_IS_TMC(I) + stepperI.push(); + #endif + #if AXIS_IS_TMC(J) + stepperJ.push(); + #endif + #if AXIS_IS_TMC(K) + stepperK.push(); + #endif #if AXIS_IS_TMC(E0) stepperE0.push(); #endif @@ -716,19 +832,27 @@ void restore_trinamic_drivers() { } void reset_trinamic_drivers() { - static constexpr bool stealthchop_by_axis[] = { ENABLED(STEALTHCHOP_XY), ENABLED(STEALTHCHOP_Z), ENABLED(STEALTHCHOP_E) }; + static constexpr bool stealthchop_by_axis[] = LOGICAL_AXIS_ARRAY( + ENABLED(STEALTHCHOP_E), + ENABLED(STEALTHCHOP_XY), + ENABLED(STEALTHCHOP_XY), + ENABLED(STEALTHCHOP_Z), + ENABLED(STEALTHCHOP_I), + ENABLED(STEALTHCHOP_J), + ENABLED(STEALTHCHOP_K) + ); #if AXIS_IS_TMC(X) - TMC_INIT(X, STEALTH_AXIS_XY); + TMC_INIT(X, STEALTH_AXIS_X); #endif #if AXIS_IS_TMC(X2) - TMC_INIT(X2, STEALTH_AXIS_XY); + TMC_INIT(X2, STEALTH_AXIS_X); #endif #if AXIS_IS_TMC(Y) - TMC_INIT(Y, STEALTH_AXIS_XY); + TMC_INIT(Y, STEALTH_AXIS_Y); #endif #if AXIS_IS_TMC(Y2) - TMC_INIT(Y2, STEALTH_AXIS_XY); + TMC_INIT(Y2, STEALTH_AXIS_Y); #endif #if AXIS_IS_TMC(Z) TMC_INIT(Z, STEALTH_AXIS_Z); @@ -742,6 +866,15 @@ void reset_trinamic_drivers() { #if AXIS_IS_TMC(Z4) TMC_INIT(Z4, STEALTH_AXIS_Z); #endif + #if AXIS_IS_TMC(I) + TMC_INIT(I, STEALTH_AXIS_I); + #endif + #if AXIS_IS_TMC(J) + TMC_INIT(J, STEALTH_AXIS_J); + #endif + #if AXIS_IS_TMC(K) + TMC_INIT(K, STEALTH_AXIS_K); + #endif #if AXIS_IS_TMC(E0) TMC_INIT(E0, STEALTH_AXIS_E); #endif @@ -792,7 +925,25 @@ void reset_trinamic_drivers() { stepperZ4.homing_threshold(CAT(TERN(Z4_SENSORLESS, Z4, Z), _STALL_SENSITIVITY)); #endif #endif - #endif + #if I_SENSORLESS + stepperI.homing_threshold(I_STALL_SENSITIVITY); + #if AXIS_HAS_STALLGUARD(I) + stepperI.homing_threshold(CAT(TERN(I_SENSORLESS, I, I), _STALL_SENSITIVITY)); + #endif + #endif + #if J_SENSORLESS + stepperJ.homing_threshold(J_STALL_SENSITIVITY); + #if AXIS_HAS_STALLGUARD(J) + stepperJ.homing_threshold(CAT(TERN(J_SENSORLESS, J, J), _STALL_SENSITIVITY)); + #endif + #endif + #if K_SENSORLESS + stepperK.homing_threshold(K_STALL_SENSITIVITY); + #if AXIS_HAS_STALLGUARD(K) + stepperK.homing_threshold(CAT(TERN(K_SENSORLESS, K, K), _STALL_SENSITIVITY)); + #endif + #endif + #endif // USE SENSORLESS #ifdef TMC_ADV TMC_ADV() @@ -816,11 +967,12 @@ void reset_trinamic_drivers() { // Using a fixed-length character array for the port name allows this to be constexpr compatible. struct SanityHwSerialDetails { const char port[20]; uint32_t address; }; #define TMC_HW_DETAIL_ARGS(A) TERN(A##_HAS_HW_SERIAL, STRINGIFY(A##_HARDWARE_SERIAL), ""), TERN0(A##_HAS_HW_SERIAL, A##_SLAVE_ADDRESS) - #define TMC_HW_DETAIL(A) {TMC_HW_DETAIL_ARGS(A)} + #define TMC_HW_DETAIL(A) { TMC_HW_DETAIL_ARGS(A) } constexpr SanityHwSerialDetails sanity_tmc_hw_details[] = { TMC_HW_DETAIL(X), TMC_HW_DETAIL(X2), TMC_HW_DETAIL(Y), TMC_HW_DETAIL(Y2), TMC_HW_DETAIL(Z), TMC_HW_DETAIL(Z2), TMC_HW_DETAIL(Z3), TMC_HW_DETAIL(Z4), + TMC_HW_DETAIL(I), TMC_HW_DETAIL(J), TMC_HW_DETAIL(K), TMC_HW_DETAIL(E0), TMC_HW_DETAIL(E1), TMC_HW_DETAIL(E2), TMC_HW_DETAIL(E3), TMC_HW_DETAIL(E4), TMC_HW_DETAIL(E5), TMC_HW_DETAIL(E6), TMC_HW_DETAIL(E7) }; @@ -840,10 +992,11 @@ void reset_trinamic_drivers() { #define TMC_HWSERIAL_CONFLICT_MSG(A) STRINGIFY(A) "_SLAVE_ADDRESS conflicts with another driver using the same " STRINGIFY(A) "_HARDWARE_SERIAL" #define SA_NO_TMC_HW_C(A) static_assert(1 >= count_tmc_hw_serial_matches(TMC_HW_DETAIL_ARGS(A), 0, COUNT(sanity_tmc_hw_details)), TMC_HWSERIAL_CONFLICT_MSG(A)); - SA_NO_TMC_HW_C(X);SA_NO_TMC_HW_C(X2); - SA_NO_TMC_HW_C(Y);SA_NO_TMC_HW_C(Y2); - SA_NO_TMC_HW_C(Z);SA_NO_TMC_HW_C(Z2);SA_NO_TMC_HW_C(Z3);SA_NO_TMC_HW_C(Z4); - SA_NO_TMC_HW_C(E0);SA_NO_TMC_HW_C(E1);SA_NO_TMC_HW_C(E2);SA_NO_TMC_HW_C(E3);SA_NO_TMC_HW_C(E4);SA_NO_TMC_HW_C(E5);SA_NO_TMC_HW_C(E6);SA_NO_TMC_HW_C(E7); + SA_NO_TMC_HW_C(X); SA_NO_TMC_HW_C(X2); + SA_NO_TMC_HW_C(Y); SA_NO_TMC_HW_C(Y2); + SA_NO_TMC_HW_C(Z); SA_NO_TMC_HW_C(Z2); SA_NO_TMC_HW_C(Z3); SA_NO_TMC_HW_C(Z4); + SA_NO_TMC_HW_C(I); SA_NO_TMC_HW_C(J); SA_NO_TMC_HW_C(K); + SA_NO_TMC_HW_C(E0); SA_NO_TMC_HW_C(E1); SA_NO_TMC_HW_C(E2); SA_NO_TMC_HW_C(E3); SA_NO_TMC_HW_C(E4); SA_NO_TMC_HW_C(E5); SA_NO_TMC_HW_C(E6); SA_NO_TMC_HW_C(E7); #endif #if ANY_AXIS_HAS(SW_SERIAL) @@ -854,7 +1007,8 @@ void reset_trinamic_drivers() { TMC_SW_DETAIL(X), TMC_SW_DETAIL(X2), TMC_SW_DETAIL(Y), TMC_SW_DETAIL(Y2), TMC_SW_DETAIL(Z), TMC_SW_DETAIL(Z2), TMC_SW_DETAIL(Z3), TMC_SW_DETAIL(Z4), - TMC_SW_DETAIL(E0), TMC_SW_DETAIL(E1), TMC_SW_DETAIL(E2), TMC_SW_DETAIL(E3), TMC_SW_DETAIL(E4), TMC_SW_DETAIL(E5), TMC_SW_DETAIL(E6), TMC_SW_DETAIL(E7) + TMC_SW_DETAIL(I), TMC_SW_DETAIL(J), TMC_SW_DETAIL(K), + TMC_SW_DETAIL(E0), TMC_SW_DETAIL(E1), TMC_SW_DETAIL(E2), TMC_SW_DETAIL(E3), TMC_SW_DETAIL(E4), TMC_SW_DETAIL(E5), TMC_SW_DETAIL(E6), TMC_SW_DETAIL(E7) }; constexpr bool sc_sw_done(size_t start, size_t end) { return start == end; } @@ -868,10 +1022,11 @@ void reset_trinamic_drivers() { #define TMC_SWSERIAL_CONFLICT_MSG(A) STRINGIFY(A) "_SLAVE_ADDRESS conflicts with another driver using the same " STRINGIFY(A) "_SERIAL_RX_PIN or " STRINGIFY(A) "_SERIAL_TX_PIN" #define SA_NO_TMC_SW_C(A) static_assert(1 >= count_tmc_sw_serial_matches(TMC_SW_DETAIL_ARGS(A), 0, COUNT(sanity_tmc_sw_details)), TMC_SWSERIAL_CONFLICT_MSG(A)); - SA_NO_TMC_SW_C(X);SA_NO_TMC_SW_C(X2); - SA_NO_TMC_SW_C(Y);SA_NO_TMC_SW_C(Y2); - SA_NO_TMC_SW_C(Z);SA_NO_TMC_SW_C(Z2);SA_NO_TMC_SW_C(Z3);SA_NO_TMC_SW_C(Z4); - SA_NO_TMC_SW_C(E0);SA_NO_TMC_SW_C(E1);SA_NO_TMC_SW_C(E2);SA_NO_TMC_SW_C(E3);SA_NO_TMC_SW_C(E4);SA_NO_TMC_SW_C(E5);SA_NO_TMC_SW_C(E6);SA_NO_TMC_SW_C(E7); + SA_NO_TMC_SW_C(X); SA_NO_TMC_SW_C(X2); + SA_NO_TMC_SW_C(Y); SA_NO_TMC_SW_C(Y2); + SA_NO_TMC_SW_C(Z); SA_NO_TMC_SW_C(Z2); SA_NO_TMC_SW_C(Z3); SA_NO_TMC_SW_C(Z4); + SA_NO_TMC_SW_C(I); SA_NO_TMC_SW_C(J); SA_NO_TMC_SW_C(K); + SA_NO_TMC_SW_C(E0); SA_NO_TMC_SW_C(E1); SA_NO_TMC_SW_C(E2); SA_NO_TMC_SW_C(E3); SA_NO_TMC_SW_C(E4); SA_NO_TMC_SW_C(E5); SA_NO_TMC_SW_C(E6); SA_NO_TMC_SW_C(E7); #endif #endif // HAS_TRINAMIC_CONFIG diff --git a/Marlin/src/module/stepper/trinamic.h b/Marlin/src/module/stepper/trinamic.h index 9f7445e4fda54..766f8fced2464 100644 --- a/Marlin/src/module/stepper/trinamic.h +++ b/Marlin/src/module/stepper/trinamic.h @@ -46,6 +46,10 @@ #define TMC_Y_LABEL 'Y', '0' #define TMC_Z_LABEL 'Z', '0' +#define TMC_I_LABEL 'I', '0' +#define TMC_J_LABEL 'J', '0' +#define TMC_K_LABEL 'K', '0' + #define TMC_X2_LABEL 'X', '2' #define TMC_Y2_LABEL 'Y', '2' #define TMC_Z2_LABEL 'Z', '2' @@ -79,13 +83,22 @@ typedef struct { #ifndef CHOPPER_TIMING_X #define CHOPPER_TIMING_X CHOPPER_TIMING #endif -#ifndef CHOPPER_TIMING_Y +#if HAS_Y_AXIS && !defined(CHOPPER_TIMING_Y) #define CHOPPER_TIMING_Y CHOPPER_TIMING #endif -#ifndef CHOPPER_TIMING_Z +#if HAS_Z_AXIS && !defined(CHOPPER_TIMING_Z) #define CHOPPER_TIMING_Z CHOPPER_TIMING #endif -#ifndef CHOPPER_TIMING_E +#if LINEAR_AXES >= 4 && !defined(CHOPPER_TIMING_I) + #define CHOPPER_TIMING_I CHOPPER_TIMING +#endif +#if LINEAR_AXES >= 5 && !defined(CHOPPER_TIMING_J) + #define CHOPPER_TIMING_J CHOPPER_TIMING +#endif +#if LINEAR_AXES >= 6 && !defined(CHOPPER_TIMING_K) + #define CHOPPER_TIMING_K CHOPPER_TIMING +#endif +#if HAS_EXTRUDERS && !defined(CHOPPER_TIMING_E) #define CHOPPER_TIMING_E CHOPPER_TIMING #endif @@ -225,6 +238,48 @@ void reset_trinamic_drivers(); #endif #endif +// I Stepper +#if AXIS_IS_TMC(I) + extern TMC_CLASS(I, I) stepperI; + static constexpr chopper_timing_t chopper_timing_I = CHOPPER_TIMING_I; + #if ENABLED(SOFTWARE_DRIVER_ENABLE) + #define I_ENABLE_INIT() NOOP + #define I_ENABLE_WRITE(STATE) stepperI.toff((STATE)==I_ENABLE_ON ? chopper_timing.toff : 0) + #define I_ENABLE_READ() stepperI.isEnabled() + #endif + #if AXIS_HAS_SQUARE_WAVE(I) + #define I_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(I_STEP_PIN); }while(0) + #endif +#endif + +// J Stepper +#if AXIS_IS_TMC(J) + extern TMC_CLASS(J, J) stepperJ; + static constexpr chopper_timing_t chopper_timing_J = CHOPPER_TIMING_J; + #if ENABLED(SOFTWARE_DRIVER_ENABLE) + #define J_ENABLE_INIT() NOOP + #define J_ENABLE_WRITE(STATE) stepperJ.toff((STATE)==J_ENABLE_ON ? chopper_timing.toff : 0) + #define J_ENABLE_READ() stepperJ.isEnabled() + #endif + #if AXIS_HAS_SQUARE_WAVE(J) + #define J_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(J_STEP_PIN); }while(0) + #endif +#endif + +// K Stepper +#if AXIS_IS_TMC(K) + extern TMC_CLASS(K, K) stepperK; + static constexpr chopper_timing_t chopper_timing_K = CHOPPER_TIMING_K; + #if ENABLED(SOFTWARE_DRIVER_ENABLE) + #define K_ENABLE_INIT() NOOP + #define K_ENABLE_WRITE(STATE) stepperK.toff((STATE)==K_ENABLE_ON ? chopper_timing.toff : 0) + #define K_ENABLE_READ() stepperK.isEnabled() + #endif + #if AXIS_HAS_SQUARE_WAVE(K) + #define K_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(K_STEP_PIN); }while(0) + #endif +#endif + // E0 Stepper #if AXIS_IS_TMC(E0) extern TMC_CLASS_E(0) stepperE0; diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 1f32e6b11827d..9f32ce933bff5 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -56,13 +56,15 @@ #include "../feature/host_actions.h" #endif +#define TEMP_SENSOR_IS_ANY_MAX_TC(n) (ENABLED(TEMP_SENSOR_##n##_IS_MAX_TC) || (ENABLED(TEMP_SENSOR_REDUNDANT_IS_MAX_TC) && ENABLED(TEMP_SENSOR_REDUNDANT_SOURCE) && TEMP_SENSOR_REDUNDANT_SOURCE == n)) + // LIB_MAX31855 can be added to the build_flags in platformio.ini to use a user-defined library #if LIB_USR_MAX31855 #include #if PIN_EXISTS(MAX31855_MISO) && PIN_EXISTS(MAX31855_SCK) #define MAX31855_USES_SW_SPI 1 #endif - #if TEMP_SENSOR_0_IS_MAX31855 && PIN_EXISTS(MAX31855_CS) + #if TEMP_SENSOR_IS_MAX(0, MAX31855) && PIN_EXISTS(MAX31855_CS) #define HAS_MAX31855_TEMP 1 Adafruit_MAX31855 max31855_0 = Adafruit_MAX31855(MAX31855_CS_PIN #if MAX31855_USES_SW_SPI @@ -73,7 +75,7 @@ #endif ); #endif - #if TEMP_SENSOR_1_IS_MAX31855 && PIN_EXISTS(MAX31855_CS2) + #if TEMP_SENSOR_IS_MAX(1, MAX31855) && PIN_EXISTS(MAX31855_CS2) #define HAS_MAX31855_TEMP 1 Adafruit_MAX31855 max31855_1 = Adafruit_MAX31855(MAX31855_CS2_PIN #if MAX31855_USES_SW_SPI @@ -96,7 +98,7 @@ #if PIN_EXISTS(MAX31865_MISO) && PIN_EXISTS(MAX31865_SCK) #define MAX31865_USES_SW_SPI 1 #endif - #if TEMP_SENSOR_0_IS_MAX31865 && PIN_EXISTS(MAX31865_CS) + #if TEMP_SENSOR_IS_MAX(0, MAX31865) && PIN_EXISTS(MAX31865_CS) #define HAS_MAX31865_TEMP 1 Adafruit_MAX31865 max31865_0 = Adafruit_MAX31865(MAX31865_CS_PIN #if MAX31865_USES_SW_SPI && PIN_EXISTS(MAX31865_MOSI) @@ -107,7 +109,7 @@ #endif ); #endif - #if TEMP_SENSOR_1_IS_MAX31865 && PIN_EXISTS(MAX31865_CS2) + #if TEMP_SENSOR_IS_MAX(1, MAX31865) && PIN_EXISTS(MAX31865_CS2) #define HAS_MAX31865_TEMP 1 Adafruit_MAX31865 max31865_1 = Adafruit_MAX31865(MAX31865_CS2_PIN #if MAX31865_USES_SW_SPI && PIN_EXISTS(MAX31865_MOSI) @@ -126,7 +128,7 @@ #if PIN_EXISTS(MAX6675_MISO) && PIN_EXISTS(MAX6675_SCK) #define MAX6675_USES_SW_SPI 1 #endif - #if TEMP_SENSOR_0_IS_MAX6675 && PIN_EXISTS(MAX6675_CS) + #if TEMP_SENSOR_IS_MAX(0, MAX6675) && PIN_EXISTS(MAX6675_CS) #define HAS_MAX6675_TEMP 1 MAX6675 max6675_0 = MAX6675(MAX6675_CS_PIN #if MAX6675_USES_SW_SPI @@ -137,7 +139,7 @@ #endif ); #endif - #if TEMP_SENSOR_1_IS_MAX6675 && PIN_EXISTS(MAX6675_CS2) + #if TEMP_SENSOR_IS_MAX(1, MAX6675) && PIN_EXISTS(MAX6675_CS2) #define HAS_MAX6675_TEMP 1 MAX6675 max6675_1 = MAX6675(MAX6675_CS2_PIN #if MAX6675_USES_SW_SPI @@ -154,7 +156,7 @@ #define NO_THERMO_TEMPS 1 #endif -#if (TEMP_SENSOR_0_IS_MAX_TC || TEMP_SENSOR_1_IS_MAX_TC) && PINS_EXIST(MAX6675_SCK, MAX6675_DO) && NO_THERMO_TEMPS +#if (TEMP_SENSOR_0_IS_MAX_TC || TEMP_SENSOR_1_IS_MAX_TC || TEMP_SENSOR_REDUNDANT_IS_MAX_TC) && PINS_EXIST(MAX6675_SCK, MAX6675_DO) && NO_THERMO_TEMPS #define THERMO_SEPARATE_SPI 1 #endif @@ -210,15 +212,10 @@ #endif #if HAS_HOTEND_THERMISTOR - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - static const temp_entry_t* heater_ttbl_map[2] = { TEMPTABLE_0, TEMPTABLE_1 }; - static constexpr uint8_t heater_ttbllen_map[2] = { TEMPTABLE_0_LEN, TEMPTABLE_1_LEN }; - #else - #define NEXT_TEMPTABLE(N) ,TEMPTABLE_##N - #define NEXT_TEMPTABLE_LEN(N) ,TEMPTABLE_##N##_LEN - static const temp_entry_t* heater_ttbl_map[HOTENDS] = ARRAY_BY_HOTENDS(TEMPTABLE_0 REPEAT_S(1, HOTENDS, NEXT_TEMPTABLE)); - static constexpr uint8_t heater_ttbllen_map[HOTENDS] = ARRAY_BY_HOTENDS(TEMPTABLE_0_LEN REPEAT_S(1, HOTENDS, NEXT_TEMPTABLE_LEN)); - #endif + #define NEXT_TEMPTABLE(N) ,TEMPTABLE_##N + #define NEXT_TEMPTABLE_LEN(N) ,TEMPTABLE_##N##_LEN + static const temp_entry_t* heater_ttbl_map[HOTENDS] = ARRAY_BY_HOTENDS(TEMPTABLE_0 REPEAT_S(1, HOTENDS, NEXT_TEMPTABLE)); + static constexpr uint8_t heater_ttbllen_map[HOTENDS] = ARRAY_BY_HOTENDS(TEMPTABLE_0_LEN REPEAT_S(1, HOTENDS, NEXT_TEMPTABLE_LEN)); #endif Temperature thermalManager; @@ -257,13 +254,14 @@ const char str_t_thermal_runaway[] PROGMEM = STR_T_THERMAL_RUNAWAY, #if HAS_HOTEND hotend_info_t Temperature::temp_hotend[HOTENDS]; - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - temp_info_t Temperature::temp_redundant; - #endif #define _HMT(N) HEATER_##N##_MAXTEMP, const celsius_t Temperature::hotend_maxtemp[HOTENDS] = ARRAY_BY_HOTENDS(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP, HEATER_4_MAXTEMP, HEATER_5_MAXTEMP, HEATER_6_MAXTEMP, HEATER_7_MAXTEMP); #endif +#if HAS_TEMP_REDUNDANT + redundant_temp_info_t Temperature::temp_redundant; +#endif + #if ENABLED(AUTO_POWER_E_FANS) uint8_t Temperature::autofan_speed[HOTENDS]; // = { 0 } #endif @@ -335,6 +333,9 @@ const char str_t_thermal_runaway[] PROGMEM = STR_T_THERMAL_RUNAWAY, if (fan >= FAN_COUNT) return; fan_speed[fan] = speed; + #if REDUNDANT_PART_COOLING_FAN + if (fan == 0) fan_speed[REDUNDANT_PART_COOLING_FAN] = speed; + #endif TERN_(REPORT_FAN_CHANGE, report_fan_speed(fan)); } @@ -1219,8 +1220,12 @@ void Temperature::manage_heater() { if (degHotend(0) < _MAX(HEATER_0_MINTEMP, TEMP_SENSOR_0_MAX_TC_TMIN + .01)) min_temp_error(H_E0); #endif #if TEMP_SENSOR_1_IS_MAX_TC - if (TERN(TEMP_SENSOR_1_AS_REDUNDANT, degHotendRedundant(), degHotend(1)) > _MIN(HEATER_1_MAXTEMP, TEMP_SENSOR_1_MAX_TC_TMAX - 1.0)) max_temp_error(H_E1); - if (TERN(TEMP_SENSOR_1_AS_REDUNDANT, degHotendRedundant(), degHotend(1)) < _MAX(HEATER_1_MINTEMP, TEMP_SENSOR_1_MAX_TC_TMIN + .01)) min_temp_error(H_E1); + if (degHotend(1) > _MIN(HEATER_1_MAXTEMP, TEMP_SENSOR_1_MAX_TC_TMAX - 1.0)) max_temp_error(H_E1); + if (degHotend(1) < _MAX(HEATER_1_MINTEMP, TEMP_SENSOR_1_MAX_TC_TMIN + .01)) min_temp_error(H_E1); + #endif + #if TEMP_SENSOR_REDUNDANT_IS_MAX_TC + if (degRedundant() > TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX - 1.0) max_temp_error(H_REDUNDANT); + if (degRedundant() < TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN + .01) min_temp_error(H_REDUNDANT); #endif #endif @@ -1254,16 +1259,16 @@ void Temperature::manage_heater() { } #endif - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - // Make sure measured temperatures are close together - if (ABS(degHotend(0) - degHotendRedundant()) > MAX_REDUNDANT_TEMP_SENSOR_DIFF) - _temp_error(H_E0, PSTR(STR_REDUNDANCY), GET_TEXT(MSG_ERR_REDUNDANT_TEMP)); - #endif - } // HOTEND_LOOP #endif // HAS_HOTEND + #if HAS_TEMP_REDUNDANT + // Make sure measured temperatures are close together + if (ABS(degRedundantTarget() - degRedundant()) > TEMP_SENSOR_REDUNDANT_MAX_DIFF) + _temp_error((heater_id_t)TEMP_SENSOR_REDUNDANT_TARGET, PSTR(STR_REDUNDANCY), GET_TEXT(MSG_ERR_REDUNDANT_TEMP)); + #endif + #if HAS_AUTO_FAN if (ELAPSED(ms, next_auto_fan_check_ms)) { // only need to check fan state very infrequently checkExtruderAutoFans(); @@ -1613,13 +1618,16 @@ void Temperature::manage_heater() { { true, 0, 0, BED_PULLUP_RESISTOR_OHMS, BED_RESISTANCE_25C_OHMS, 0, 0, BED_BETA, 0 }, #endif #if TEMP_SENSOR_CHAMBER_IS_CUSTOM - { true, 0, 0, CHAMBER_PULLUP_RESISTOR_OHMS, CHAMBER_RESISTANCE_25C_OHMS, 0, 0, CHAMBER_BETA, 0 } + { true, 0, 0, CHAMBER_PULLUP_RESISTOR_OHMS, CHAMBER_RESISTANCE_25C_OHMS, 0, 0, CHAMBER_BETA, 0 }, #endif #if TEMP_SENSOR_COOLER_IS_CUSTOM - { true, 0, 0, COOLER_PULLUP_RESISTOR_OHMS, COOLER_RESISTANCE_25C_OHMS, 0, 0, COOLER_BETA, 0 } + { true, 0, 0, COOLER_PULLUP_RESISTOR_OHMS, COOLER_RESISTANCE_25C_OHMS, 0, 0, COOLER_BETA, 0 }, #endif #if TEMP_SENSOR_PROBE_IS_CUSTOM - { true, 0, 0, PROBE_PULLUP_RESISTOR_OHMS, PROBE_RESISTANCE_25C_OHMS, 0, 0, PROBE_BETA, 0 } + { true, 0, 0, PROBE_PULLUP_RESISTOR_OHMS, PROBE_RESISTANCE_25C_OHMS, 0, 0, PROBE_BETA, 0 }, + #endif + #if TEMP_SENSOR_REDUNDANT_IS_CUSTOM + { true, 0, 0, REDUNDANT_PULLUP_RESISTOR_OHMS, REDUNDANT_RESISTANCE_25C_OHMS, 0, 0, REDUNDANT_BETA, 0 }, #endif }; COPY(user_thermistor, default_user_thermistor); @@ -1653,6 +1661,7 @@ void Temperature::manage_heater() { TERN_(TEMP_SENSOR_CHAMBER_IS_CUSTOM, t_index == CTI_CHAMBER ? PSTR("CHAMBER") :) TERN_(TEMP_SENSOR_COOLER_IS_CUSTOM, t_index == CTI_COOLER ? PSTR("COOLER") :) TERN_(TEMP_SENSOR_PROBE_IS_CUSTOM, t_index == CTI_PROBE ? PSTR("PROBE") :) + TERN_(TEMP_SENSOR_REDUNDANT_IS_CUSTOM, t_index == CTI_REDUNDANT ? PSTR("REDUNDANT") :) nullptr ); SERIAL_EOL(); @@ -1708,7 +1717,7 @@ void Temperature::manage_heater() { // Derived from RepRap FiveD extruder::getTemperature() // For hot end temperature measurement. celsius_float_t Temperature::analog_to_celsius_hotend(const int16_t raw, const uint8_t e) { - if (e >= HOTENDS + ENABLED(TEMP_SENSOR_1_AS_REDUNDANT)) { + if (e >= HOTENDS) { SERIAL_ERROR_START(); SERIAL_ECHO(e); SERIAL_ECHOLNPGM(STR_INVALID_EXTRUDER_NUM); @@ -1886,6 +1895,28 @@ void Temperature::manage_heater() { } #endif // HAS_TEMP_PROBE +#if HAS_TEMP_REDUNDANT + // For redundant temperature measurement. + celsius_float_t Temperature::analog_to_celsius_redundant(const int16_t raw) { + #if TEMP_SENSOR_REDUNDANT_IS_CUSTOM + return user_thermistor_to_deg_c(CTI_REDUNDANT, raw); + #elif TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 0 + return TERN(TEMP_SENSOR_REDUNDANT_IS_MAX31865, max31865_0.temperature(MAX31865_SENSOR_OHMS_0, MAX31865_CALIBRATION_OHMS_0), raw * 0.25); + #elif TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 1 + return TERN(TEMP_SENSOR_REDUNDANT_IS_MAX31865, max31865_1.temperature(MAX31865_SENSOR_OHMS_1, MAX31865_CALIBRATION_OHMS_1), raw * 0.25); + #elif TEMP_SENSOR_REDUNDANT_IS_THERMISTOR + SCAN_THERMISTOR_TABLE(TEMPTABLE_REDUNDANT, TEMPTABLE_REDUNDANT_LEN); + #elif TEMP_SENSOR_REDUNDANT_IS_AD595 + return TEMP_AD595(raw); + #elif TEMP_SENSOR_REDUNDANT_IS_AD8495 + return TEMP_AD8495(raw); + #else + UNUSED(raw); + return 0; + #endif + } +#endif // HAS_TEMP_REDUNDANT + /** * Convert the raw sensor readings into actual Celsius temperatures and * validate raw temperatures. Bad readings generate min/maxtemp errors. @@ -1903,26 +1934,34 @@ void Temperature::updateTemperaturesFromRawValues() { watchdog_refresh(); // Reset because raw_temps_ready was set by the interrupt TERN_(TEMP_SENSOR_0_IS_MAX_TC, temp_hotend[0].raw = READ_MAX_TC(0)); - TERN_(TEMP_SENSOR_1_IS_MAX_TC, TERN(TEMP_SENSOR_1_AS_REDUNDANT, temp_redundant, temp_hotend[1]).raw = READ_MAX_TC(1)); + TERN_(TEMP_SENSOR_1_IS_MAX_TC, temp_hotend[1].raw = READ_MAX_TC(1)); + TERN_(TEMP_SENSOR_REDUNDANT_IS_MAX_TC, temp_redundant.raw = READ_MAX_TC(TEMP_SENSOR_REDUNDANT_SOURCE)); #if HAS_HOTEND HOTEND_LOOP() temp_hotend[e].celsius = analog_to_celsius_hotend(temp_hotend[e].raw, e); #endif - TERN_(TEMP_SENSOR_1_AS_REDUNDANT, temp_redundant.celsius = analog_to_celsius_hotend(temp_redundant.raw, 1)); - TERN_(HAS_HEATED_BED, temp_bed.celsius = analog_to_celsius_bed(temp_bed.raw)); - TERN_(HAS_TEMP_CHAMBER, temp_chamber.celsius = analog_to_celsius_chamber(temp_chamber.raw)); - TERN_(HAS_TEMP_COOLER, temp_cooler.celsius = analog_to_celsius_cooler(temp_cooler.raw)); - TERN_(HAS_TEMP_PROBE, temp_probe.celsius = analog_to_celsius_probe(temp_probe.raw)); + TERN_(HAS_HEATED_BED, temp_bed.celsius = analog_to_celsius_bed(temp_bed.raw)); + TERN_(HAS_TEMP_CHAMBER, temp_chamber.celsius = analog_to_celsius_chamber(temp_chamber.raw)); + TERN_(HAS_TEMP_COOLER, temp_cooler.celsius = analog_to_celsius_cooler(temp_cooler.raw)); + TERN_(HAS_TEMP_PROBE, temp_probe.celsius = analog_to_celsius_probe(temp_probe.raw)); + TERN_(HAS_TEMP_REDUNDANT, temp_redundant.celsius = analog_to_celsius_redundant(temp_redundant.raw)); TERN_(FILAMENT_WIDTH_SENSOR, filwidth.update_measured_mm()); TERN_(HAS_POWER_MONITOR, power_monitor.capture_values()); #if HAS_HOTEND - static constexpr int8_t temp_dir[] = { - TERN(TEMP_SENSOR_0_IS_MAX_TC, 0, TEMPDIR(0)) + #if TEMP_SENSOR_IS_ANY_MAX_TC(0) + 0 + #else + TEMPDIR(0) + #endif #if HAS_MULTI_HOTEND - , TERN(TEMP_SENSOR_1_IS_MAX_TC, 0, TEMPDIR(1)) + #if TEMP_SENSOR_IS_ANY_MAX_TC(1) + , 0 + #else + , TEMPDIR(1) + #endif #if HOTENDS > 2 #define _TEMPDIR(N) , TEMPDIR(N) REPEAT_S(2, HOTENDS, _TEMPDIR) @@ -2031,42 +2070,56 @@ void Temperature::init() { #endif // Init (and disable) SPI thermocouples - #if TEMP_SENSOR_0_IS_MAX6675 && PIN_EXISTS(MAX6675_CS) + #if TEMP_SENSOR_IS_MAX(0, MAX6675) && PIN_EXISTS(MAX6675_CS) OUT_WRITE(MAX6675_CS_PIN, HIGH); #endif - #if TEMP_SENSOR_1_IS_MAX6675 && PIN_EXISTS(MAX6675_CS2) + #if TEMP_SENSOR_IS_MAX(1, MAX6675) && PIN_EXISTS(MAX6675_CS2) OUT_WRITE(MAX6675_CS2_PIN, HIGH); #endif - #if TEMP_SENSOR_0_IS_MAX6675 && PIN_EXISTS(MAX31855_CS) + #if TEMP_SENSOR_IS_MAX(0, MAX6675) && PIN_EXISTS(MAX31855_CS) OUT_WRITE(MAX31855_CS_PIN, HIGH); #endif - #if TEMP_SENSOR_1_IS_MAX6675 && PIN_EXISTS(MAX31855_CS2) + #if TEMP_SENSOR_IS_MAX(1, MAX6675) && PIN_EXISTS(MAX31855_CS2) OUT_WRITE(MAX31855_CS2_PIN, HIGH); #endif - #if TEMP_SENSOR_0_IS_MAX6675 && PIN_EXISTS(MAX31865_CS) + #if TEMP_SENSOR_IS_MAX(0, MAX6675) && PIN_EXISTS(MAX31865_CS) OUT_WRITE(MAX31865_CS_PIN, HIGH); #endif - #if TEMP_SENSOR_1_IS_MAX6675 && PIN_EXISTS(MAX31865_CS2) + #if TEMP_SENSOR_IS_MAX(1, MAX6675) && PIN_EXISTS(MAX31865_CS2) OUT_WRITE(MAX31865_CS2_PIN, HIGH); #endif #if HAS_MAX31865_TEMP - TERN_(TEMP_SENSOR_0_IS_MAX31865, max31865_0.begin(MAX31865_2WIRE)); // MAX31865_2WIRE, MAX31865_3WIRE, MAX31865_4WIRE - TERN_(TEMP_SENSOR_1_IS_MAX31865, max31865_1.begin(MAX31865_2WIRE)); + #if TEMP_SENSOR_IS_MAX(0, MAX31865) + max31865_0.begin(MAX31865_2WIRE); // MAX31865_2WIRE, MAX31865_3WIRE, MAX31865_4WIRE + #endif + #if TEMP_SENSOR_IS_MAX(1, MAX31865) + max31865_1.begin(MAX31865_2WIRE); + #endif #endif + #if HAS_MAX31855_TEMP - TERN_(TEMP_SENSOR_0_IS_MAX31855, max31855_0.begin()); - TERN_(TEMP_SENSOR_1_IS_MAX31855, max31855_1.begin()); + #if TEMP_SENSOR_IS_MAX(0, MAX31855) + max31855_0.begin(MAX31855); + #endif + #if TEMP_SENSOR_IS_MAX(1, MAX31855) + max31855_1.begin(MAX31855); + #endif #endif + #if HAS_MAX6675_TEMP - TERN_(TEMP_SENSOR_0_IS_MAX6675, max6675_0.begin()); - TERN_(TEMP_SENSOR_1_IS_MAX6675, max6675_1.begin()); + #if TEMP_SENSOR_IS_MAX(0, MAX6675) + max6675_0.begin(MAX6675); + #endif + #if TEMP_SENSOR_IS_MAX(1, MAX6675) + max6675_1.begin(MAX6675); + #endif #endif #if MB(RUMBA) // Disable RUMBA JTAG in case the thermocouple extension is plugged on top of JTAG connector #define _AD(N) (TEMP_SENSOR_##N##_IS_AD595 || TEMP_SENSOR_##N##_IS_AD8495) - #if _AD(0) || _AD(1) || _AD(2) || _AD(BED) || _AD(CHAMBER) + #if _AD(0) || _AD(1) || _AD(2) || _AD(BED) || _AD(CHAMBER) || _AD(REDUNDANT) MCUCR = _BV(JTD); MCUCR = _BV(JTD); #endif @@ -2074,10 +2127,22 @@ void Temperature::init() { // Thermistor activation by MCU pin #if PIN_EXISTS(TEMP_0_TR_ENABLE) - OUT_WRITE(TEMP_0_TR_ENABLE_PIN, ENABLED(TEMP_SENSOR_0_IS_MAX_TC)); + OUT_WRITE(TEMP_0_TR_ENABLE_PIN, + #if TEMP_SENSOR_IS_ANY_MAX_TC(0) + 1 + #else + 0 + #endif + ); #endif #if PIN_EXISTS(TEMP_1_TR_ENABLE) - OUT_WRITE(TEMP_1_TR_ENABLE_PIN, ENABLED(TEMP_SENSOR_1_IS_MAX_TC)); + OUT_WRITE(TEMP_1_TR_ENABLE_PIN, + #if TEMP_SENSOR_IS_ANY_MAX_TC(1) + 1 + #else + 0 + #endif + ); #endif #if HAS_HEATER_0 @@ -2206,6 +2271,9 @@ void Temperature::init() { #if HAS_TEMP_ADC_PROBE HAL_ANALOG_SELECT(TEMP_PROBE_PIN); #endif + #if HAS_TEMP_ADC_REDUNDANT + HAL_ANALOG_SELECT(TEMP_REDUNDANT_PIN); + #endif #if ENABLED(FILAMENT_WIDTH_SENSOR) HAL_ANALOG_SELECT(FILWIDTH_PIN); #endif @@ -2268,7 +2336,7 @@ void Temperature::init() { temp_range[NR].raw_max -= TEMPDIR(NR) * (OVERSAMPLENR); \ }while(0) - #define _MINMAX_TEST(N,M) (HOTENDS > N && TEMP_SENSOR_ ##N## _THERMISTOR_ID && TEMP_SENSOR_ ##N## _THERMISTOR_ID != 998 && TEMP_SENSOR_ ##N## _THERMISTOR_ID != 999 && defined(HEATER_##N##_##M##TEMP)) + #define _MINMAX_TEST(N,M) (HOTENDS > N && TEMP_SENSOR_##N > 0 && TEMP_SENSOR_##N != 998 && TEMP_SENSOR_##N != 999 && defined(HEATER_##N##_##M##TEMP)) #if _MINMAX_TEST(0, MIN) _TEMP_MIN_E(0); @@ -2335,6 +2403,22 @@ void Temperature::init() { while (analog_to_celsius_cooler(mintemp_raw_COOLER) > COOLER_MINTEMP) mintemp_raw_COOLER += TEMPDIR(COOLER) * (OVERSAMPLENR); while (analog_to_celsius_cooler(maxtemp_raw_COOLER) < COOLER_MAXTEMP) maxtemp_raw_COOLER -= TEMPDIR(COOLER) * (OVERSAMPLENR); #endif + + #if HAS_TEMP_REDUNDANT + temp_redundant.target = &( + #if TEMP_SENSOR_REDUNDANT_TARGET == -5 && HAS_TEMP_COOLER + temp_cooler + #elif TEMP_SENSOR_REDUNDANT_TARGET == -4 && HAS_TEMP_PROBE + temp_probe + #elif TEMP_SENSOR_REDUNDANT_TARGET == -2 && HAS_TEMP_CHAMBER + temp_chamber + #elif TEMP_SENSOR_REDUNDANT_TARGET == -1 && HAS_TEMP_BED + temp_bed + #else + temp_hotend[TEMP_SENSOR_REDUNDANT_TARGET] + #endif + ); + #endif } #if HAS_THERMAL_PROTECTION @@ -2373,7 +2457,7 @@ void Temperature::init() { , " ; Idle Timeout:", heater_idle[idle_index].timed_out #endif ); - //*/ + */ #if HEATER_IDLE_HANDLER // If the heater idle timeout expires, restart @@ -2526,7 +2610,7 @@ void Temperature::disable_all_heaters() { if (singlenozzle_temp[new_tool] && singlenozzle_temp[new_tool] != singlenozzle_temp[old_tool]) { setTargetHotend(singlenozzle_temp[new_tool], 0); TERN_(AUTOTEMP, planner.autotemp_update()); - TERN_(HAS_STATUS_MESSAGE, set_heating_message(0)); + set_heating_message(0); (void)wait_for_hotend(0, false); // Wait for heating or cooling } #endif @@ -2570,12 +2654,12 @@ void Temperature::disable_all_heaters() { #else constexpr uint8_t hindex = 0; #define THERMO_TEMP(I) max_tc_temp - #if TEMP_SENSOR_1_IS_MAX31865 + #if TEMP_SENSOR_IS_ANY_MAX_TC(1) #define THERMO_SEL(A,B) B #else #define THERMO_SEL(A,B) A #endif - #if TEMP_SENSOR_0_IS_MAX6675 + #if TEMP_SENSOR_IS_MAX(0, MAX6675) #define MAX6675_WRITE(V) WRITE(MAX6675_SS_PIN, V) #define MAX6675_SET_OUTPUT() SET_OUTPUT(MAX6675_SS_PIN) #else @@ -2723,12 +2807,12 @@ void Temperature::update_raw_temperatures() { temp_hotend[0].update(); #endif - #if HAS_TEMP_ADC_1 - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - temp_redundant.update(); - #elif !TEMP_SENSOR_1_IS_MAX_TC - temp_hotend[1].update(); - #endif + #if HAS_TEMP_ADC_1 && !TEMP_SENSOR_1_IS_MAX_TC + temp_hotend[1].update(); + #endif + + #if HAS_TEMP_ADC_REDUNDANT && !TEMP_SENSOR_REDUNDANT_IS_MAX_TC + temp_redundant.update(); #endif TERN_(HAS_TEMP_ADC_2, temp_hotend[2].update()); @@ -2764,13 +2848,13 @@ void Temperature::readings_ready() { #if HAS_HOTEND HOTEND_LOOP() temp_hotend[e].reset(); - TERN_(TEMP_SENSOR_1_AS_REDUNDANT, temp_redundant.reset()); #endif TERN_(HAS_HEATED_BED, temp_bed.reset()); TERN_(HAS_TEMP_CHAMBER, temp_chamber.reset()); TERN_(HAS_TEMP_PROBE, temp_probe.reset()); TERN_(HAS_TEMP_COOLER, temp_cooler.reset()); + TERN_(HAS_TEMP_REDUNDANT, temp_redundant.reset()); TERN_(HAS_JOY_ADC_X, joystick.x.reset()); TERN_(HAS_JOY_ADC_Y, joystick.y.reset()); @@ -3196,9 +3280,14 @@ void Temperature::isr() { case MeasureTemp_PROBE: ACCUMULATE_ADC(temp_probe); break; #endif + #if HAS_TEMP_ADC_REDUNDANT + case PrepareTemp_REDUNDANT: HAL_START_ADC(TEMP_REDUNDANT_PIN); break; + case MeasureTemp_REDUNDANT: ACCUMULATE_ADC(temp_redundant); break; + #endif + #if HAS_TEMP_ADC_1 case PrepareTemp_1: HAL_START_ADC(TEMP_1_PIN); break; - case MeasureTemp_1: ACCUMULATE_ADC(TERN(TEMP_SENSOR_1_AS_REDUNDANT, temp_redundant, temp_hotend[1])); break; + case MeasureTemp_1: ACCUMULATE_ADC(temp_hotend[1]); break; #endif #if HAS_TEMP_ADC_2 @@ -3332,14 +3421,12 @@ void Temperature::isr() { * Chamber: " C:nnn.nn /nnn.nn" * Probe: " P:nnn.nn /nnn.nn" * Cooler: " L:nnn.nn /nnn.nn" + * Redundant: " R:nnn.nn /nnn.nn" * Extruder: " T0:nnn.nn /nnn.nn" * With ADC: " T0:nnn.nn /nnn.nn (nnn.nn)" */ - static void print_heater_state(const_celsius_float_t c, const_celsius_float_t t - #if ENABLED(SHOW_TEMP_ADC_VALUES) - , const float r - #endif - , const heater_id_t e=INDEX_NONE + static void print_heater_state(const heater_id_t e, const_celsius_float_t c, const_celsius_float_t t + OPTARG(SHOW_TEMP_ADC_VALUES, const float r) ) { char k; switch (e) { @@ -3359,7 +3446,7 @@ void Temperature::isr() { #if HAS_TEMP_COOLER case H_COOLER: k = 'L'; break; #endif - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) + #if HAS_TEMP_REDUNDANT case H_REDUNDANT: k = 'R'; break; #endif } @@ -3385,64 +3472,28 @@ void Temperature::isr() { } void Temperature::print_heater_states(const uint8_t target_extruder - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - , const bool include_r/*=false*/ - #endif + OPTARG(HAS_TEMP_REDUNDANT, const bool include_r/*=false*/) ) { #if HAS_TEMP_HOTEND - print_heater_state(degHotend(target_extruder), degTargetHotend(target_extruder) - #if ENABLED(SHOW_TEMP_ADC_VALUES) - , rawHotendTemp(target_extruder) - #endif - ); - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - if (include_r) print_heater_state(degHotendRedundant(), degTargetHotend(0) - #if ENABLED(SHOW_TEMP_ADC_VALUES) - , rawHotendTempRedundant() - #endif - , H_REDUNDANT - ); - #endif + print_heater_state(H_NONE, degHotend(target_extruder), degTargetHotend(target_extruder) OPTARG(SHOW_TEMP_ADC_VALUES, rawHotendTemp(target_extruder))); #endif #if HAS_HEATED_BED - print_heater_state(degBed(), degTargetBed() - #if ENABLED(SHOW_TEMP_ADC_VALUES) - , rawBedTemp() - #endif - , H_BED - ); + print_heater_state(H_BED, degBed(), degTargetBed() OPTARG(SHOW_TEMP_ADC_VALUES, rawBedTemp())); #endif #if HAS_TEMP_CHAMBER - print_heater_state(degChamber(), TERN0(HAS_HEATED_CHAMBER, degTargetChamber()) - #if ENABLED(SHOW_TEMP_ADC_VALUES) - , rawChamberTemp() - #endif - , H_CHAMBER - ); - #endif // HAS_TEMP_CHAMBER + print_heater_state(H_CHAMBER, degChamber(), TERN0(HAS_HEATED_CHAMBER, degTargetChamber()) OPTARG(SHOW_TEMP_ADC_VALUES, rawChamberTemp())); + #endif #if HAS_TEMP_COOLER - print_heater_state(degCooler(), TERN0(HAS_COOLER, degTargetCooler()) - #if ENABLED(SHOW_TEMP_ADC_VALUES) - , rawCoolerTemp() - #endif - , H_COOLER - ); - #endif // HAS_TEMP_COOLER + print_heater_state(H_COOLER, degCooler(), TERN0(HAS_COOLER, degTargetCooler()) OPTARG(SHOW_TEMP_ADC_VALUES, rawCoolerTemp())); + #endif #if HAS_TEMP_PROBE - print_heater_state(degProbe(), 0 - #if ENABLED(SHOW_TEMP_ADC_VALUES) - , rawProbeTemp() - #endif - , H_PROBE - ); + print_heater_state(H_PROBE, degProbe(), 0 OPTARG(SHOW_TEMP_ADC_VALUES, rawProbeTemp()) ); + #endif + #if HAS_TEMP_REDUNDANT + if (include_r) print_heater_state(H_REDUNDANT, degRedundant(), degRedundantTarget() OPTARG(SHOW_TEMP_ADC_VALUES, rawRedundantTemp())); #endif #if HAS_MULTI_HOTEND - HOTEND_LOOP() print_heater_state(degHotend(e), degTargetHotend(e) - #if ENABLED(SHOW_TEMP_ADC_VALUES) - , rawHotendTemp(e) - #endif - , (heater_id_t)e - ); + HOTEND_LOOP() print_heater_state((heater_id_t)e, degHotend(e), degTargetHotend(e) OPTARG(SHOW_TEMP_ADC_VALUES, rawHotendTemp(e))); #endif SERIAL_ECHOPAIR(" @:", getHeaterPower((heater_id_t)target_extruder)); #if HAS_HEATED_BED @@ -3465,10 +3516,7 @@ void Temperature::isr() { #if ENABLED(AUTO_REPORT_TEMPERATURES) AutoReporter Temperature::auto_reporter; - void Temperature::AutoReportTemp::report() { - print_heater_states(active_extruder); - SERIAL_EOL(); - } + void Temperature::AutoReportTemp::report() { print_heater_states(active_extruder); SERIAL_EOL(); } #endif #if HAS_HOTEND && HAS_STATUS_MESSAGE @@ -3495,11 +3543,8 @@ void Temperature::isr() { #endif bool Temperature::wait_for_hotend(const uint8_t target_extruder, const bool no_wait_for_cooling/*=true*/ - #if G26_CLICK_CAN_CANCEL - , const bool click_to_cancel/*=false*/ - #endif + OPTARG(G26_CLICK_CAN_CANCEL, const bool click_to_cancel/*=false*/) ) { - #if ENABLED(AUTOTEMP) REMEMBER(1, planner.autotemp_enabled, false); #endif @@ -3593,7 +3638,7 @@ void Temperature::isr() { #if G26_CLICK_CAN_CANCEL if (click_to_cancel && ui.use_click()) { wait_for_heatup = false; - ui.quick_feedback(); + TERN_(HAS_LCD_MENU, ui.quick_feedback()); } #endif @@ -3638,9 +3683,7 @@ void Temperature::isr() { #endif bool Temperature::wait_for_bed(const bool no_wait_for_cooling/*=true*/ - #if G26_CLICK_CAN_CANCEL - , const bool click_to_cancel/*=false*/ - #endif + OPTARG(G26_CLICK_CAN_CANCEL, const bool click_to_cancel/*=false*/) ) { #if TEMP_BED_RESIDENCY_TIME > 0 millis_t residency_start_ms = 0; @@ -3729,7 +3772,7 @@ void Temperature::isr() { #if G26_CLICK_CAN_CANCEL if (click_to_cancel && ui.use_click()) { wait_for_heatup = false; - ui.quick_feedback(); + TERN_(HAS_LCD_MENU, ui.quick_feedback()); } #endif diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index 7ad58e9ab8bd1..3a8c506a5db09 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -46,7 +46,7 @@ // Element identifiers. Positive values are hotends. Negative values are other heaters or coolers. typedef enum : int8_t { - INDEX_NONE = -6, + H_NONE = -6, H_COOLER, H_PROBE, H_REDUNDANT, H_CHAMBER, H_BED, H_E0, H_E1, H_E2, H_E3, H_E4, H_E5, H_E6, H_E7 } heater_id_t; @@ -105,6 +105,9 @@ enum ADCSensorState : char { #if HAS_TEMP_ADC_PROBE PrepareTemp_PROBE, MeasureTemp_PROBE, #endif + #if HAS_TEMP_ADC_REDUNDANT + PrepareTemp_REDUNDANT, MeasureTemp_REDUNDANT, + #endif #if HAS_TEMP_ADC_1 PrepareTemp_1, MeasureTemp_1, #endif @@ -171,7 +174,7 @@ enum ADCSensorState : char { #define unscalePID_d(d) ( float(d) * PID_dT ) #endif -#if BOTH(HAS_LCD_MENU, G26_MESH_VALIDATION) +#if ENABLED(G26_MESH_VALIDATION) && EITHER(HAS_LCD_MENU, EXTENSIBLE_UI) #define G26_CLICK_CAN_CANCEL 1 #endif @@ -185,6 +188,13 @@ typedef struct TempInfo { inline void update() { raw = acc; } } temp_info_t; +#if HAS_TEMP_REDUNDANT + // A redundant temperature sensor + typedef struct RedundantTempInfo : public TempInfo { + temp_info_t* target; + } redundant_temp_info_t; +#endif + // A PWM heater with temperature sensor typedef struct HeaterInfo : public TempInfo { celsius_t target; @@ -299,9 +309,12 @@ typedef struct { int16_t raw_min, raw_max; celsius_t mintemp, maxtemp; } temp_ra #if TEMP_SENSOR_CHAMBER_IS_CUSTOM CTI_CHAMBER, #endif - #if COOLER_USER_THERMISTOR + #if TEMP_SENSOR_COOLER_IS_CUSTOM CTI_COOLER, #endif + #if TEMP_SENSOR_REDUNDANT_IS_CUSTOM + CTI_REDUNDANT, + #endif USER_THERMISTORS }; @@ -323,9 +336,6 @@ class Temperature { public: #if HAS_HOTEND - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - static temp_info_t temp_redundant; - #endif static hotend_info_t temp_hotend[HOTENDS]; static const celsius_t hotend_maxtemp[HOTENDS]; static inline celsius_t hotend_max_target(const uint8_t e) { return hotend_maxtemp[e] - (HOTEND_OVERSHOOT); } @@ -342,6 +352,9 @@ class Temperature { #if ENABLED(HAS_TEMP_COOLER) static cooler_info_t temp_cooler; #endif + #if HAS_TEMP_REDUNDANT + static redundant_temp_info_t temp_redundant; + #endif #if ENABLED(AUTO_POWER_E_FANS) static uint8_t autofan_speed[HOTENDS]; @@ -395,21 +408,21 @@ class Temperature { } heater_idle_t; // Indices and size for the heater_idle array - #define _ENUM_FOR_E(N) IDLE_INDEX_E##N, - enum IdleIndex : uint8_t { - REPEAT(HOTENDS, _ENUM_FOR_E) - #if ENABLED(HAS_HEATED_BED) - IDLE_INDEX_BED, - #endif - NR_HEATER_IDLE + enum IdleIndex : int8_t { + _II = -1 + + #define _IDLE_INDEX_E(N) ,IDLE_INDEX_E##N + REPEAT(HOTENDS, _IDLE_INDEX_E) + #undef _IDLE_INDEX_E + + OPTARG(HAS_HEATED_BED, IDLE_INDEX_BED) + + , NR_HEATER_IDLE }; - #undef _ENUM_FOR_E // Convert the given heater_id_t to idle array index static inline IdleIndex idle_index_for_id(const int8_t heater_id) { - #if HAS_HEATED_BED - if (heater_id == H_BED) return IDLE_INDEX_BED; - #endif + TERN_(HAS_HEATED_BED, if (heater_id == H_BED) return IDLE_INDEX_BED); return (IdleIndex)_MAX(heater_id, 0); } @@ -538,6 +551,9 @@ class Temperature { #if HAS_TEMP_COOLER static celsius_float_t analog_to_celsius_cooler(const int16_t raw); #endif + #if HAS_TEMP_REDUNDANT + static celsius_float_t analog_to_celsius_redundant(const int16_t raw); + #endif #if HAS_FAN @@ -626,10 +642,6 @@ class Temperature { return TERN0(HAS_HOTEND, temp_hotend[HOTEND_INDEX].celsius); } - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - static inline celsius_float_t degHotendRedundant() { return temp_redundant.celsius; } - #endif - static inline celsius_t wholeDegHotend(const uint8_t E_NAME) { return TERN0(HAS_HOTEND, static_cast(temp_hotend[HOTEND_INDEX].celsius + 0.5f)); } @@ -638,9 +650,6 @@ class Temperature { static inline int16_t rawHotendTemp(const uint8_t E_NAME) { return TERN0(HAS_HOTEND, temp_hotend[HOTEND_INDEX].raw); } - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - static inline int16_t rawHotendTempRedundant() { return temp_redundant.raw; } - #endif #endif static inline celsius_t degTargetHotend(const uint8_t E_NAME) { @@ -672,9 +681,7 @@ class Temperature { #if HAS_TEMP_HOTEND static bool wait_for_hotend(const uint8_t target_extruder, const bool no_wait_for_cooling=true - #if G26_CLICK_CAN_CANCEL - , const bool click_to_cancel=false - #endif + OPTARG(G26_CLICK_CAN_CANCEL, const bool click_to_cancel=false) ); #if ENABLED(WAIT_FOR_HOTEND) @@ -721,9 +728,7 @@ class Temperature { } static bool wait_for_bed(const bool no_wait_for_cooling=true - #if G26_CLICK_CAN_CANCEL - , const bool click_to_cancel=false - #endif + OPTARG(G26_CLICK_CAN_CANCEL, const bool click_to_cancel=false) ); static void wait_for_bed_heating(); @@ -782,6 +787,17 @@ class Temperature { #endif #endif + #if HAS_TEMP_REDUNDANT + #if ENABLED(SHOW_TEMP_ADC_VALUES) + static inline int16_t rawRedundantTemp() { return temp_redundant.raw; } + static inline int16_t rawRedundanTargetTemp() { return (*temp_redundant.target).raw; } + #endif + static inline celsius_float_t degRedundant() { return temp_redundant.celsius; } + static inline celsius_float_t degRedundantTarget() { return (*temp_redundant.target).celsius; } + static inline celsius_t wholeDegRedundant() { return static_cast(temp_redundant.celsius + 0.5f); } + static inline celsius_t wholeDegRedundantTarget() { return static_cast((*temp_redundant.target).celsius + 0.5f); } + #endif + #if HAS_COOLER static inline void setTargetCooler(const celsius_t celsius) { temp_cooler.target = constrain(celsius, COOLER_MIN_TARGET, COOLER_MAX_TARGET); @@ -859,9 +875,7 @@ class Temperature { #if HAS_TEMP_SENSOR static void print_heater_states(const uint8_t target_extruder - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - , const bool include_r=false - #endif + OPTARG(HAS_TEMP_REDUNDANT, const bool include_r=false) ); #if ENABLED(AUTO_REPORT_TEMPERATURES) struct AutoReportTemp { static void report(); }; @@ -869,8 +883,10 @@ class Temperature { #endif #endif - #if HAS_STATUS_MESSAGE + #if HAS_HOTEND && HAS_STATUS_MESSAGE static void set_heating_message(const uint8_t e); + #else + static inline void set_heating_message(const uint8_t) {} #endif #if HAS_LCD_MENU && HAS_TEMPERATURE @@ -892,7 +908,7 @@ class Temperature { // MAX Thermocouples #if HAS_MAX_TC - #define MAX_TC_COUNT 1 + BOTH(TEMP_SENSOR_0_IS_MAX_TC, TEMP_SENSOR_1_IS_MAX_TC) + #define MAX_TC_COUNT COUNT_ENABLED(TEMP_SENSOR_0_IS_MAX_TC, TEMP_SENSOR_1_IS_MAX_TC, TEMP_SENSOR_REDUNDANT_IS_MAX_TC) #if MAX_TC_COUNT > 1 #define HAS_MULTI_MAX_TC 1 #define READ_MAX_TC(N) read_max_tc(N) @@ -923,35 +939,24 @@ class Temperature { #if HAS_THERMAL_PROTECTION // Indices and size for the tr_state_machine array. One for each protected heater. - #define _ENUM_FOR_E(N) RUNAWAY_IND_E##N, - enum RunawayIndex : uint8_t { + enum RunawayIndex : int8_t { + _RI = -1 #if ENABLED(THERMAL_PROTECTION_HOTENDS) - REPEAT(HOTENDS, _ENUM_FOR_E) - #endif - #if ENABLED(HAS_THERMALLY_PROTECTED_BED) - RUNAWAY_IND_BED, - #endif - #if ENABLED(THERMAL_PROTECTION_CHAMBER) - RUNAWAY_IND_CHAMBER, - #endif - #if ENABLED(THERMAL_PROTECTION_COOLER) - RUNAWAY_IND_COOLER, + #define _RUNAWAY_IND_E(N) ,RUNAWAY_IND_E##N + REPEAT(HOTENDS, _RUNAWAY_IND_E) + #undef _RUNAWAY_IND_E #endif - NR_HEATER_RUNAWAY + OPTARG(HAS_THERMALLY_PROTECTED_BED, RUNAWAY_IND_BED) + OPTARG(THERMAL_PROTECTION_CHAMBER, RUNAWAY_IND_CHAMBER) + OPTARG(THERMAL_PROTECTION_COOLER, RUNAWAY_IND_COOLER) + , NR_HEATER_RUNAWAY }; - #undef _ENUM_FOR_E // Convert the given heater_id_t to runaway state array index static inline RunawayIndex runaway_index_for_id(const int8_t heater_id) { - #if HAS_THERMALLY_PROTECTED_CHAMBER - if (heater_id == H_CHAMBER) return RUNAWAY_IND_CHAMBER; - #endif - #if HAS_THERMALLY_PROTECTED_CHAMBER - if (heater_id == H_COOLER) return RUNAWAY_IND_COOLER; - #endif - #if HAS_THERMALLY_PROTECTED_BED - if (heater_id == H_BED) return RUNAWAY_IND_BED; - #endif + TERN_(HAS_THERMALLY_PROTECTED_CHAMBER, if (heater_id == H_CHAMBER) return RUNAWAY_IND_CHAMBER); + TERN_(HAS_THERMALLY_PROTECTED_CHAMBER, if (heater_id == H_COOLER) return RUNAWAY_IND_COOLER); + TERN_(HAS_THERMALLY_PROTECTED_BED, if (heater_id == H_BED) return RUNAWAY_IND_BED); return (RunawayIndex)_MAX(heater_id, 0); } diff --git a/Marlin/src/module/thermistor/thermistor_1.h b/Marlin/src/module/thermistor/thermistor_1.h index fad790837571f..2ebf8da550a0c 100644 --- a/Marlin/src/module/thermistor/thermistor_1.h +++ b/Marlin/src/module/thermistor/thermistor_1.h @@ -22,7 +22,7 @@ #pragma once // R25 = 100 kOhm, beta25 = 4092 K, 4.7 kOhm pull-up, bed thermistor -const temp_entry_t temptable_1[] PROGMEM = { +constexpr temp_entry_t temptable_1[] PROGMEM = { { OV( 23), 300 }, { OV( 25), 295 }, { OV( 27), 290 }, diff --git a/Marlin/src/module/thermistor/thermistor_10.h b/Marlin/src/module/thermistor/thermistor_10.h index c24ad40bf483b..9f2285c3fd837 100644 --- a/Marlin/src/module/thermistor/thermistor_10.h +++ b/Marlin/src/module/thermistor/thermistor_10.h @@ -22,7 +22,7 @@ #pragma once // R25 = 100 kOhm, beta25 = 3960 K, 4.7 kOhm pull-up, RS thermistor 198-961 -const temp_entry_t temptable_10[] PROGMEM = { +constexpr temp_entry_t temptable_10[] PROGMEM = { { OV( 1), 929 }, { OV( 36), 299 }, { OV( 71), 246 }, diff --git a/Marlin/src/module/thermistor/thermistor_1010.h b/Marlin/src/module/thermistor/thermistor_1010.h index 8ab5e3b364c63..6f2e3ab318f2d 100644 --- a/Marlin/src/module/thermistor/thermistor_1010.h +++ b/Marlin/src/module/thermistor/thermistor_1010.h @@ -24,7 +24,7 @@ #define REVERSE_TEMP_SENSOR_RANGE_1010 1 // Pt1000 with 1k0 pullup -const temp_entry_t temptable_1010[] PROGMEM = { +constexpr temp_entry_t temptable_1010[] PROGMEM = { PtLine( 0, 1000, 1000), PtLine( 25, 1000, 1000), PtLine( 50, 1000, 1000), diff --git a/Marlin/src/module/thermistor/thermistor_1047.h b/Marlin/src/module/thermistor/thermistor_1047.h index 6e1b61f9d073c..fb901d0a8d021 100644 --- a/Marlin/src/module/thermistor/thermistor_1047.h +++ b/Marlin/src/module/thermistor/thermistor_1047.h @@ -24,7 +24,7 @@ #define REVERSE_TEMP_SENSOR_RANGE_1047 1 // Pt1000 with 4k7 pullup -const temp_entry_t temptable_1047[] PROGMEM = { +constexpr temp_entry_t temptable_1047[] PROGMEM = { // only a few values are needed as the curve is very flat PtLine( 0, 1000, 4700), PtLine( 50, 1000, 4700), diff --git a/Marlin/src/module/thermistor/thermistor_11.h b/Marlin/src/module/thermistor/thermistor_11.h index 345d009a6498b..52f89814e732e 100644 --- a/Marlin/src/module/thermistor/thermistor_11.h +++ b/Marlin/src/module/thermistor/thermistor_11.h @@ -22,7 +22,7 @@ #pragma once // R25 = 100 kOhm, beta25 = 3950 K, 4.7 kOhm pull-up, QU-BD silicone bed QWG-104F-3950 thermistor -const temp_entry_t temptable_11[] PROGMEM = { +constexpr temp_entry_t temptable_11[] PROGMEM = { { OV( 1), 938 }, { OV( 31), 314 }, { OV( 41), 290 }, diff --git a/Marlin/src/module/thermistor/thermistor_110.h b/Marlin/src/module/thermistor/thermistor_110.h index 215495e2c6a13..5d76d1ee1bda8 100644 --- a/Marlin/src/module/thermistor/thermistor_110.h +++ b/Marlin/src/module/thermistor/thermistor_110.h @@ -24,7 +24,7 @@ #define REVERSE_TEMP_SENSOR_RANGE_110 1 // Pt100 with 1k0 pullup -const temp_entry_t temptable_110[] PROGMEM = { +constexpr temp_entry_t temptable_110[] PROGMEM = { // only a few values are needed as the curve is very flat PtLine( 0, 100, 1000), PtLine( 50, 100, 1000), diff --git a/Marlin/src/module/thermistor/thermistor_12.h b/Marlin/src/module/thermistor/thermistor_12.h index d1ee23b2b7f77..c0cbd254cffc8 100644 --- a/Marlin/src/module/thermistor/thermistor_12.h +++ b/Marlin/src/module/thermistor/thermistor_12.h @@ -22,7 +22,7 @@ #pragma once // R25 = 100 kOhm, beta25 = 4700 K, 4.7 kOhm pull-up, (personal calibration for Makibox hot bed) -const temp_entry_t temptable_12[] PROGMEM = { +constexpr temp_entry_t temptable_12[] PROGMEM = { { OV( 35), 180 }, // top rating 180C { OV( 211), 140 }, { OV( 233), 135 }, diff --git a/Marlin/src/module/thermistor/thermistor_13.h b/Marlin/src/module/thermistor/thermistor_13.h index bb622240c82d3..7e87373948a21 100644 --- a/Marlin/src/module/thermistor/thermistor_13.h +++ b/Marlin/src/module/thermistor/thermistor_13.h @@ -22,7 +22,7 @@ #pragma once // R25 = 100 kOhm, beta25 = 4100 K, 4.7 kOhm pull-up, Hisens thermistor -const temp_entry_t temptable_13[] PROGMEM = { +constexpr temp_entry_t temptable_13[] PROGMEM = { { OV( 20.04), 300 }, { OV( 23.19), 290 }, { OV( 26.71), 280 }, diff --git a/Marlin/src/module/thermistor/thermistor_147.h b/Marlin/src/module/thermistor/thermistor_147.h index 6d846ad5bed7d..542e4844ec6b3 100644 --- a/Marlin/src/module/thermistor/thermistor_147.h +++ b/Marlin/src/module/thermistor/thermistor_147.h @@ -24,7 +24,7 @@ #define REVERSE_TEMP_SENSOR_RANGE_147 1 // Pt100 with 4k7 pullup -const temp_entry_t temptable_147[] PROGMEM = { +constexpr temp_entry_t temptable_147[] PROGMEM = { // only a few values are needed as the curve is very flat PtLine( 0, 100, 4700), PtLine( 50, 100, 4700), diff --git a/Marlin/src/module/thermistor/thermistor_15.h b/Marlin/src/module/thermistor/thermistor_15.h index 46dcce8c1e4f8..ce9824879357a 100644 --- a/Marlin/src/module/thermistor/thermistor_15.h +++ b/Marlin/src/module/thermistor/thermistor_15.h @@ -22,7 +22,7 @@ #pragma once // 100k bed thermistor in JGAurora A5. Calibrated by Sam Pinches 21st Jan 2018 using cheap k-type thermocouple inserted into heater block, using TM-902C meter. -const temp_entry_t temptable_15[] PROGMEM = { +constexpr temp_entry_t temptable_15[] PROGMEM = { { OV( 31), 275 }, { OV( 33), 270 }, { OV( 35), 260 }, diff --git a/Marlin/src/module/thermistor/thermistor_17.h b/Marlin/src/module/thermistor/thermistor_17.h index 32b5bb77a8883..55d3bc39d0afa 100644 --- a/Marlin/src/module/thermistor/thermistor_17.h +++ b/Marlin/src/module/thermistor/thermistor_17.h @@ -22,7 +22,7 @@ #pragma once // Dagoma NTC 100k white thermistor -const temp_entry_t temptable_17[] PROGMEM = { +constexpr temp_entry_t temptable_17[] PROGMEM = { { OV( 16), 309 }, { OV( 18), 307 }, { OV( 20), 300 }, diff --git a/Marlin/src/module/thermistor/thermistor_18.h b/Marlin/src/module/thermistor/thermistor_18.h index 9c2d81b3e6984..061cf78129e06 100644 --- a/Marlin/src/module/thermistor/thermistor_18.h +++ b/Marlin/src/module/thermistor/thermistor_18.h @@ -22,7 +22,7 @@ #pragma once // ATC Semitec 204GT-2 (4.7k pullup) Dagoma.Fr - MKS_Base_DKU001327 - version (measured/tested/approved) -const temp_entry_t temptable_18[] PROGMEM = { +constexpr temp_entry_t temptable_18[] PROGMEM = { { OV( 1), 713 }, { OV( 17), 284 }, { OV( 20), 275 }, diff --git a/Marlin/src/module/thermistor/thermistor_2.h b/Marlin/src/module/thermistor/thermistor_2.h index d0e1e4f3dfca0..a899fd17ee0f9 100644 --- a/Marlin/src/module/thermistor/thermistor_2.h +++ b/Marlin/src/module/thermistor/thermistor_2.h @@ -26,7 +26,7 @@ // Verified by linagee. Source: https://www.mouser.com/datasheet/2/362/semitec%20usa%20corporation_gtthermistor-1202937.pdf // Calculated using 4.7kohm pullup, voltage divider math, and manufacturer provided temp/resistance // -const temp_entry_t temptable_2[] PROGMEM = { +constexpr temp_entry_t temptable_2[] PROGMEM = { { OV( 1), 848 }, { OV( 30), 300 }, // top rating 300C { OV( 34), 290 }, diff --git a/Marlin/src/module/thermistor/thermistor_20.h b/Marlin/src/module/thermistor/thermistor_20.h index 73094f14604df..a8267e93e4a6b 100644 --- a/Marlin/src/module/thermistor/thermistor_20.h +++ b/Marlin/src/module/thermistor/thermistor_20.h @@ -24,7 +24,7 @@ #define REVERSE_TEMP_SENSOR_RANGE_20 1 // Pt100 with INA826 amp on Ultimaker v2.0 electronics -const temp_entry_t temptable_20[] PROGMEM = { +constexpr temp_entry_t temptable_20[] PROGMEM = { { OV( 0), 0 }, { OV(227), 1 }, { OV(236), 10 }, diff --git a/Marlin/src/module/thermistor/thermistor_201.h b/Marlin/src/module/thermistor/thermistor_201.h index 44d52806813aa..9c083a2d1bf0a 100644 --- a/Marlin/src/module/thermistor/thermistor_201.h +++ b/Marlin/src/module/thermistor/thermistor_201.h @@ -24,7 +24,7 @@ #define REVERSE_TEMP_SENSOR_RANGE_201 1 // Pt100 with LMV324 amp on Overlord v1.1 electronics -const temp_entry_t temptable_201[] PROGMEM = { +constexpr temp_entry_t temptable_201[] PROGMEM = { { OV( 0), 0 }, { OV( 8), 1 }, { OV( 23), 6 }, diff --git a/Marlin/src/module/thermistor/thermistor_202.h b/Marlin/src/module/thermistor/thermistor_202.h index c5229607ae332..e1b0ee258e799 100644 --- a/Marlin/src/module/thermistor/thermistor_202.h +++ b/Marlin/src/module/thermistor/thermistor_202.h @@ -3,7 +3,7 @@ // Temptable sent from dealer technologyoutlet.co.uk // -const temp_entry_t temptable_202[] PROGMEM = { +constexpr temp_entry_t temptable_202[] PROGMEM = { { OV( 1), 864 }, { OV( 35), 300 }, { OV( 38), 295 }, diff --git a/Marlin/src/module/thermistor/thermistor_21.h b/Marlin/src/module/thermistor/thermistor_21.h index 2ca705b95005e..f8a5de2e150d1 100644 --- a/Marlin/src/module/thermistor/thermistor_21.h +++ b/Marlin/src/module/thermistor/thermistor_21.h @@ -28,7 +28,7 @@ // Pt100 with INA826 amplifier board with 5v supply based on Thermistor 20, with 3v3 ADC reference on the mainboard. // If the ADC reference and INA826 board supply voltage are identical, Thermistor 20 instead. -const temp_entry_t temptable_21[] PROGMEM = { +constexpr temp_entry_t temptable_21[] PROGMEM = { { OV( 0), 0 }, { OV(227), 1 }, { OV(236), 10 }, diff --git a/Marlin/src/module/thermistor/thermistor_22.h b/Marlin/src/module/thermistor/thermistor_22.h index 6f4a31050add0..90e1af8c1a6c9 100644 --- a/Marlin/src/module/thermistor/thermistor_22.h +++ b/Marlin/src/module/thermistor/thermistor_22.h @@ -21,7 +21,7 @@ */ // 100k hotend thermistor with 4.7k pull up to 3.3v and 220R to analog input as in GTM32 Pro vB -const temp_entry_t temptable_22[] PROGMEM = { +constexpr temp_entry_t temptable_22[] PROGMEM = { { OV( 1), 352 }, { OV( 6), 341 }, { OV( 11), 330 }, diff --git a/Marlin/src/module/thermistor/thermistor_23.h b/Marlin/src/module/thermistor/thermistor_23.h index 02ff9fb2b6c89..9b806af5b77f4 100644 --- a/Marlin/src/module/thermistor/thermistor_23.h +++ b/Marlin/src/module/thermistor/thermistor_23.h @@ -21,7 +21,7 @@ */ // 100k hotbed thermistor with 4.7k pull up to 3.3v and 220R to analog input as in GTM32 Pro vB -const temp_entry_t temptable_23[] PROGMEM = { +constexpr temp_entry_t temptable_23[] PROGMEM = { { OV( 1), 938 }, { OV( 11), 423 }, { OV( 21), 351 }, diff --git a/Marlin/src/module/thermistor/thermistor_3.h b/Marlin/src/module/thermistor/thermistor_3.h index 74e00e2ba4f44..cb6d75738ed22 100644 --- a/Marlin/src/module/thermistor/thermistor_3.h +++ b/Marlin/src/module/thermistor/thermistor_3.h @@ -22,7 +22,7 @@ #pragma once // R25 = 100 kOhm, beta25 = 4120 K, 4.7 kOhm pull-up, mendel-parts -const temp_entry_t temptable_3[] PROGMEM = { +constexpr temp_entry_t temptable_3[] PROGMEM = { { OV( 1), 864 }, { OV( 21), 300 }, { OV( 25), 290 }, diff --git a/Marlin/src/module/thermistor/thermistor_30.h b/Marlin/src/module/thermistor/thermistor_30.h index bc1781b1351cd..daf4d29aa761d 100644 --- a/Marlin/src/module/thermistor/thermistor_30.h +++ b/Marlin/src/module/thermistor/thermistor_30.h @@ -28,7 +28,7 @@ // B Value Tolerance + / - 1% // Kis3d Silicone Heater 24V 200W/300W with 6mm Precision cast plate (EN AW 5083) // Temperature setting time 10 min to determine the 12Bit ADC value on the surface. (le3tspeak) -const temp_entry_t temptable_30[] PROGMEM = { +constexpr temp_entry_t temptable_30[] PROGMEM = { { OV( 1), 938 }, { OV( 298), 125 }, // 1193 - 125° { OV( 321), 121 }, // 1285 - 121° diff --git a/Marlin/src/module/thermistor/thermistor_331.h b/Marlin/src/module/thermistor/thermistor_331.h index ccb0f6b62d2b2..847dbc30a03b6 100644 --- a/Marlin/src/module/thermistor/thermistor_331.h +++ b/Marlin/src/module/thermistor/thermistor_331.h @@ -24,7 +24,7 @@ #define OVM(V) OV((V)*(0.327/0.5)) // R25 = 100 kOhm, beta25 = 4092 K, 4.7 kOhm pull-up, bed thermistor -const temp_entry_t temptable_331[] PROGMEM = { +constexpr temp_entry_t temptable_331[] PROGMEM = { { OVM( 23), 300 }, { OVM( 25), 295 }, { OVM( 27), 290 }, diff --git a/Marlin/src/module/thermistor/thermistor_332.h b/Marlin/src/module/thermistor/thermistor_332.h index 9502f1bdae9ed..83a5d39f0fee5 100644 --- a/Marlin/src/module/thermistor/thermistor_332.h +++ b/Marlin/src/module/thermistor/thermistor_332.h @@ -24,7 +24,7 @@ #define OVM(V) OV((V)*(0.327/0.327)) // R25 = 100 kOhm, beta25 = 4092 K, 4.7 kOhm pull-up, bed thermistor -const temp_entry_t temptable_332[] PROGMEM = { +constexpr temp_entry_t temptable_332[] PROGMEM = { { OVM( 268), 150 }, { OVM( 293), 145 }, { OVM( 320), 141 }, diff --git a/Marlin/src/module/thermistor/thermistor_4.h b/Marlin/src/module/thermistor/thermistor_4.h index 92d907249be91..98192a1124548 100644 --- a/Marlin/src/module/thermistor/thermistor_4.h +++ b/Marlin/src/module/thermistor/thermistor_4.h @@ -22,7 +22,7 @@ #pragma once // R25 = 10 kOhm, beta25 = 3950 K, 4.7 kOhm pull-up, Generic 10k thermistor -const temp_entry_t temptable_4[] PROGMEM = { +constexpr temp_entry_t temptable_4[] PROGMEM = { { OV( 1), 430 }, { OV( 54), 137 }, { OV( 107), 107 }, diff --git a/Marlin/src/module/thermistor/thermistor_5.h b/Marlin/src/module/thermistor/thermistor_5.h index 1d5fa2fec739e..69ef99fae1eed 100644 --- a/Marlin/src/module/thermistor/thermistor_5.h +++ b/Marlin/src/module/thermistor/thermistor_5.h @@ -26,7 +26,7 @@ // ATC Semitec 104GT-2/104NT-4-R025H42G (Used in ParCan) // Verified by linagee. Source: https://www.mouser.com/datasheet/2/362/semitec%20usa%20corporation_gtthermistor-1202937.pdf // Calculated using 4.7kohm pullup, voltage divider math, and manufacturer provided temp/resistance -const temp_entry_t temptable_5[] PROGMEM = { +constexpr temp_entry_t temptable_5[] PROGMEM = { { OV( 1), 713 }, { OV( 17), 300 }, // top rating 300C { OV( 20), 290 }, diff --git a/Marlin/src/module/thermistor/thermistor_501.h b/Marlin/src/module/thermistor/thermistor_501.h index d40e341f7e31e..0e142628ec6b0 100644 --- a/Marlin/src/module/thermistor/thermistor_501.h +++ b/Marlin/src/module/thermistor/thermistor_501.h @@ -22,7 +22,7 @@ #pragma once // 100k Zonestar thermistor. Adjusted By Hally -const temp_entry_t temptable_501[] PROGMEM = { +constexpr temp_entry_t temptable_501[] PROGMEM = { { OV( 1), 713 }, { OV( 14), 300 }, // Top rating 300C { OV( 16), 290 }, diff --git a/Marlin/src/module/thermistor/thermistor_502.h b/Marlin/src/module/thermistor/thermistor_502.h index 69cee2431c5fc..3ddbf30d47ed3 100644 --- a/Marlin/src/module/thermistor/thermistor_502.h +++ b/Marlin/src/module/thermistor/thermistor_502.h @@ -23,7 +23,7 @@ // Unknown thermistor for the Zonestar P802M hot bed. Adjusted By Nerseth // These were the shipped settings from Zonestar in original firmware: P802M_8_Repetier_V1.6_Zonestar.zip -const temp_entry_t temptable_502[] PROGMEM = { +constexpr temp_entry_t temptable_502[] PROGMEM = { { OV( 56.0 / 4), 300 }, { OV( 187.0 / 4), 250 }, { OV( 615.0 / 4), 190 }, diff --git a/Marlin/src/module/thermistor/thermistor_503.h b/Marlin/src/module/thermistor/thermistor_503.h index fc4bffffdb58b..6ffe4b4a666f4 100644 --- a/Marlin/src/module/thermistor/thermistor_503.h +++ b/Marlin/src/module/thermistor/thermistor_503.h @@ -23,7 +23,7 @@ // Zonestar (Z8XM2) Heated Bed thermistor. Added By AvanOsch // These are taken from the Zonestar settings in original Repetier firmware: Z8XM2_ZRIB_LCD12864_V51.zip -const temp_entry_t temptable_503[] PROGMEM = { +constexpr temp_entry_t temptable_503[] PROGMEM = { { OV( 12), 300 }, { OV( 27), 270 }, { OV( 47), 250 }, diff --git a/Marlin/src/module/thermistor/thermistor_51.h b/Marlin/src/module/thermistor/thermistor_51.h index d02dd47ba5d17..ee63a0e61bbb1 100644 --- a/Marlin/src/module/thermistor/thermistor_51.h +++ b/Marlin/src/module/thermistor/thermistor_51.h @@ -26,7 +26,7 @@ // Verified by linagee. // Calculated using 1kohm pullup, voltage divider math, and manufacturer provided temp/resistance // Advantage: Twice the resolution and better linearity from 150C to 200C -const temp_entry_t temptable_51[] PROGMEM = { +constexpr temp_entry_t temptable_51[] PROGMEM = { { OV( 1), 350 }, { OV( 190), 250 }, // top rating 250C { OV( 203), 245 }, diff --git a/Marlin/src/module/thermistor/thermistor_512.h b/Marlin/src/module/thermistor/thermistor_512.h index e8021e1e48c4c..e380b4a16bfd0 100644 --- a/Marlin/src/module/thermistor/thermistor_512.h +++ b/Marlin/src/module/thermistor/thermistor_512.h @@ -22,7 +22,7 @@ // 100k thermistor supplied with RPW-Ultra hotend, 4.7k pullup -const temp_entry_t temptable_512[] PROGMEM = { +constexpr temp_entry_t temptable_512[] PROGMEM = { { OV(26), 300 }, { OV(28), 295 }, { OV(30), 290 }, diff --git a/Marlin/src/module/thermistor/thermistor_52.h b/Marlin/src/module/thermistor/thermistor_52.h index 5c9cb9dc4df92..f3bb75d4627fc 100644 --- a/Marlin/src/module/thermistor/thermistor_52.h +++ b/Marlin/src/module/thermistor/thermistor_52.h @@ -26,7 +26,7 @@ // Verified by linagee. Source: https://www.mouser.com/datasheet/2/362/semitec%20usa%20corporation_gtthermistor-1202937.pdf // Calculated using 1kohm pullup, voltage divider math, and manufacturer provided temp/resistance // Advantage: More resolution and better linearity from 150C to 200C -const temp_entry_t temptable_52[] PROGMEM = { +constexpr temp_entry_t temptable_52[] PROGMEM = { { OV( 1), 500 }, { OV( 125), 300 }, // top rating 300C { OV( 142), 290 }, diff --git a/Marlin/src/module/thermistor/thermistor_55.h b/Marlin/src/module/thermistor/thermistor_55.h index 707b7d420a12d..41004a97ef23d 100644 --- a/Marlin/src/module/thermistor/thermistor_55.h +++ b/Marlin/src/module/thermistor/thermistor_55.h @@ -26,7 +26,7 @@ // Verified by linagee. Source: https://www.mouser.com/datasheet/2/362/semitec%20usa%20corporation_gtthermistor-1202937.pdf // Calculated using 1kohm pullup, voltage divider math, and manufacturer provided temp/resistance // Advantage: More resolution and better linearity from 150C to 200C -const temp_entry_t temptable_55[] PROGMEM = { +constexpr temp_entry_t temptable_55[] PROGMEM = { { OV( 1), 500 }, { OV( 76), 300 }, { OV( 87), 290 }, diff --git a/Marlin/src/module/thermistor/thermistor_6.h b/Marlin/src/module/thermistor/thermistor_6.h index 68113419e5839..b5e79a9b0e728 100644 --- a/Marlin/src/module/thermistor/thermistor_6.h +++ b/Marlin/src/module/thermistor/thermistor_6.h @@ -22,7 +22,7 @@ #pragma once // R25 = 100 kOhm, beta25 = 4092 K, 8.2 kOhm pull-up, 100k Epcos (?) thermistor -const temp_entry_t temptable_6[] PROGMEM = { +constexpr temp_entry_t temptable_6[] PROGMEM = { { OV( 1), 350 }, { OV( 28), 250 }, // top rating 250C { OV( 31), 245 }, diff --git a/Marlin/src/module/thermistor/thermistor_60.h b/Marlin/src/module/thermistor/thermistor_60.h index a3fe50559fd0b..a057080e45c1c 100644 --- a/Marlin/src/module/thermistor/thermistor_60.h +++ b/Marlin/src/module/thermistor/thermistor_60.h @@ -31,7 +31,7 @@ // beta: 3950 // min adc: 1 at 0.0048828125 V // max adc: 1023 at 4.9951171875 V -const temp_entry_t temptable_60[] PROGMEM = { +constexpr temp_entry_t temptable_60[] PROGMEM = { { OV( 51), 272 }, { OV( 61), 258 }, { OV( 71), 247 }, diff --git a/Marlin/src/module/thermistor/thermistor_61.h b/Marlin/src/module/thermistor/thermistor_61.h index ed4c4c8859566..deeec356a1d62 100644 --- a/Marlin/src/module/thermistor/thermistor_61.h +++ b/Marlin/src/module/thermistor/thermistor_61.h @@ -30,7 +30,7 @@ // Resistance Tolerance + / -1% // B Value 3950K at 25/50 deg. C // B Value Tolerance + / - 1% -const temp_entry_t temptable_61[] PROGMEM = { +constexpr temp_entry_t temptable_61[] PROGMEM = { { OV( 2.00), 420 }, // Guestimate to ensure we dont lose a reading and drop temps to -50 when over { OV( 12.07), 350 }, { OV( 12.79), 345 }, diff --git a/Marlin/src/module/thermistor/thermistor_66.h b/Marlin/src/module/thermistor/thermistor_66.h index 0ad5994ea811e..3b057ac6960e4 100644 --- a/Marlin/src/module/thermistor/thermistor_66.h +++ b/Marlin/src/module/thermistor/thermistor_66.h @@ -22,7 +22,7 @@ #pragma once // R25 = 2.5 MOhm, beta25 = 4500 K, 4.7 kOhm pull-up, DyzeDesign 500 °C Thermistor -const temp_entry_t temptable_66[] PROGMEM = { +constexpr temp_entry_t temptable_66[] PROGMEM = { { OV( 17.5), 850 }, { OV( 17.9), 500 }, { OV( 21.7), 480 }, diff --git a/Marlin/src/module/thermistor/thermistor_666.h b/Marlin/src/module/thermistor/thermistor_666.h index 490dbd5f3ee95..bba3e606fc061 100644 --- a/Marlin/src/module/thermistor/thermistor_666.h +++ b/Marlin/src/module/thermistor/thermistor_666.h @@ -33,7 +33,7 @@ * B: 0.00031362 * C: -2.03978e-07 */ -const temp_entry_t temptable_666[] PROGMEM = { +constexpr temp_entry_t temptable_666[] PROGMEM = { { OV( 1), 794 }, { OV( 18), 288 }, { OV( 35), 234 }, diff --git a/Marlin/src/module/thermistor/thermistor_67.h b/Marlin/src/module/thermistor/thermistor_67.h index 7d6d7f697df31..10fa9310b1cfe 100644 --- a/Marlin/src/module/thermistor/thermistor_67.h +++ b/Marlin/src/module/thermistor/thermistor_67.h @@ -22,7 +22,7 @@ #pragma once // R25 = 500 KOhm, beta25 = 3800 K, 4.7 kOhm pull-up, SliceEngineering 450 °C Thermistor -const temp_entry_t temptable_67[] PROGMEM = { +constexpr temp_entry_t temptable_67[] PROGMEM = { { OV( 22 ), 500 }, { OV( 23 ), 490 }, { OV( 25 ), 480 }, diff --git a/Marlin/src/module/thermistor/thermistor_7.h b/Marlin/src/module/thermistor/thermistor_7.h index 7a737559841c6..964897859e843 100644 --- a/Marlin/src/module/thermistor/thermistor_7.h +++ b/Marlin/src/module/thermistor/thermistor_7.h @@ -22,7 +22,7 @@ #pragma once // R25 = 100 kOhm, beta25 = 3974 K, 4.7 kOhm pull-up, Honeywell 135-104LAG-J01 -const temp_entry_t temptable_7[] PROGMEM = { +constexpr temp_entry_t temptable_7[] PROGMEM = { { OV( 1), 941 }, { OV( 19), 362 }, { OV( 37), 299 }, // top rating 300C diff --git a/Marlin/src/module/thermistor/thermistor_70.h b/Marlin/src/module/thermistor/thermistor_70.h index 466b9255533ee..f0163dcabc9f1 100644 --- a/Marlin/src/module/thermistor/thermistor_70.h +++ b/Marlin/src/module/thermistor/thermistor_70.h @@ -26,7 +26,7 @@ // ANENG AN8009 DMM with a K-type probe used for measurements. // R25 = 100 kOhm, beta25 = 4100 K, 4.7 kOhm pull-up, bqh2 stock thermistor -const temp_entry_t temptable_70[] PROGMEM = { +constexpr temp_entry_t temptable_70[] PROGMEM = { { OV( 18), 270 }, { OV( 27), 248 }, { OV( 34), 234 }, diff --git a/Marlin/src/module/thermistor/thermistor_71.h b/Marlin/src/module/thermistor/thermistor_71.h index abd7fc5b986ef..c94b4d5bbc6ff 100644 --- a/Marlin/src/module/thermistor/thermistor_71.h +++ b/Marlin/src/module/thermistor/thermistor_71.h @@ -27,7 +27,7 @@ // Beta = 3974 // R1 = 0 Ohm // R2 = 4700 Ohm -const temp_entry_t temptable_71[] PROGMEM = { +constexpr temp_entry_t temptable_71[] PROGMEM = { { OV( 35), 300 }, { OV( 51), 269 }, { OV( 59), 258 }, diff --git a/Marlin/src/module/thermistor/thermistor_75.h b/Marlin/src/module/thermistor/thermistor_75.h index 79800d2e40484..bb2ecce7dcf8c 100644 --- a/Marlin/src/module/thermistor/thermistor_75.h +++ b/Marlin/src/module/thermistor/thermistor_75.h @@ -34,7 +34,7 @@ //#define HIGH_TEMP_RANGE_75 -const temp_entry_t temptable_75[] PROGMEM = { // Generic Silicon Heat Pad with NTC 100K MGB18-104F39050L32 thermistor +constexpr temp_entry_t temptable_75[] PROGMEM = { // Generic Silicon Heat Pad with NTC 100K MGB18-104F39050L32 thermistor { OV(111.06), 200 }, // v=0.542 r=571.747 res=0.501 degC/count #ifdef HIGH_TEMP_RANGE_75 diff --git a/Marlin/src/module/thermistor/thermistor_8.h b/Marlin/src/module/thermistor/thermistor_8.h index 9e19168fed0d7..4b0f791f16be2 100644 --- a/Marlin/src/module/thermistor/thermistor_8.h +++ b/Marlin/src/module/thermistor/thermistor_8.h @@ -22,7 +22,7 @@ #pragma once // R25 = 100 kOhm, beta25 = 3950 K, 10 kOhm pull-up, NTCS0603E3104FHT -const temp_entry_t temptable_8[] PROGMEM = { +constexpr temp_entry_t temptable_8[] PROGMEM = { { OV( 1), 704 }, { OV( 54), 216 }, { OV( 107), 175 }, diff --git a/Marlin/src/module/thermistor/thermistor_9.h b/Marlin/src/module/thermistor/thermistor_9.h index 29097420ec119..3830a7dfcce78 100644 --- a/Marlin/src/module/thermistor/thermistor_9.h +++ b/Marlin/src/module/thermistor/thermistor_9.h @@ -22,7 +22,7 @@ #pragma once // R25 = 100 kOhm, beta25 = 3960 K, 4.7 kOhm pull-up, GE Sensing AL03006-58.2K-97-G1 -const temp_entry_t temptable_9[] PROGMEM = { +constexpr temp_entry_t temptable_9[] PROGMEM = { { OV( 1), 936 }, { OV( 36), 300 }, { OV( 71), 246 }, diff --git a/Marlin/src/module/thermistor/thermistor_99.h b/Marlin/src/module/thermistor/thermistor_99.h index 839a511c09182..f813abae69819 100644 --- a/Marlin/src/module/thermistor/thermistor_99.h +++ b/Marlin/src/module/thermistor/thermistor_99.h @@ -24,7 +24,7 @@ // 100k bed thermistor with a 10K pull-up resistor - made by $ buildroot/share/scripts/createTemperatureLookupMarlin.py --rp=10000 -const temp_entry_t temptable_99[] PROGMEM = { +constexpr temp_entry_t temptable_99[] PROGMEM = { { OV( 5.81), 350 }, // v=0.028 r= 57.081 res=13.433 degC/count { OV( 6.54), 340 }, // v=0.032 r= 64.248 res=11.711 degC/count { OV( 7.38), 330 }, // v=0.036 r= 72.588 res=10.161 degC/count diff --git a/Marlin/src/module/thermistor/thermistor_998.h b/Marlin/src/module/thermistor/thermistor_998.h index e4cfbbaa0d2fe..753cdd40bc6a3 100644 --- a/Marlin/src/module/thermistor/thermistor_998.h +++ b/Marlin/src/module/thermistor/thermistor_998.h @@ -27,7 +27,7 @@ #define DUMMY_THERMISTOR_998_VALUE 25 #endif -const temp_entry_t temptable_998[] PROGMEM = { +constexpr temp_entry_t temptable_998[] PROGMEM = { { OV( 1), DUMMY_THERMISTOR_998_VALUE }, { OV(1023), DUMMY_THERMISTOR_998_VALUE } }; diff --git a/Marlin/src/module/thermistor/thermistor_999.h b/Marlin/src/module/thermistor/thermistor_999.h index 0271c47f8585e..41e44ef631890 100644 --- a/Marlin/src/module/thermistor/thermistor_999.h +++ b/Marlin/src/module/thermistor/thermistor_999.h @@ -27,7 +27,7 @@ #define DUMMY_THERMISTOR_999_VALUE 25 #endif -const temp_entry_t temptable_999[] PROGMEM = { +constexpr temp_entry_t temptable_999[] PROGMEM = { { OV( 1), DUMMY_THERMISTOR_999_VALUE }, { OV(1023), DUMMY_THERMISTOR_999_VALUE } }; diff --git a/Marlin/src/module/thermistor/thermistors.h b/Marlin/src/module/thermistor/thermistors.h index 97d268c303eb2..a6cd7c86dfd8c 100644 --- a/Marlin/src/module/thermistor/thermistors.h +++ b/Marlin/src/module/thermistor/thermistors.h @@ -42,7 +42,16 @@ #define OV_SCALE(N) (N) #define OV(N) int16_t(OV_SCALE(N) * (OVERSAMPLENR) * (THERMISTOR_TABLE_SCALE)) -#define ANY_THERMISTOR_IS(n) (TEMP_SENSOR_0_THERMISTOR_ID == n || TEMP_SENSOR_1_THERMISTOR_ID == n || TEMP_SENSOR_2_THERMISTOR_ID == n || TEMP_SENSOR_3_THERMISTOR_ID == n || TEMP_SENSOR_4_THERMISTOR_ID == n || TEMP_SENSOR_5_THERMISTOR_ID == n || TEMP_SENSOR_6_THERMISTOR_ID == n || TEMP_SENSOR_7_THERMISTOR_ID == n || TEMP_SENSOR_BED_THERMISTOR_ID == n || TEMP_SENSOR_CHAMBER_THERMISTOR_ID == n || TEMP_SENSOR_COOLER_THERMISTOR_ID == n || TEMP_SENSOR_PROBE_THERMISTOR_ID == n) +#define TEMP_SENSOR_IS(n,H) (n == TEMP_SENSOR_##H) +#define ANY_THERMISTOR_IS(n) ( TEMP_SENSOR_IS(n, 0) || TEMP_SENSOR_IS(n, 1) \ + || TEMP_SENSOR_IS(n, 2) || TEMP_SENSOR_IS(n, 3) \ + || TEMP_SENSOR_IS(n, 4) || TEMP_SENSOR_IS(n, 5) \ + || TEMP_SENSOR_IS(n, 6) || TEMP_SENSOR_IS(n, 7) \ + || TEMP_SENSOR_IS(n, BED) \ + || TEMP_SENSOR_IS(n, CHAMBER) \ + || TEMP_SENSOR_IS(n, COOLER) \ + || TEMP_SENSOR_IS(n, PROBE) \ + || TEMP_SENSOR_IS(n, REDUNDANT) ) typedef struct { int16_t value; celsius_t celsius; } temp_entry_t; @@ -198,146 +207,128 @@ typedef struct { int16_t value; celsius_t celsius; } temp_entry_t; #include "thermistor_999.h" #endif #if ANY_THERMISTOR_IS(1000) // Custom - const temp_entry_t temptable_1000[] PROGMEM = { { 0, 0 } }; + constexpr temp_entry_t temptable_1000[] PROGMEM = { { 0, 0 } }; #endif #define _TT_NAME(_N) temptable_ ## _N #define TT_NAME(_N) _TT_NAME(_N) - -#if TEMP_SENSOR_0_THERMISTOR_ID - #define TEMPTABLE_0 TT_NAME(TEMP_SENSOR_0_THERMISTOR_ID) +#if TEMP_SENSOR_0 > 0 + #define TEMPTABLE_0 TT_NAME(TEMP_SENSOR_0) #define TEMPTABLE_0_LEN COUNT(TEMPTABLE_0) -#elif TEMP_SENSOR_0_IS_THERMISTOR - #error "No heater 0 thermistor table specified" #else #define TEMPTABLE_0 nullptr #define TEMPTABLE_0_LEN 0 #endif -#if TEMP_SENSOR_1_THERMISTOR_ID - #define TEMPTABLE_1 TT_NAME(TEMP_SENSOR_1_THERMISTOR_ID) +#if TEMP_SENSOR_1 > 0 + #define TEMPTABLE_1 TT_NAME(TEMP_SENSOR_1) #define TEMPTABLE_1_LEN COUNT(TEMPTABLE_1) -#elif TEMP_SENSOR_1_IS_THERMISTOR - #error "No heater 1 thermistor table specified" #else #define TEMPTABLE_1 nullptr #define TEMPTABLE_1_LEN 0 #endif -#if TEMP_SENSOR_2_THERMISTOR_ID - #define TEMPTABLE_2 TT_NAME(TEMP_SENSOR_2_THERMISTOR_ID) +#if TEMP_SENSOR_2 > 0 + #define TEMPTABLE_2 TT_NAME(TEMP_SENSOR_2) #define TEMPTABLE_2_LEN COUNT(TEMPTABLE_2) -#elif TEMP_SENSOR_2_IS_THERMISTOR - #error "No heater 2 thermistor table specified" #else #define TEMPTABLE_2 nullptr #define TEMPTABLE_2_LEN 0 #endif -#if TEMP_SENSOR_3_THERMISTOR_ID - #define TEMPTABLE_3 TT_NAME(TEMP_SENSOR_3_THERMISTOR_ID) +#if TEMP_SENSOR_3 > 0 + #define TEMPTABLE_3 TT_NAME(TEMP_SENSOR_3) #define TEMPTABLE_3_LEN COUNT(TEMPTABLE_3) -#elif TEMP_SENSOR_3_IS_THERMISTOR - #error "No heater 3 thermistor table specified" #else #define TEMPTABLE_3 nullptr #define TEMPTABLE_3_LEN 0 #endif -#if TEMP_SENSOR_4_THERMISTOR_ID - #define TEMPTABLE_4 TT_NAME(TEMP_SENSOR_4_THERMISTOR_ID) +#if TEMP_SENSOR_4 > 0 + #define TEMPTABLE_4 TT_NAME(TEMP_SENSOR_4) #define TEMPTABLE_4_LEN COUNT(TEMPTABLE_4) -#elif TEMP_SENSOR_4_IS_THERMISTOR - #error "No heater 4 thermistor table specified" #else #define TEMPTABLE_4 nullptr #define TEMPTABLE_4_LEN 0 #endif -#if TEMP_SENSOR_5_THERMISTOR_ID - #define TEMPTABLE_5 TT_NAME(TEMP_SENSOR_5_THERMISTOR_ID) +#if TEMP_SENSOR_5 > 0 + #define TEMPTABLE_5 TT_NAME(TEMP_SENSOR_5) #define TEMPTABLE_5_LEN COUNT(TEMPTABLE_5) -#elif TEMP_SENSOR_5_IS_THERMISTOR - #error "No heater 5 thermistor table specified" #else #define TEMPTABLE_5 nullptr #define TEMPTABLE_5_LEN 0 #endif -#if TEMP_SENSOR_6_THERMISTOR_ID - #define TEMPTABLE_6 TT_NAME(TEMP_SENSOR_6_THERMISTOR_ID) +#if TEMP_SENSOR_6 > 0 + #define TEMPTABLE_6 TT_NAME(TEMP_SENSOR_6) #define TEMPTABLE_6_LEN COUNT(TEMPTABLE_6) -#elif TEMP_SENSOR_6_IS_THERMISTOR - #error "No heater 6 thermistor table specified" #else #define TEMPTABLE_6 nullptr #define TEMPTABLE_6_LEN 0 #endif -#if TEMP_SENSOR_7_THERMISTOR_ID - #define TEMPTABLE_7 TT_NAME(TEMP_SENSOR_7_THERMISTOR_ID) +#if TEMP_SENSOR_7 > 0 + #define TEMPTABLE_7 TT_NAME(TEMP_SENSOR_7) #define TEMPTABLE_7_LEN COUNT(TEMPTABLE_7) -#elif TEMP_SENSOR_7_IS_THERMISTOR - #error "No heater 7 thermistor table specified" #else #define TEMPTABLE_7 nullptr #define TEMPTABLE_7_LEN 0 #endif -#ifdef TEMP_SENSOR_BED_THERMISTOR_ID - #define TEMPTABLE_BED TT_NAME(TEMP_SENSOR_BED_THERMISTOR_ID) +#if TEMP_SENSOR_BED > 0 + #define TEMPTABLE_BED TT_NAME(TEMP_SENSOR_BED) #define TEMPTABLE_BED_LEN COUNT(TEMPTABLE_BED) -#elif TEMP_SENSOR_BED_IS_THERMISTOR - #error "No bed thermistor table specified" #else #define TEMPTABLE_BED_LEN 0 #endif -#ifdef TEMP_SENSOR_CHAMBER_THERMISTOR_ID - #define TEMPTABLE_CHAMBER TT_NAME(TEMP_SENSOR_CHAMBER_THERMISTOR_ID) +#if TEMP_SENSOR_CHAMBER > 0 + #define TEMPTABLE_CHAMBER TT_NAME(TEMP_SENSOR_CHAMBER) #define TEMPTABLE_CHAMBER_LEN COUNT(TEMPTABLE_CHAMBER) -#elif TEMP_SENSOR_CHAMBER_IS_THERMISTOR - #error "No chamber thermistor table specified" #else #define TEMPTABLE_CHAMBER_LEN 0 #endif -#ifdef TEMP_SENSOR_COOLER_THERMISTOR_ID - #define TEMPTABLE_COOLER TT_NAME(TEMP_SENSOR_COOLER_THERMISTOR_ID) +#if TEMP_SENSOR_COOLER > 0 + #define TEMPTABLE_COOLER TT_NAME(TEMP_SENSOR_COOLER) #define TEMPTABLE_COOLER_LEN COUNT(TEMPTABLE_COOLER) -#elif TEMP_SENSOR_COOLER_IS_THERMISTOR - #error "No cooler thermistor table specified" #else #define TEMPTABLE_COOLER_LEN 0 #endif -#ifdef TEMP_SENSOR_PROBE_THERMISTOR_ID - #define TEMPTABLE_PROBE TT_NAME(TEMP_SENSOR_PROBE_THERMISTOR_ID) + +#if TEMP_SENSOR_PROBE > 0 + #define TEMPTABLE_PROBE TT_NAME(TEMP_SENSOR_PROBE) #define TEMPTABLE_PROBE_LEN COUNT(TEMPTABLE_PROBE) -#elif TEMP_SENSOR_PROBE_IS_THERMISTOR - #error "No probe thermistor table specified" #else #define TEMPTABLE_PROBE_LEN 0 #endif +#if TEMP_SENSOR_REDUNDANT > 0 + #define TEMPTABLE_REDUNDANT TT_NAME(TEMP_SENSOR_REDUNDANT) + #define TEMPTABLE_REDUNDANT_LEN COUNT(TEMPTABLE_REDUNDANT) +#else + #define TEMPTABLE_REDUNDANT_LEN 0 +#endif + // The SCAN_THERMISTOR_TABLE macro needs alteration? -static_assert( - TEMPTABLE_0_LEN < 256 && TEMPTABLE_1_LEN < 256 - && TEMPTABLE_2_LEN < 256 && TEMPTABLE_3_LEN < 256 - && TEMPTABLE_4_LEN < 256 && TEMPTABLE_5_LEN < 256 - && TEMPTABLE_6_LEN < 256 && TEMPTABLE_7_LEN < 256 - && TEMPTABLE_BED_LEN < 256 && TEMPTABLE_CHAMBER_LEN < 256 - && TEMPTABLE_COOLER_LEN < 256 && TEMPTABLE_PROBE_LEN < 256, - "Temperature conversion tables over 255 entries need special consideration." +static_assert(255 > TEMPTABLE_0_LEN || 255 > TEMPTABLE_1_LEN || 255 > TEMPTABLE_2_LEN || 255 > TEMPTABLE_3_LEN + || 255 > TEMPTABLE_4_LEN || 255 > TEMPTABLE_5_LEN || 255 > TEMPTABLE_6_LEN || 255 > TEMPTABLE_7_LEN + || 255 > TEMPTABLE_BED_LEN + || 255 > TEMPTABLE_CHAMBER_LEN + || 255 > TEMPTABLE_COOLER_LEN + || 255 > TEMPTABLE_PROBE_LEN + || 255 > TEMPTABLE_REDUNDANT_LEN + , "Temperature conversion tables over 255 entries need special consideration." ); // Set the high and low raw values for the heaters // For thermistors the highest temperature results in the lowest ADC value // For thermocouples the highest temperature results in the highest ADC value -#define __TT_REV(N) REVERSE_TEMP_SENSOR_RANGE_##N -#define _TT_REV(N) __TT_REV(N) -#define TT_REV(N) _TT_REV(TEMP_SENSOR_##N##_THERMISTOR_ID) +#define _TT_REV(N) REVERSE_TEMP_SENSOR_RANGE_##N +#define TT_REV(N) TERN0(TEMP_SENSOR_##N##_IS_THERMISTOR, DEFER4(_TT_REV)(TEMP_SENSOR_##N)) #define _TT_REVRAW(N) !TEMP_SENSOR_##N##_IS_THERMISTOR #define TT_REVRAW(N) (TT_REV(N) || _TT_REVRAW(N)) @@ -522,6 +513,15 @@ static_assert( #define TEMP_SENSOR_PROBE_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE #endif #endif +#ifndef TEMP_SENSOR_REDUNDANT_RAW_HI_TEMP + #if TT_REVRAW(REDUNDANT) + #define TEMP_SENSOR_REDUNDANT_RAW_HI_TEMP MAX_RAW_THERMISTOR_VALUE + #define TEMP_SENSOR_REDUNDANT_RAW_LO_TEMP 0 + #else + #define TEMP_SENSOR_REDUNDANT_RAW_HI_TEMP 0 + #define TEMP_SENSOR_REDUNDANT_RAW_LO_TEMP MAX_RAW_THERMISTOR_VALUE + #endif +#endif #undef __TT_REV #undef _TT_REV diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index cc34acc14f123..5b478caa1a99f 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -49,7 +49,9 @@ bool toolchange_extruder_ready[EXTRUDERS]; #endif -#if EITHER(MAGNETIC_PARKING_EXTRUDER, TOOL_SENSOR) || defined(EVENT_GCODE_AFTER_TOOLCHANGE) || (ENABLED(PARKING_EXTRUDER) && PARKING_EXTRUDER_SOLENOIDS_DELAY > 0) +#if EITHER(MAGNETIC_PARKING_EXTRUDER, TOOL_SENSOR) \ + || defined(EVENT_GCODE_TOOLCHANGE_T0) || defined(EVENT_GCODE_TOOLCHANGE_T1) || defined(EVENT_GCODE_AFTER_TOOLCHANGE) \ + || (ENABLED(PARKING_EXTRUDER) && PARKING_EXTRUDER_SOLENOIDS_DELAY > 0) #include "../gcode/gcode.h" #endif @@ -1311,10 +1313,22 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { TERN_(HAS_FANMUX, fanmux_switch(active_extruder)); - #ifdef EVENT_GCODE_AFTER_TOOLCHANGE - if (!no_move && TERN1(DUAL_X_CARRIAGE, dual_x_carriage_mode == DXC_AUTO_PARK_MODE)) - gcode.process_subcommands_now_P(PSTR(EVENT_GCODE_AFTER_TOOLCHANGE)); - #endif + if (!no_move) { + #ifdef EVENT_GCODE_TOOLCHANGE_T0 + if (new_tool == 0) + gcode.process_subcommands_now_P(PSTR(EVENT_GCODE_TOOLCHANGE_T0)); + #endif + + #ifdef EVENT_GCODE_TOOLCHANGE_T1 + if (new_tool == 1) + gcode.process_subcommands_now_P(PSTR(EVENT_GCODE_TOOLCHANGE_T1)); + #endif + + #ifdef EVENT_GCODE_AFTER_TOOLCHANGE + if (TERN1(DUAL_X_CARRIAGE, dual_x_carriage_mode == DXC_AUTO_PARK_MODE)) + gcode.process_subcommands_now_P(PSTR(EVENT_GCODE_AFTER_TOOLCHANGE)); + #endif + } SERIAL_ECHO_MSG(STR_ACTIVE_EXTRUDER, active_extruder); @@ -1382,7 +1396,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { #if HAS_MULTI_HOTEND thermalManager.setTargetHotend(thermalManager.degTargetHotend(active_extruder), migration_extruder); TERN_(AUTOTEMP, planner.autotemp_update()); - TERN_(HAS_STATUS_MESSAGE, thermalManager.set_heating_message(0)); + thermalManager.set_heating_message(0); thermalManager.wait_for_hotend(active_extruder); #endif diff --git a/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h b/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h index 0760eee0abe19..5131069f6beaa 100644 --- a/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h +++ b/Marlin/src/pins/lpc1768/pins_AZSMZ_MINI.h @@ -37,8 +37,8 @@ // // Limit Switches // -#define X_MIN_PIN P1_24 -#define Y_MIN_PIN P1_26 +#define X_STOP_PIN P1_24 +#define Y_STOP_PIN P1_26 #define Z_MIN_PIN P1_28 #define Z_MAX_PIN P1_29 diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h index 0508c5b5a99e6..73b4d3e63ddf2 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -31,6 +31,20 @@ #define BOARD_CUSTOM_BUILD_FLAGS -DLPC_PINCFG_UART3_P4_28 #endif +// +// EEPROM +// +#if NO_EEPROM_SELECTED + //#define I2C_EEPROM // EEPROM on I2C-0 + //#define SDCARD_EEPROM_EMULATION +#endif + +#if ENABLED(I2C_EEPROM) + #define MARLIN_EEPROM_SIZE 0x8000 // 32Kb +#elif ENABLED(SDCARD_EEPROM_EMULATION) + #define MARLIN_EEPROM_SIZE 0x800 // 2Kb +#endif + // // Servos // diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h index 01f2303a359a3..066c65be3af8a 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_common.h @@ -139,14 +139,14 @@ #endif #if ENABLED(BTT_MOTOR_EXPANSION) - /** _____ _____ - * NC | . . | GND NC | . . | GND - * NC | . . | M1EN M2EN | . . | M3EN - * M1STP | . . M1DIR M1RX | . . M1DIAG - * M2DIR | . . | M2STP M2RX | . . | M2DIAG - * M3DIR | . . | M3STP M3RX | . . | M3DIAG - * ----- ----- - * EXP2 EXP1 + /** ______ ______ + * NC | 1 2 | GND NC | 1 2 | GND + * NC | 3 4 | M1EN M2EN | 3 4 | M3EN + * M1STP | 5 6 M1DIR M1RX | 5 6 M1DIAG + * M2DIR | 7 8 | M2STP M2RX | 7 8 | M2DIAG + * M3DIR | 9 10 | M3STP M3RX | 9 10 | M3DIAG + * ------ ------ + * EXP2 EXP1 * * NB In EXP_MOT_USE_EXP2_ONLY mode EXP1 is not used and M2EN and M3EN need to be jumpered to M1EN */ diff --git a/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h b/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h index 29fe3b528c08c..2972ac7560796 100644 --- a/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h +++ b/Marlin/src/pins/lpc1768/pins_SELENA_COMPACT.h @@ -40,11 +40,11 @@ // #define X_MIN_PIN P1_28 #define X_MAX_PIN P1_25 -#define Y_MIN_PIN P2_11 -#define Y_MAX_PIN -1 -#define Z_MIN_PIN P1_27 -#define Z_MAX_PIN -1 -#define Z_PROBE P1_22 +#define Y_STOP_PIN P2_11 +#define Z_STOP_PIN P1_27 +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN P1_22 +#endif // // Steppers @@ -95,22 +95,22 @@ // #if IS_RRD_FG_SC - #define LCD_PINS_RS P0_16 - #define LCD_PINS_ENABLE P0_18 - #define LCD_PINS_D4 P0_15 - #define LCD_PINS_D5 P1_00 - #define LCD_PINS_D6 P1_01 - #define LCD_PINS_D7 P1_04 - #define BEEPER_PIN P1_31 - - #define BTN_EN1 P3_25 - #define BTN_EN2 P3_26 - #define BTN_ENC P1_30 - - #define SD_DETECT_PIN -1 - - #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) - #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder - #endif + #define LCD_PINS_RS P0_16 + #define LCD_PINS_ENABLE P0_18 + #define LCD_PINS_D4 P0_15 + #define LCD_PINS_D5 P1_00 + #define LCD_PINS_D6 P1_01 + #define LCD_PINS_D7 P1_04 + #define BEEPER_PIN P1_31 + + #define BTN_EN1 P3_25 + #define BTN_EN2 P3_26 + #define BTN_ENC P1_30 + + #define SD_DETECT_PIN -1 + + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif #endif // IS_RRD_FG_SC diff --git a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h index 2e1e02f991349..4719dd81115b7 100644 --- a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h +++ b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h @@ -201,7 +201,15 @@ #define EXP1_09_PIN P0_16 #define EXP1_10_PIN P2_08 -#if HAS_WIRED_LCD +#if ENABLED(DWIN_CREALITY_LCD) + #error "DWIN_CREALITY_LCD requires a custom cable with TX = P0_15, RX = P0_16, and LCD_SERIAL_PORT 1. Comment out this line to continue." + + #define BEEPER_PIN EXP1_10_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_04_PIN + #define BTN_ENC EXP1_06_PIN + +#elif HAS_WIRED_LCD #if ENABLED(CR10_STOCKDISPLAY) @@ -264,5 +272,3 @@ #elif SD_CONNECTION_IS(CUSTOM_CABLE) #error "SD CUSTOM_CABLE is not compatible with SKR E3 Turbo." #endif - -#define ON_BOARD_SPI_DEVICE 1 // SPI1 diff --git a/Marlin/src/pins/mega/env_validate.h b/Marlin/src/pins/mega/env_validate.h index fe4a39a612efc..97c52d4e5e054 100644 --- a/Marlin/src/pins/mega/env_validate.h +++ b/Marlin/src/pins/mega/env_validate.h @@ -21,10 +21,12 @@ */ #pragma once -#if ENABLED(ALLOW_MEGA1280) && NOT_TARGET(__AVR_ATmega1280__, __AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560 or 1280' in 'Tools > Board.'" -#elif NOT_TARGET(__AVR_ATmega2560__) - #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" +#if NOT_TARGET(__AVR_ATmega2560__) + #if DISABLED(ALLOW_MEGA1280) + #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560' in 'Tools > Board.'" + #elif NOT_TARGET(__AVR_ATmega1280__) + #error "Oops! Select 'Arduino/Genuino Mega or Mega 2560 or 1280' in 'Tools > Board.'" + #endif #endif #undef ALLOW_MEGA1280 diff --git a/Marlin/src/pins/mega/pins_MALYAN_M180.h b/Marlin/src/pins/mega/pins_MALYAN_M180.h new file mode 100644 index 0000000000000..e244d294f1c63 --- /dev/null +++ b/Marlin/src/pins/mega/pins_MALYAN_M180.h @@ -0,0 +1,100 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +/** + * Malyan M180 pin assignments + * Contributed by Timo Birnschein (timo.birnschein@microforge.de) + */ + +#include "env_validate.h" + +#define BOARD_INFO_NAME "Malyan M180 v.2" +// +// Limit Switches +// +#define X_STOP_PIN 48 +#define Y_STOP_PIN 46 +#define Z_STOP_PIN 42 + +// +// Z Probe (when not Z_MIN_PIN) +// +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN -1 +#endif + +// +// Steppers +// +#define X_STEP_PIN 55 +#define X_DIR_PIN 54 +#define X_ENABLE_PIN 56 + +#define Y_STEP_PIN 59 +#define Y_DIR_PIN 58 +#define Y_ENABLE_PIN 60 + +#define Z_STEP_PIN 63 +#define Z_DIR_PIN 62 +#define Z_ENABLE_PIN 64 + +#define E0_STEP_PIN 25 +#define E0_DIR_PIN 24 +#define E0_ENABLE_PIN 26 + +#define E1_STEP_PIN 29 +#define E1_DIR_PIN 28 +#define E1_ENABLE_PIN 39 + +// +// Temperature Sensors +// +#define TEMP_BED_PIN 15 // Analog Input + +// Extruder thermocouples 0 and 1 are read out by two separate ICs using +// SPI for Max6675 Thermocouple +// Uses a separate SPI bus +#define THERMO_SCK_PIN 78 // E2 - SCK +#define THERMO_DO_PIN 3 // E5 - DO +#define THERMO_CS1_PIN 5 // E3 - CS0 +#define THERMO_CS2_PIN 2 // E4 - CS1 + +#define MAX6675_SS_PIN THERMO_CS1_PIN +#define MAX6675_SS2_PIN THERMO_CS2_PIN +#define MAX6675_SCK_PIN THERMO_SCK_PIN +#define MAX6675_DO_PIN THERMO_DO_PIN + +// +// Heaters / Fans +// +#define HEATER_0_PIN 6 +#define HEATER_1_PIN 11 +#define HEATER_BED_PIN 45 + +#ifndef FAN_PIN + #define FAN_PIN 7 // M106 Sxxx command supported and tested. M107 as well. +#endif + +#ifndef FAN_PIN1 + #define FAN_PIN1 12 // Currently Unsupported by Marlin +#endif diff --git a/Marlin/src/pins/mega/pins_PICA.h b/Marlin/src/pins/mega/pins_PICA.h index 81f631937708a..41afe5d891b37 100644 --- a/Marlin/src/pins/mega/pins_PICA.h +++ b/Marlin/src/pins/mega/pins_PICA.h @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ +#pragma once /** * Arduino Mega with PICA pin assignments diff --git a/Marlin/src/pins/mega/pins_PICAOLD.h b/Marlin/src/pins/mega/pins_PICAOLD.h index f53a4cdcd258d..e19ea744e5eb7 100644 --- a/Marlin/src/pins/mega/pins_PICAOLD.h +++ b/Marlin/src/pins/mega/pins_PICAOLD.h @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ +#pragma once #define HEATER_0_PIN 9 // E0 #define HEATER_1_PIN 10 // E1 diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index a8ed35b009530..88dd170a9effd 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -35,11 +35,6 @@ * These numbers are the same in any pin mapping. */ -#if HAS_EXTENDABLE_MMU - #define MAX_EXTRUDERS 15 -#else - #define MAX_EXTRUDERS 8 -#endif #define MAX_E_STEPPERS 8 #if MB(RAMPS_13_EFB, RAMPS_14_EFB, RAMPS_PLUS_EFB, RAMPS_14_RE_ARM_EFB, RAMPS_SMART_EFB, RAMPS_DUO_EFB, RAMPS4DUE_EFB) @@ -221,7 +216,7 @@ #elif MB(CNCONTROLS_15) #include "mega/pins_CNCONTROLS_15.h" // ATmega2560, ATmega1280 env:mega2560 env:mega1280 #elif MB(MIGHTYBOARD_REVE) - #include "mega/pins_MIGHTYBOARD_REVE.h" // ATmega2560, ATmega1280 env:mega2560ext env:mega1280 + #include "mega/pins_MIGHTYBOARD_REVE.h" // ATmega2560, ATmega1280 env:mega2560ext env:mega1280 env:MightyBoard1280 env:MightyBoard2560 #elif MB(CHEAPTRONIC) #include "mega/pins_CHEAPTRONIC.h" // ATmega2560 env:mega2560 #elif MB(CHEAPTRONIC_V2) @@ -270,6 +265,8 @@ #include "mega/pins_PICAOLD.h" // ATmega2560 env:mega2560 #elif MB(INTAMSYS40) #include "mega/pins_INTAMSYS40.h" // ATmega2560 env:mega2560 +#elif MB(MALYAN_M180) + #include "mega/pins_MALYAN_M180.h" // ATmega2560 env:mega2560 // // ATmega1281, ATmega2561 @@ -467,33 +464,33 @@ // #elif MB(STM32F103RE) - #include "stm32f1/pins_STM32F1R.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_STM32F1R.h" // STM32F103RE env:STM32F103RE env:STM32F103RE_maple #elif MB(MALYAN_M200) - #include "stm32f1/pins_MALYAN_M200.h" // STM32F1 env:STM32F103CB_malyan + #include "stm32f1/pins_MALYAN_M200.h" // STM32F103CB env:STM32F103CB_malyan env:STM32F103CB_malyan_maple #elif MB(STM3R_MINI) - #include "stm32f1/pins_STM3R_MINI.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_STM3R_MINI.h" // STM32F103VE? env:STM32F103VE env:STM32F103RE_maple #elif MB(GTM32_PRO_VB) - #include "stm32f1/pins_GTM32_PRO_VB.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_GTM32_PRO_VB.h" // STM32F103VE env:STM32F103VE env:STM32F103RE_maple #elif MB(GTM32_PRO_VD) - #include "stm32f1/pins_GTM32_PRO_VD.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_GTM32_PRO_VD.h" // STM32F103VE env:STM32F103VE env:STM32F103RE_maple #elif MB(GTM32_MINI) - #include "stm32f1/pins_GTM32_MINI.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_GTM32_MINI.h" // STM32F103VE env:STM32F103VE env:STM32F103RE_maple #elif MB(GTM32_MINI_A30) - #include "stm32f1/pins_GTM32_MINI_A30.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_GTM32_MINI_A30.h" // STM32F103VE env:STM32F103VE env:STM32F103RE_maple #elif MB(GTM32_REV_B) - #include "stm32f1/pins_GTM32_REV_B.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_GTM32_REV_B.h" // STM32F103VE env:STM32F103VE env:STM32F103RE_maple #elif MB(MORPHEUS) - #include "stm32f1/pins_MORPHEUS.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_MORPHEUS.h" // STM32F103RE env:STM32F103RE env:STM32F103RE_maple #elif MB(CHITU3D) - #include "stm32f1/pins_CHITU3D.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_CHITU3D.h" // STM32F103ZE env:STM32F103ZE env:STM32F103RE_maple #elif MB(MKS_ROBIN) - #include "stm32f1/pins_MKS_ROBIN.h" // STM32F1 env:mks_robin env:mks_robin_stm32 + #include "stm32f1/pins_MKS_ROBIN.h" // STM32F1 env:mks_robin env:mks_robin_maple #elif MB(MKS_ROBIN_MINI) #include "stm32f1/pins_MKS_ROBIN_MINI.h" // STM32F1 env:mks_robin_mini #elif MB(MKS_ROBIN_NANO) - #include "stm32f1/pins_MKS_ROBIN_NANO.h" // STM32F1 env:mks_robin_nano35 env:mks_robin_nano35_stm32 + #include "stm32f1/pins_MKS_ROBIN_NANO.h" // STM32F1 env:mks_robin_nano35 env:mks_robin_nano35_maple #elif MB(MKS_ROBIN_NANO_V2) - #include "stm32f1/pins_MKS_ROBIN_NANO_V2.h" // STM32F1 env:mks_robin_nano35 env:mks_robin_nano35_stm32 + #include "stm32f1/pins_MKS_ROBIN_NANO_V2.h" // STM32F1 env:mks_robin_nano35 env:mks_robin_nano35_maple #elif MB(MKS_ROBIN_LITE) #include "stm32f1/pins_MKS_ROBIN_LITE.h" // STM32F1 env:mks_robin_lite #elif MB(MKS_ROBIN_LITE3) @@ -501,7 +498,7 @@ #elif MB(MKS_ROBIN_PRO) #include "stm32f1/pins_MKS_ROBIN_PRO.h" // STM32F1 env:mks_robin_pro #elif MB(MKS_ROBIN_E3) - #include "stm32f1/pins_MKS_ROBIN_E3.h" // STM32F1 env:mks_robin_e3 + #include "stm32f1/pins_MKS_ROBIN_E3.h" // STM32F1 env:mks_robin_e3 env:mks_robin_e3_maple #elif MB(MKS_ROBIN_E3_V1_1) #include "stm32f1/pins_MKS_ROBIN_E3_V1_1.h" // STM32F1 env:mks_robin_e3 #elif MB(MKS_ROBIN_E3D) @@ -511,19 +508,19 @@ #elif MB(MKS_ROBIN_E3P) #include "stm32f1/pins_MKS_ROBIN_E3P.h" // STM32F1 env:mks_robin_e3p #elif MB(BTT_SKR_MINI_V1_1) - #include "stm32f1/pins_BTT_SKR_MINI_V1_1.h" // STM32F1 env:STM32F103RC_btt_stm32 env:STM32F103RC_btt_512K_stm32 env:STM32F103RC_btt_USB_stm32 env:STM32F103RC_btt_512K_USB_stm32 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB + #include "stm32f1/pins_BTT_SKR_MINI_V1_1.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_USB env:STM32F103RC_btt_maple env:STM32F103RC_btt_USB_maple #elif MB(BTT_SKR_MINI_E3_V1_0) - #include "stm32f1/pins_BTT_SKR_MINI_E3_V1_0.h" // STM32F1 env:STM32F103RC_btt_stm32 env:STM32F103RC_btt_512K_stm32 env:STM32F103RC_btt_USB_stm32 env:STM32F103RC_btt_512K_USB_stm32 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB + #include "stm32f1/pins_BTT_SKR_MINI_E3_V1_0.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_USB env:STM32F103RC_btt_maple env:STM32F103RC_btt_USB_maple #elif MB(BTT_SKR_MINI_E3_V1_2) - #include "stm32f1/pins_BTT_SKR_MINI_E3_V1_2.h" // STM32F1 env:STM32F103RC_btt_stm32 env:STM32F103RC_btt_512K_stm32 env:STM32F103RC_btt_USB_stm32 env:STM32F103RC_btt_512K_USB_stm32 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB + #include "stm32f1/pins_BTT_SKR_MINI_E3_V1_2.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_USB env:STM32F103RC_btt_maple env:STM32F103RC_btt_USB_maple #elif MB(BTT_SKR_MINI_E3_V2_0) - #include "stm32f1/pins_BTT_SKR_MINI_E3_V2_0.h" // STM32F1 env:STM32F103RC_btt_stm32 env:STM32F103RC_btt_512K_stm32 env:STM32F103RC_btt_USB_stm32 env:STM32F103RC_btt_512K_USB_stm32 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB + #include "stm32f1/pins_BTT_SKR_MINI_E3_V2_0.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_USB env:STM32F103RE_btt env:STM32F103RE_btt_USB env:STM32F103RC_btt_maple env:STM32F103RC_btt_USB_maple env:STM32F103RE_btt_maple env:STM32F103RE_btt_USB_maple #elif MB(BTT_SKR_MINI_MZ_V1_0) - #include "stm32f1/pins_BTT_SKR_MINI_MZ_V1_0.h" // STM32F1 env:STM32F103RC_btt_stm32 env:STM32F103RC_btt_512K_stm32 env:STM32F103RC_btt_USB_stm32 env:STM32F103RC_btt_512K_USB_stm32 env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB + #include "stm32f1/pins_BTT_SKR_MINI_MZ_V1_0.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_USB env:STM32F103RC_btt_maple env:STM32F103RC_btt_USB_maple #elif MB(BTT_SKR_E3_DIP) - #include "stm32f1/pins_BTT_SKR_E3_DIP.h" // STM32F1 env:STM32F103RE_btt env:STM32F103RE_btt_USB env:STM32F103RC_btt env:STM32F103RC_btt_512K env:STM32F103RC_btt_USB env:STM32F103RC_btt_512K_USB + #include "stm32f1/pins_BTT_SKR_E3_DIP.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_USB env:STM32F103RE_btt env:STM32F103RE_btt_USB env:STM32F103RC_btt_maple env:STM32F103RC_btt_USB_maple env:STM32F103RE_btt_maple env:STM32F103RE_btt_USB_maple #elif MB(BTT_SKR_CR6) - #include "stm32f1/pins_BTT_SKR_CR6.h" // STM32F1 env:STM32F103RE_btt env:STM32F103RE_btt_USB + #include "stm32f1/pins_BTT_SKR_CR6.h" // STM32F1 env:STM32F103RE_btt env:STM32F103RE_btt_USB env:STM32F103RE_btt_maple env:STM32F103RE_btt_USB_maple #elif MB(JGAURORA_A5S_A1) #include "stm32f1/pins_JGAURORA_A5S_A1.h" // STM32F1 env:jgaurora_a5s_a1 #elif MB(FYSETC_AIO_II) @@ -541,17 +538,17 @@ #elif MB(CHITU3D_V6) #include "stm32f1/pins_CHITU3D_V6.h" // STM32F1 env:chitu_f103 #elif MB(CREALITY_V4) - #include "stm32f1/pins_CREALITY_V4.h" // STM32F1 env:STM32F103RET6_creality + #include "stm32f1/pins_CREALITY_V4.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_maple #elif MB(CREALITY_V4210) - #include "stm32f1/pins_CREALITY_V4210.h" // STM32F1 env:STM32F103RET6_creality + #include "stm32f1/pins_CREALITY_V4210.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_maple #elif MB(CREALITY_V427) - #include "stm32f1/pins_CREALITY_V427.h" // STM32F1 env:STM32F103RET6_creality + #include "stm32f1/pins_CREALITY_V427.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_maple #elif MB(CREALITY_V431) - #include "stm32f1/pins_CREALITY_V431.h" // STM32F1 env:STM32F103RET6_creality + #include "stm32f1/pins_CREALITY_V431.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_maple #elif MB(CREALITY_V452) - #include "stm32f1/pins_CREALITY_V452.h" // STM32F1 env:STM32F103RET6_creality + #include "stm32f1/pins_CREALITY_V452.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_maple #elif MB(CREALITY_V453) - #include "stm32f1/pins_CREALITY_V453.h" // STM32F1 env:STM32F103RET6_creality + #include "stm32f1/pins_CREALITY_V453.h" // STM32F1 env:STM32F103RET6_creality env:STM32F103RET6_creality_maple #elif MB(TRIGORILLA_PRO) #include "stm32f1/pins_TRIGORILLA_PRO.h" // STM32F1 env:trigorilla_pro #elif MB(FLY_MINI) @@ -559,9 +556,9 @@ #elif MB(FLSUN_HISPEED) #include "stm32f1/pins_FLSUN_HISPEED.h" // STM32F1 env:flsun_hispeedv1 #elif MB(BEAST) - #include "stm32f1/pins_BEAST.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_BEAST.h" // STM32F103VE? env:STM32F103VE env:STM32F103RE_maple #elif MB(MINGDA_MPX_ARM_MINI) - #include "stm32f1/pins_MINGDA_MPX_ARM_MINI.h" // STM32F1 env:STM32F103RE + #include "stm32f1/pins_MINGDA_MPX_ARM_MINI.h" // STM32F1 env:mingda_mpx_arm_mini // // ARM Cortex-M4F @@ -601,7 +598,9 @@ #elif MB(BTT_SKR_V2_0_REV_B) #include "stm32f4/pins_BTT_SKR_V2_0_REV_B.h" // STM32F4 env:BIGTREE_SKR_2 #elif MB(BTT_OCTOPUS_V1_0) - #include "stm32f4/pins_BTT_OCTOPUS_V1_0.h" // STM32F4 env:BIGTREE_OCTOPUS_V1_0 env:BIGTREE_OCTOPUS_V1_0_USB + #include "stm32f4/pins_BTT_OCTOPUS_V1_0.h" // STM32F4 env:BIGTREE_OCTOPUS_V1 env:BIGTREE_OCTOPUS_V1_USB +#elif MB(BTT_OCTOPUS_V1_1) + #include "stm32f4/pins_BTT_OCTOPUS_V1_1.h" // STM32F4 env:BIGTREE_OCTOPUS_V1 env:BIGTREE_OCTOPUS_V1_USB #elif MB(LERDGE_K) #include "stm32f4/pins_LERDGE_K.h" // STM32F4 env:LERDGEK env:LERDGEK_usb_flash_drive #elif MB(LERDGE_S) diff --git a/Marlin/src/pins/pinsDebug_list.h b/Marlin/src/pins/pinsDebug_list.h index 8eee4f18fb15b..1ab7188b701ad 100644 --- a/Marlin/src/pins/pinsDebug_list.h +++ b/Marlin/src/pins/pinsDebug_list.h @@ -1319,6 +1319,105 @@ #if PIN_EXISTS(Z_MIN_PROBE) REPORT_NAME_DIGITAL(__LINE__, Z_MIN_PROBE_PIN) #endif +#if PIN_EXISTS(I_ATT) + REPORT_NAME_DIGITAL(__LINE__, I_ATT_PIN) +#endif +#if PIN_EXISTS(I_CS) + REPORT_NAME_DIGITAL(__LINE__, I_CS_PIN) +#endif +#if PIN_EXISTS(I_DIR) + REPORT_NAME_DIGITAL(__LINE__, I_DIR_PIN) +#endif +#if PIN_EXISTS(I_ENABLE) + REPORT_NAME_DIGITAL(__LINE__, I_ENABLE_PIN) +#endif +#if PIN_EXISTS(I_MAX) + REPORT_NAME_DIGITAL(__LINE__, I_MAX_PIN) +#endif +#if PIN_EXISTS(I_MIN) + REPORT_NAME_DIGITAL(__LINE__, I_MIN_PIN) +#endif +#if PIN_EXISTS(I_MS1) + REPORT_NAME_DIGITAL(__LINE__, I_MS1_PIN) +#endif +#if PIN_EXISTS(I_MS2) + REPORT_NAME_DIGITAL(__LINE__, I_MS2_PIN) +#endif +#if PIN_EXISTS(I_MS3) + REPORT_NAME_DIGITAL(__LINE__, I_MS3_PIN) +#endif +#if PIN_EXISTS(I_STEP) + REPORT_NAME_DIGITAL(__LINE__, I_STEP_PIN) +#endif +#if PIN_EXISTS(I_STOP) + REPORT_NAME_DIGITAL(__LINE__, I_STOP_PIN) +#endif +#if PIN_EXISTS(J_ATT) + REPORT_NAME_DIGITAL(__LINE__, J_ATT_PIN) +#endif +#if PIN_EXISTS(J_CS) + REPORT_NAME_DIGITAL(__LINE__, J_CS_PIN) +#endif +#if PIN_EXISTS(J_DIR) + REPORT_NAME_DIGITAL(__LINE__, J_DIR_PIN) +#endif +#if PIN_EXISTS(J_ENABLE) + REPORT_NAME_DIGITAL(__LINE__, J_ENABLE_PIN) +#endif +#if PIN_EXISTS(J_MAX) + REPORT_NAME_DIGITAL(__LINE__, J_MAX_PIN) +#endif +#if PIN_EXISTS(J_MIN) + REPORT_NAME_DIGITAL(__LINE__, J_MIN_PIN) +#endif +#if PIN_EXISTS(J_MS1) + REPORT_NAME_DIGITAL(__LINE__, J_MS1_PIN) +#endif +#if PIN_EXISTS(J_MS2) + REPORT_NAME_DIGITAL(__LINE__, J_MS2_PIN) +#endif +#if PIN_EXISTS(J_MS3) + REPORT_NAME_DIGITAL(__LINE__, J_MS3_PIN) +#endif +#if PIN_EXISTS(J_STEP) + REPORT_NAME_DIGITAL(__LINE__, J_STEP_PIN) +#endif +#if PIN_EXISTS(J_STOP) + REPORT_NAME_DIGITAL(__LINE__, J_STOP_PIN) +#endif +#if PIN_EXISTS(K_ATT) + REPORT_NAME_DIGITAL(__LINE__, K_ATT_PIN) +#endif +#if PIN_EXISTS(K_CS) + REPORT_NAME_DIGITAL(__LINE__, K_CS_PIN) +#endif +#if PIN_EXISTS(K_DIR) + REPORT_NAME_DIGITAL(__LINE__, K_DIR_PIN) +#endif +#if PIN_EXISTS(K_ENABLE) + REPORT_NAME_DIGITAL(__LINE__, K_ENABLE_PIN) +#endif +#if PIN_EXISTS(K_MAX) + REPORT_NAME_DIGITAL(__LINE__, K_MAX_PIN) +#endif +#if PIN_EXISTS(K_MIN) + REPORT_NAME_DIGITAL(__LINE__, K_MIN_PIN) +#endif +#if PIN_EXISTS(K_MS1) + REPORT_NAME_DIGITAL(__LINE__, K_MS1_PIN) +#endif +#if PIN_EXISTS(K_MS2) + REPORT_NAME_DIGITAL(__LINE__, K_MS2_PIN) +#endif +#if PIN_EXISTS(K_MS3) + REPORT_NAME_DIGITAL(__LINE__, K_MS3_PIN) +#endif +#if PIN_EXISTS(K_STEP) + REPORT_NAME_DIGITAL(__LINE__, K_STEP_PIN) +#endif +#if PIN_EXISTS(K_STOP) + REPORT_NAME_DIGITAL(__LINE__, K_STOP_PIN) +#endif #if PIN_EXISTS(ZRIB_V20_D6) REPORT_NAME_DIGITAL(__LINE__, ZRIB_V20_D6_PIN) #endif diff --git a/Marlin/src/pins/pins_postprocess.h b/Marlin/src/pins/pins_postprocess.h index 37ebbd47addb7..ac4459bd028c4 100644 --- a/Marlin/src/pins/pins_postprocess.h +++ b/Marlin/src/pins/pins_postprocess.h @@ -212,6 +212,15 @@ #if !AXIS_HAS_SPI(Z) #undef Z_CS_PIN #endif +#if !AXIS_HAS_SPI(I) + #undef I_CS_PIN +#endif +#if !AXIS_HAS_SPI(J) + #undef J_CS_PIN +#endif +#if !AXIS_HAS_SPI(K) + #undef K_CS_PIN +#endif #if E_STEPPERS && !AXIS_HAS_SPI(E0) #undef E0_CS_PIN #endif @@ -246,6 +255,15 @@ #ifndef Z_CS_PIN #define Z_CS_PIN -1 #endif +#ifndef I_CS_PIN + #define I_CS_PIN -1 +#endif +#ifndef J_CS_PIN + #define J_CS_PIN -1 +#endif +#ifndef K_CS_PIN + #define K_CS_PIN -1 +#endif #ifndef E0_CS_PIN #define E0_CS_PIN -1 #endif @@ -402,124 +420,92 @@ #define X_STOP_PIN X_MAX_PIN #endif -#ifdef Y_STOP_PIN - #if Y_HOME_TO_MIN - #define Y_MIN_PIN Y_STOP_PIN - #ifndef Y_MAX_PIN - #define Y_MAX_PIN -1 +#if HAS_Y_AXIS + #ifdef Y_STOP_PIN + #if Y_HOME_TO_MIN + #define Y_MIN_PIN Y_STOP_PIN + #ifndef Y_MAX_PIN + #define Y_MAX_PIN -1 + #endif + #else + #define Y_MAX_PIN Y_STOP_PIN + #ifndef Y_MIN_PIN + #define Y_MIN_PIN -1 + #endif #endif + #elif Y_HOME_TO_MIN + #define Y_STOP_PIN Y_MIN_PIN #else - #define Y_MAX_PIN Y_STOP_PIN - #ifndef Y_MIN_PIN - #define Y_MIN_PIN -1 - #endif + #define Y_STOP_PIN Y_MAX_PIN #endif -#elif Y_HOME_TO_MIN - #define Y_STOP_PIN Y_MIN_PIN -#else - #define Y_STOP_PIN Y_MAX_PIN #endif -#ifdef Z_STOP_PIN - #if Z_HOME_TO_MIN - #define Z_MIN_PIN Z_STOP_PIN - #ifndef Z_MAX_PIN - #define Z_MAX_PIN -1 +#if HAS_Z_AXIS + #ifdef Z_STOP_PIN + #if Z_HOME_TO_MIN + #define Z_MIN_PIN Z_STOP_PIN + #ifndef Z_MAX_PIN + #define Z_MAX_PIN -1 + #endif + #else + #define Z_MAX_PIN Z_STOP_PIN + #ifndef Z_MIN_PIN + #define Z_MIN_PIN -1 + #endif #endif + #elif Z_HOME_TO_MIN + #define Z_STOP_PIN Z_MIN_PIN #else - #define Z_MAX_PIN Z_STOP_PIN - #ifndef Z_MIN_PIN - #define Z_MIN_PIN -1 + #define Z_STOP_PIN Z_MAX_PIN + #endif +#endif + +#if LINEAR_AXES >= 4 + #ifdef I_STOP_PIN + #if I_HOME_TO_MIN + #define I_MIN_PIN I_STOP_PIN + #define I_MAX_PIN -1 + #else + #define I_MIN_PIN -1 + #define I_MAX_PIN I_STOP_PIN #endif #endif -#elif Z_HOME_TO_MIN - #define Z_STOP_PIN Z_MIN_PIN #else - #define Z_STOP_PIN Z_MAX_PIN + #undef I_MIN_PIN + #undef I_MAX_PIN #endif -// -// Disable unused endstop / probe pins -// -#define _STOP_IN_USE(N) (X2_USE_ENDSTOP == N || Y2_USE_ENDSTOP == N || Z2_USE_ENDSTOP == N || Z3_USE_ENDSTOP == N || Z4_USE_ENDSTOP == N) -#if _STOP_IN_USE(_XMAX_) - #define USE_XMAX_PLUG -#endif -#if _STOP_IN_USE(_YMAX_) - #define USE_YMAX_PLUG -#endif -#if _STOP_IN_USE(_ZMAX_) - #define USE_ZMAX_PLUG -#endif -#if _STOP_IN_USE(_XMIN_) - #define USE_XMIN_PLUG -#endif -#if _STOP_IN_USE(_YMIN_) - #define USE_YMIN_PLUG -#endif -#if _STOP_IN_USE(_ZMIN_) - #define USE_ZMIN_PLUG -#endif -#undef _STOP_IN_USE -#if !HAS_CUSTOM_PROBE_PIN - #undef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN -1 -#endif -#if DISABLED(USE_XMAX_PLUG) - #undef X_MAX_PIN - #define X_MAX_PIN -1 -#endif -#if DISABLED(USE_YMAX_PLUG) - #undef Y_MAX_PIN - #define Y_MAX_PIN -1 -#endif -#if DISABLED(USE_ZMAX_PLUG) - #undef Z_MAX_PIN - #define Z_MAX_PIN -1 -#endif -#if DISABLED(USE_XMIN_PLUG) - #undef X_MIN_PIN - #define X_MIN_PIN -1 -#endif -#if DISABLED(USE_YMIN_PLUG) - #undef Y_MIN_PIN - #define Y_MIN_PIN -1 -#endif -#if DISABLED(USE_ZMIN_PLUG) - #undef Z_MIN_PIN - #define Z_MIN_PIN -1 -#endif -#if DISABLED(X_DUAL_ENDSTOPS) || X_HOME_TO_MAX - #undef X2_MIN_PIN -#endif -#if DISABLED(X_DUAL_ENDSTOPS) || X_HOME_TO_MIN - #undef X2_MAX_PIN -#endif -#if DISABLED(Y_DUAL_ENDSTOPS) || Y_HOME_TO_MAX - #undef Y2_MIN_PIN -#endif -#if DISABLED(Y_DUAL_ENDSTOPS) || Y_HOME_TO_MIN - #undef Y2_MAX_PIN -#endif -#if DISABLED(Z_MULTI_ENDSTOPS) || Z_HOME_TO_MAX - #undef Z2_MIN_PIN -#endif -#if DISABLED(Z_MULTI_ENDSTOPS) || Z_HOME_TO_MIN - #undef Z2_MAX_PIN -#endif -#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPER_DRIVERS < 3 || Z_HOME_TO_MAX - #undef Z3_MIN_PIN -#endif -#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPER_DRIVERS < 3 || Z_HOME_TO_MIN - #undef Z3_MAX_PIN -#endif -#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPER_DRIVERS < 4 || Z_HOME_TO_MAX - #undef Z4_MIN_PIN +#if LINEAR_AXES >= 5 + #ifdef J_STOP_PIN + #if J_HOME_TO_MIN + #define J_MIN_PIN J_STOP_PIN + #define J_MAX_PIN -1 + #else + #define J_MIN_PIN -1 + #define J_MAX_PIN J_STOP_PIN + #endif + #endif +#else + #undef J_MIN_PIN + #undef J_MAX_PIN #endif -#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPER_DRIVERS < 4 || Z_HOME_TO_MIN - #undef Z4_MAX_PIN + +#if LINEAR_AXES >= 6 + #ifdef K_STOP_PIN + #if K_HOME_TO_MIN + #define K_MIN_PIN K_STOP_PIN + #define K_MAX_PIN -1 + #else + #define K_MIN_PIN -1 + #define K_MAX_PIN K_STOP_PIN + #endif + #endif +#else + #undef K_MIN_PIN + #undef K_MAX_PIN #endif +// Filament Sensor first pin alias #if HAS_FILAMENT_SENSOR #define FIL_RUNOUT1_PIN FIL_RUNOUT_PIN #else @@ -557,9 +543,17 @@ #define _EPIN(p,q) __EPIN(p,q) #define DIAG_REMAPPED(p,q) (PIN_EXISTS(q) && _EPIN(p##_E_INDEX, DIAG) == q##_PIN) -// The X2 axis, if any, should be the next open extruder port -#define X2_E_INDEX E_STEPPERS +// The E0/E1 steppers are always used for Dual E +#if ENABLED(E_DUAL_STEPPER_DRIVERS) + #ifndef E1_STEP_PIN + #error "No E1 stepper available for E_DUAL_STEPPER_DRIVERS!" + #endif + #define X2_E_INDEX INCREMENT(E_STEPPERS) +#else + #define X2_E_INDEX E_STEPPERS +#endif +// The X2 axis, if any, should be the next open extruder port #if EITHER(DUAL_X_CARRIAGE, X_DUAL_STEPPER_DRIVERS) #ifndef X2_STEP_PIN #define X2_STEP_PIN _EPIN(X2_E_INDEX, STEP) @@ -593,7 +587,7 @@ // // Auto-assign pins for stallGuard sensorless homing // - #if defined(X2_STALL_SENSITIVITY) && ENABLED(X_DUAL_ENDSTOPS) && _PEXI(X2_E_INDEX, DIAG) + #if !defined(X2_USE_ENDSTOP) && defined(X2_STALL_SENSITIVITY) && ENABLED(X_DUAL_ENDSTOPS) && _PEXI(X2_E_INDEX, DIAG) #define X2_DIAG_PIN _EPIN(X2_E_INDEX, DIAG) #if DIAG_REMAPPED(X2, X_MIN) // If already remapped in the pins file... #define X2_USE_ENDSTOP _XMIN_ @@ -662,7 +656,8 @@ #define Y2_SERIAL_RX_PIN _EPIN(Y2_E_INDEX, SERIAL_RX) #endif #endif - #if defined(Y2_STALL_SENSITIVITY) && ENABLED(Y_DUAL_ENDSTOPS) && _PEXI(Y2_E_INDEX, DIAG) + // Auto-assign pins for stallGuard sensorless homing + #if !defined(Y2_USE_ENDSTOP) && defined(Y2_STALL_SENSITIVITY) && ENABLED(Y_DUAL_ENDSTOPS) && _PEXI(Y2_E_INDEX, DIAG) #define Y2_DIAG_PIN _EPIN(Y2_E_INDEX, DIAG) #if DIAG_REMAPPED(Y2, X_MIN) #define Y2_USE_ENDSTOP _XMIN_ @@ -730,7 +725,8 @@ #define Z2_SERIAL_RX_PIN _EPIN(Z2_E_INDEX, SERIAL_RX) #endif #endif - #if defined(Z2_STALL_SENSITIVITY) && ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 2 && _PEXI(Z2_E_INDEX, DIAG) + // Auto-assign pins for stallGuard sensorless homing + #if !defined(Z2_USE_ENDSTOP) && defined(Z2_STALL_SENSITIVITY) && ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 2 && _PEXI(Z2_E_INDEX, DIAG) #define Z2_DIAG_PIN _EPIN(Z2_E_INDEX, DIAG) #if DIAG_REMAPPED(Z2, X_MIN) #define Z2_USE_ENDSTOP _XMIN_ @@ -799,7 +795,8 @@ #define Z3_SERIAL_RX_PIN _EPIN(Z3_E_INDEX, SERIAL_RX) #endif #endif - #if defined(Z3_STALL_SENSITIVITY) && ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 3 && _PEXI(Z3_E_INDEX, DIAG) + // Auto-assign pins for stallGuard sensorless homing + #if !defined(Z3_USE_ENDSTOP) && defined(Z3_STALL_SENSITIVITY) && ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 3 && _PEXI(Z3_E_INDEX, DIAG) #define Z3_DIAG_PIN _EPIN(Z3_E_INDEX, DIAG) #if DIAG_REMAPPED(Z3, X_MIN) #define Z3_USE_ENDSTOP _XMIN_ @@ -820,6 +817,8 @@ #undef Z3_DIAG_PIN #endif #define Z4_E_INDEX INCREMENT(Z3_E_INDEX) +#else + #define Z4_E_INDEX Z3_E_INDEX #endif #ifndef Z3_CS_PIN @@ -866,7 +865,8 @@ #define Z4_SERIAL_RX_PIN _EPIN(Z4_E_INDEX, SERIAL_RX) #endif #endif - #if defined(Z4_STALL_SENSITIVITY) && ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4 && _PEXI(Z4_E_INDEX, DIAG) + // Auto-assign pins for stallGuard sensorless homing + #if !defined(Z4_USE_ENDSTOP) && defined(Z4_STALL_SENSITIVITY) && ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4 && _PEXI(Z4_E_INDEX, DIAG) #define Z4_DIAG_PIN _EPIN(Z4_E_INDEX, DIAG) #if DIAG_REMAPPED(Z4, X_MIN) #define Z4_USE_ENDSTOP _XMIN_ @@ -886,6 +886,9 @@ #endif #undef Z4_DIAG_PIN #endif + #define I_E_INDEX INCREMENT(Z4_E_INDEX) +#else + #define I_E_INDEX Z4_E_INDEX #endif #ifndef Z4_CS_PIN @@ -901,6 +904,323 @@ #define Z4_MS3_PIN -1 #endif +#if LINEAR_AXES >= 4 + #ifndef I_STEP_PIN + #define I_STEP_PIN _EPIN(I_E_INDEX, STEP) + #define I_DIR_PIN _EPIN(I_E_INDEX, DIR) + #define I_ENABLE_PIN _EPIN(I_E_INDEX, ENABLE) + #if I_E_INDEX >= MAX_E_STEPPERS || !PIN_EXISTS(I_STEP) + #error "No E stepper plug left for I!" + #endif + #endif + #if AXIS_HAS_SPI(I) + #ifndef I_CS_PIN + #define I_CS_PIN _EPIN(I_E_INDEX, CS) + #endif + #endif + #ifndef I_MS1_PIN + #define I_MS1_PIN _EPIN(I_E_INDEX, MS1) + #endif + #ifndef I_MS2_PIN + #define I_MS2_PIN _EPIN(I_E_INDEX, MS2) + #endif + #ifndef I_MS3_PIN + #define I_MS3_PIN _EPIN(I_E_INDEX, MS3) + #endif + #if AXIS_HAS_UART(I) + #ifndef I_SERIAL_TX_PIN + #define I_SERIAL_TX_PIN _EPIN(I_E_INDEX, SERIAL_TX) + #endif + #ifndef I_SERIAL_RX_PIN + #define I_SERIAL_RX_PIN _EPIN(I_E_INDEX, SERIAL_RX) + #endif + #endif + // Auto-assign pins for stallGuard sensorless homing + #if !defined(I_USE_ENDSTOP) && defined(I_STALL_SENSITIVITY) && _PEXI(I_E_INDEX, DIAG) + #define I_DIAG_PIN _EPIN(I_E_INDEX, DIAG) + #if DIAG_REMAPPED(I, X_MIN) + #define I_USE_ENDSTOP _XMIN_ + #elif DIAG_REMAPPED(I, Y_MIN) + #define I_USE_ENDSTOP _YMIN_ + #elif DIAG_REMAPPED(I, Z_MIN) + #define I_USE_ENDSTOP _ZMIN_ + #elif DIAG_REMAPPED(I, X_MAX) + #define I_USE_ENDSTOP _XMAX_ + #elif DIAG_REMAPPED(I, Y_MAX) + #define I_USE_ENDSTOP _YMAX_ + #elif DIAG_REMAPPED(I, Z_MAX) + #define I_USE_ENDSTOP _ZMAX_ + #else + #define _I_USE_ENDSTOP(P) _E##P##_DIAG_ + #define I_USE_ENDSTOP _I_USE_ENDSTOP(I_E_INDEX) + #endif + #undef I_DIAG_PIN + #endif + #define J_E_INDEX INCREMENT(I_E_INDEX) +#else + #define J_E_INDEX I_E_INDEX +#endif + +#ifndef I_CS_PIN + #define I_CS_PIN -1 +#endif +#ifndef I_MS1_PIN + #define I_MS1_PIN -1 +#endif +#ifndef I_MS2_PIN + #define I_MS2_PIN -1 +#endif +#ifndef I_MS3_PIN + #define I_MS3_PIN -1 +#endif + +#if LINEAR_AXES >= 5 + #ifndef J_STEP_PIN + #define J_STEP_PIN _EPIN(J_E_INDEX, STEP) + #define J_DIR_PIN _EPIN(J_E_INDEX, DIR) + #define J_ENABLE_PIN _EPIN(J_E_INDEX, ENABLE) + #if I_E_INDEX >= MAX_E_STEPPERS || !PIN_EXISTS(J_STEP) + #error "No E stepper plug left for J!" + #endif + #endif + #if AXIS_HAS_SPI(J) + #ifndef J_CS_PIN + #define J_CS_PIN _EPIN(J_E_INDEX, CS) + #endif + #endif + #ifndef J_MS1_PIN + #define J_MS1_PIN _EPIN(J_E_INDEX, MS1) + #endif + #ifndef J_MS2_PIN + #define J_MS2_PIN _EPIN(J_E_INDEX, MS2) + #endif + #ifndef J_MS3_PIN + #define J_MS3_PIN _EPIN(J_E_INDEX, MS3) + #endif + #if AXIS_HAS_UART(J) + #ifndef J_SERIAL_TX_PIN + #define J_SERIAL_TX_PIN _EPIN(J_E_INDEX, SERIAL_TX) + #endif + #ifndef J_SERIAL_RX_PIN + #define J_SERIAL_RX_PIN _EPIN(J_E_INDEX, SERIAL_RX) + #endif + #endif + // Auto-assign pins for stallGuard sensorless homing + #if !defined(J_USE_ENDSTOP) && defined(J_STALL_SENSITIVITY) && _PEXI(J_E_INDEX, DIAG) + #define J_DIAG_PIN _EPIN(J_E_INDEX, DIAG) + #if DIAG_REMAPPED(J, X_MIN) + #define J_USE_ENDSTOP _XMIN_ + #elif DIAG_REMAPPED(J, Y_MIN) + #define J_USE_ENDSTOP _YMIN_ + #elif DIAG_REMAPPED(J, Z_MIN) + #define J_USE_ENDSTOP _ZMIN_ + #elif DIAG_REMAPPED(J, X_MAX) + #define J_USE_ENDSTOP _XMAX_ + #elif DIAG_REMAPPED(J, Y_MAX) + #define J_USE_ENDSTOP _YMAX_ + #elif DIAG_REMAPPED(I, Z_MAX) + #define J_USE_ENDSTOP _ZMAX_ + #else + #define _J_USE_ENDSTOP(P) _E##P##_DIAG_ + #define J_USE_ENDSTOP _J_USE_ENDSTOP(J_E_INDEX) + #endif + #undef J_DIAG_PIN + #endif + #define K_E_INDEX INCREMENT(J_E_INDEX) +#else + #define K_E_INDEX J_E_INDEX +#endif + +#ifndef J_CS_PIN + #define J_CS_PIN -1 +#endif +#ifndef J_MS1_PIN + #define J_MS1_PIN -1 +#endif +#ifndef J_MS2_PIN + #define J_MS2_PIN -1 +#endif +#ifndef J_MS3_PIN + #define J_MS3_PIN -1 +#endif + +#if LINEAR_AXES >= 6 + #ifndef K_STEP_PIN + #define K_STEP_PIN _EPIN(K_E_INDEX, STEP) + #define K_DIR_PIN _EPIN(K_E_INDEX, DIR) + #define K_ENABLE_PIN _EPIN(K_E_INDEX, ENABLE) + #if K_E_INDEX >= MAX_E_STEPPERS || !PIN_EXISTS(K_STEP) + #error "No E stepper plug left for K!" + #endif + #endif + #if AXIS_HAS_SPI(K) + #ifndef K_CS_PIN + #define K_CS_PIN _EPIN(K_E_INDEX, CS) + #endif + #endif + #ifndef K_MS1_PIN + #define K_MS1_PIN _EPIN(K_E_INDEX, MS1) + #endif + #ifndef K_MS2_PIN + #define K_MS2_PIN _EPIN(K_E_INDEX, MS2) + #endif + #ifndef K_MS3_PIN + #define K_MS3_PIN _EPIN(K_E_INDEX, MS3) + #endif + #if AXIS_HAS_UART(K) + #ifndef K_SERIAL_TX_PIN + #define K_SERIAL_TX_PIN _EPIN(K_E_INDEX, SERIAL_TX) + #endif + #ifndef K_SERIAL_RX_PIN + #define K_SERIAL_RX_PIN _EPIN(K_E_INDEX, SERIAL_RX) + #endif + #endif + // Auto-assign pins for stallGuard sensorless homing + #if !defined(K_USE_ENDSTOP) && defined(K_STALL_SENSITIVITY) && _PEXI(K_E_INDEX, DIAG) + #define K_DIAG_PIN _EPIN(K_E_INDEX, DIAG) + #if DIAG_REMAPPED(K, X_MIN) + #define K_USE_ENDSTOP _XMIN_ + #elif DIAG_REMAPPED(K, Y_MIN) + #define K_USE_ENDSTOP _YMIN_ + #elif DIAG_REMAPPED(K, Z_MIN) + #define K_USE_ENDSTOP _ZMIN_ + #elif DIAG_REMAPPED(K, X_MAX) + #define K_USE_ENDSTOP _XMAX_ + #elif DIAG_REMAPPED(K, Y_MAX) + #define K_USE_ENDSTOP _YMAX_ + #elif DIAG_REMAPPED(K, Z_MAX) + #define K_USE_ENDSTOP _ZMAX_ + #else + #define _K_USE_ENDSTOP(P) _E##P##_DIAG_ + #define K_USE_ENDSTOP _K_USE_ENDSTOP(K_E_INDEX) + #endif + #undef K_DIAG_PIN + #endif +#endif + +#ifndef K_CS_PIN + #define K_CS_PIN -1 +#endif +#ifndef K_MS1_PIN + #define K_MS1_PIN -1 +#endif +#ifndef K_MS2_PIN + #define K_MS2_PIN -1 +#endif +#ifndef K_MS3_PIN + #define K_MS3_PIN -1 +#endif + +// +// Disable unused endstop / probe pins +// +#define _STOP_IN_USE(N) (X2_USE_ENDSTOP == N || Y2_USE_ENDSTOP == N || Z2_USE_ENDSTOP == N || Z3_USE_ENDSTOP == N || Z4_USE_ENDSTOP == N) +#if _STOP_IN_USE(_XMAX_) + #define USE_XMAX_PLUG +#endif +#if _STOP_IN_USE(_YMAX_) + #define USE_YMAX_PLUG +#endif +#if _STOP_IN_USE(_ZMAX_) + #define USE_ZMAX_PLUG +#endif +#if _STOP_IN_USE(_XMIN_) + #define USE_XMIN_PLUG +#endif +#if _STOP_IN_USE(_YMIN_) + #define USE_YMIN_PLUG +#endif +#if _STOP_IN_USE(_ZMIN_) + #define USE_ZMIN_PLUG +#endif +#undef _STOP_IN_USE +#if !HAS_CUSTOM_PROBE_PIN + #undef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN -1 +#endif +#if DISABLED(USE_XMIN_PLUG) + #undef X_MIN_PIN + #define X_MIN_PIN -1 +#endif +#if DISABLED(USE_XMAX_PLUG) + #undef X_MAX_PIN + #define X_MAX_PIN -1 +#endif +#if DISABLED(USE_YMIN_PLUG) + #undef Y_MIN_PIN + #define Y_MIN_PIN -1 +#endif +#if DISABLED(USE_YMAX_PLUG) + #undef Y_MAX_PIN + #define Y_MAX_PIN -1 +#endif +#if DISABLED(USE_ZMIN_PLUG) + #undef Z_MIN_PIN + #define Z_MIN_PIN -1 +#endif +#if DISABLED(USE_ZMAX_PLUG) + #undef Z_MAX_PIN + #define Z_MAX_PIN -1 +#endif +#if DISABLED(USE_IMIN_PLUG) + #undef I_MIN_PIN + #define I_MIN_PIN -1 +#endif +#if DISABLED(USE_IMAX_PLUG) + #undef I_MAX_PIN + #define I_MAX_PIN -1 +#endif +#if DISABLED(USE_JMIN_PLUG) + #undef J_MIN_PIN + #define J_MIN_PIN -1 +#endif +#if DISABLED(USE_JMAX_PLUG) + #undef J_MAX_PIN + #define J_MAX_PIN -1 +#endif +#if DISABLED(USE_KMIN_PLUG) + #undef K_MIN_PIN + #define K_MIN_PIN -1 +#endif +#if DISABLED(USE_KMAX_PLUG) + #undef K_MAX_PIN + #define K_MAX_PIN -1 +#endif + +#if DISABLED(X_DUAL_ENDSTOPS) || X_HOME_TO_MAX + #undef X2_MIN_PIN +#endif +#if DISABLED(X_DUAL_ENDSTOPS) || X_HOME_TO_MIN + #undef X2_MAX_PIN +#endif +#if DISABLED(Y_DUAL_ENDSTOPS) || Y_HOME_TO_MAX + #undef Y2_MIN_PIN +#endif +#if DISABLED(Y_DUAL_ENDSTOPS) || Y_HOME_TO_MIN + #undef Y2_MAX_PIN +#endif +#if DISABLED(Z_MULTI_ENDSTOPS) || Z_HOME_TO_MAX + #undef Z2_MIN_PIN +#endif +#if DISABLED(Z_MULTI_ENDSTOPS) || Z_HOME_TO_MIN + #undef Z2_MAX_PIN +#endif +#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPER_DRIVERS < 3 || Z_HOME_TO_MAX + #undef Z3_MIN_PIN +#endif +#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPER_DRIVERS < 3 || Z_HOME_TO_MIN + #undef Z3_MAX_PIN +#endif +#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPER_DRIVERS < 4 || Z_HOME_TO_MAX + #undef Z4_MIN_PIN +#endif +#if DISABLED(Z_MULTI_ENDSTOPS) || NUM_Z_STEPPER_DRIVERS < 4 || Z_HOME_TO_MIN + #undef Z4_MAX_PIN +#endif + +// +// Default DOGLCD SPI delays +// #if HAS_MARLINUI_U8GLIB #if !defined(ST7920_DELAY_1) && defined(BOARD_ST7920_DELAY_1) #define ST7920_DELAY_1 BOARD_ST7920_DELAY_1 diff --git a/Marlin/src/pins/ramps/pins_3DRAG.h b/Marlin/src/pins/ramps/pins_3DRAG.h index 08354ce2ff4ee..e78f7683f607d 100644 --- a/Marlin/src/pins/ramps/pins_3DRAG.h +++ b/Marlin/src/pins/ramps/pins_3DRAG.h @@ -44,6 +44,11 @@ #define RAMPS_D9_PIN 8 #define MOSFET_D_PIN 12 +// +// Misc. Functions +// +#define SDSS 25 + #ifndef CASE_LIGHT_PIN #define CASE_LIGHT_PIN -1 // Hardware PWM but one is not available on expansion header #endif @@ -66,12 +71,6 @@ // #define HEATER_2_PIN 6 -// -// Misc. Functions -// -#undef SDSS -#define SDSS 25 - #undef SD_DETECT_PIN #define SD_DETECT_PIN 53 diff --git a/Marlin/src/pins/ramps/pins_COPYMASTER_3D.h b/Marlin/src/pins/ramps/pins_COPYMASTER_3D.h index b9eee6bd53290..020941027aafa 100644 --- a/Marlin/src/pins/ramps/pins_COPYMASTER_3D.h +++ b/Marlin/src/pins/ramps/pins_COPYMASTER_3D.h @@ -23,10 +23,10 @@ #define BOARD_INFO_NAME "Copymaster 3D RAMPS" -#define Z_STEP_PIN 47 -#define Y_MAX_PIN 14 -#define FIL_RUNOUT_PIN 15 -#define SD_DETECT_PIN 66 +#define Z_STEP_PIN 47 +#define Y_MAX_PIN 14 +#define FIL_RUNOUT_PIN 15 +#define SD_DETECT_PIN 66 // // Import RAMPS 1.4 pins diff --git a/Marlin/src/pins/ramps/pins_K8600.h b/Marlin/src/pins/ramps/pins_K8600.h index 1a396b20f4039..47b52e75e80d2 100644 --- a/Marlin/src/pins/ramps/pins_K8600.h +++ b/Marlin/src/pins/ramps/pins_K8600.h @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ +#pragma once /** * VERTEX NANO Arduino Mega with RAMPS EFB v1.4 pin assignments. @@ -47,6 +48,7 @@ // // Misc. Functions // +#define SDSS 25 #define CASE_LIGHT_PIN 7 // @@ -87,12 +89,6 @@ // #undef HEATER_BED_PIN -// -// Misc. Functions -// -#undef SDSS -#define SDSS 25 // 53 - // // LCD / Controller // diff --git a/Marlin/src/pins/ramps/pins_RAMPS.h b/Marlin/src/pins/ramps/pins_RAMPS.h index f30a23562627e..c2d4dbeb3f812 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS.h +++ b/Marlin/src/pins/ramps/pins_RAMPS.h @@ -241,7 +241,9 @@ // // Misc. Functions // -#define SDSS EXP2_07_PIN +#ifndef SDSS + #define SDSS EXP2_07_PIN +#endif #define LED_PIN 13 #ifndef FILWIDTH_PIN diff --git a/Marlin/src/pins/ramps/pins_TT_OSCAR.h b/Marlin/src/pins/ramps/pins_TT_OSCAR.h index 18d0f1770e113..aba8f80e61078 100644 --- a/Marlin/src/pins/ramps/pins_TT_OSCAR.h +++ b/Marlin/src/pins/ramps/pins_TT_OSCAR.h @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ +#pragma once #include "env_validate.h" diff --git a/Marlin/src/pins/sam/pins_ADSK.h b/Marlin/src/pins/sam/pins_ADSK.h index 9026ca7771daf..6fe0520f810b1 100644 --- a/Marlin/src/pins/sam/pins_ADSK.h +++ b/Marlin/src/pins/sam/pins_ADSK.h @@ -86,9 +86,9 @@ A stepper for E0 extruder // // Limit Switches // -#define X_MIN_PIN 9 -#define Y_MIN_PIN 10 -#define Z_MIN_PIN 11 +#define X_STOP_PIN 9 +#define Y_STOP_PIN 10 +#define Z_STOP_PIN 11 #define Z_MIN_PROBE_PIN 62 // Analog pin 8, Digital pin 62 diff --git a/Marlin/src/pins/sam/pins_CNCONTROLS_15D.h b/Marlin/src/pins/sam/pins_CNCONTROLS_15D.h index a63c33788044b..d44f6490da63d 100644 --- a/Marlin/src/pins/sam/pins_CNCONTROLS_15D.h +++ b/Marlin/src/pins/sam/pins_CNCONTROLS_15D.h @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ +#pragma once /** * CNControls V15 for HMS434 with DUE pin assignments diff --git a/Marlin/src/pins/sam/pins_DUE3DOM.h b/Marlin/src/pins/sam/pins_DUE3DOM.h index 4ebece58e4c28..de3cb33e8de3e 100644 --- a/Marlin/src/pins/sam/pins_DUE3DOM.h +++ b/Marlin/src/pins/sam/pins_DUE3DOM.h @@ -128,7 +128,6 @@ #define BTN_EN2 52 #define BTN_ENC 48 - #define SDSS 4 #define SD_DETECT_PIN 14 #elif ENABLED(RADDS_DISPLAY) @@ -141,8 +140,6 @@ #define BTN_BACK 71 - #undef SDSS - #define SDSS 4 #define SD_DETECT_PIN 14 #elif HAS_U8GLIB_I2C_OLED diff --git a/Marlin/src/pins/sam/pins_DUE3DOM_MINI.h b/Marlin/src/pins/sam/pins_DUE3DOM_MINI.h index dd8f2636760c5..c52199a54dc5f 100644 --- a/Marlin/src/pins/sam/pins_DUE3DOM_MINI.h +++ b/Marlin/src/pins/sam/pins_DUE3DOM_MINI.h @@ -40,12 +40,9 @@ // // Limit Switches // -#define X_MIN_PIN 38 -#define X_MAX_PIN -1 -#define Y_MIN_PIN 34 -#define Y_MAX_PIN -1 -#define Z_MIN_PIN 30 -#define Z_MAX_PIN -1 +#define X_STOP_PIN 38 +#define Y_STOP_PIN 34 +#define Z_STOP_PIN 30 // // Steppers @@ -120,7 +117,10 @@ #define BTN_EN2 52 #define BTN_ENC 48 - #define SDSS 4 + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif + #define SD_DETECT_PIN 14 #elif ENABLED(RADDS_DISPLAY) @@ -133,8 +133,6 @@ #define BTN_BACK 71 - #undef SDSS - #define SDSS 4 #define SD_DETECT_PIN 14 #elif HAS_U8GLIB_I2C_OLED @@ -143,7 +141,7 @@ #define BTN_EN2 52 #define BTN_ENC 48 #define BEEPER_PIN 41 - #define LCD_SDSS 4 + #define LCD_SDSS SDSS #define SD_DETECT_PIN 14 #elif ENABLED(SPARK_FULL_GRAPHICS) @@ -158,20 +156,17 @@ #define BEEPER_PIN -1 - #elif ENABLED(MINIPANEL) + #elif ENABLED(MINIPANEL) + #define BTN_EN1 52 #define BTN_EN2 50 #define BTN_ENC 48 - #define LCD_SDSS 4 + #define LCD_SDSS SDSS #define SD_DETECT_PIN 14 #define BEEPER_PIN 41 #define DOGLCD_A0 46 #define DOGLCD_CS 45 - #endif // SPARK_FULL_GRAPHICS - - #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) - #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder #endif #endif // HAS_WIRED_LCD diff --git a/Marlin/src/pins/sam/pins_PRINTRBOARD_G2.h b/Marlin/src/pins/sam/pins_PRINTRBOARD_G2.h index 874950f34b80d..aa01a9227fb3f 100644 --- a/Marlin/src/pins/sam/pins_PRINTRBOARD_G2.h +++ b/Marlin/src/pins/sam/pins_PRINTRBOARD_G2.h @@ -40,9 +40,9 @@ // // Limit Switches // -#define X_MIN_PIN 22 // PB26 -#define Y_MAX_PIN 18 // PA11 -#define Z_MIN_PIN 19 // PA10 +#define X_STOP_PIN 22 // PB26 +#define Y_STOP_PIN 18 // PA11 +#define Z_STOP_PIN 19 // PA10 // // Z Probe (when not Z_MIN_PIN) diff --git a/Marlin/src/pins/sam/pins_RURAMPS4D_11.h b/Marlin/src/pins/sam/pins_RURAMPS4D_11.h index 908bbc6b229e8..a52af48e11227 100644 --- a/Marlin/src/pins/sam/pins_RURAMPS4D_11.h +++ b/Marlin/src/pins/sam/pins_RURAMPS4D_11.h @@ -20,6 +20,7 @@ * * Ported sys0724 & Vynt */ +#pragma once /** * Arduino Mega? or Due with RuRAMPS4DUE pin assignments diff --git a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h index 3e73c33acbc45..37ebb567a6997 100644 --- a/Marlin/src/pins/sam/pins_RURAMPS4D_13.h +++ b/Marlin/src/pins/sam/pins_RURAMPS4D_13.h @@ -20,6 +20,7 @@ * * Ported sys0724 & Vynt */ +#pragma once /** * Arduino Mega? or Due with RuRAMPS4DUE pin assignments diff --git a/Marlin/src/pins/samd/pins_RAMPS_144.h b/Marlin/src/pins/samd/pins_RAMPS_144.h index 8311ac9012a0d..fbd9d7c864120 100644 --- a/Marlin/src/pins/samd/pins_RAMPS_144.h +++ b/Marlin/src/pins/samd/pins_RAMPS_144.h @@ -130,7 +130,6 @@ // // Misc. Functions // -#define SDSS 53 #define LED_PIN 13 #ifndef FILWIDTH_PIN @@ -252,6 +251,21 @@ #endif #endif +// +// SD Support +// +#ifndef SDCARD_CONNECTION + #define SDCARD_CONNECTION ONBOARD +#endif + +#if SD_CONNECTION_IS(ONBOARD) + #define SDSS 83 + #undef SD_DETECT_PIN + #define SD_DETECT_PIN 95 +#else + #define SDSS 53 +#endif + ////////////////////////// // LCDs and Controllers // ////////////////////////// @@ -356,6 +370,9 @@ #else #define BTN_EN1 31 #define BTN_EN2 33 + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif #endif #define BTN_ENC 35 @@ -365,8 +382,7 @@ #define KILL_PIN 41 #if ENABLED(BQ_LCD_SMART_CONTROLLER) - // TO TEST - //#define LCD_BACKLIGHT_PIN 39 + //#define LCD_BACKLIGHT_PIN 39 // TO TEST #endif #elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD) @@ -563,22 +579,4 @@ #endif #endif // IS_NEWPANEL - #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) - #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder - #endif - #endif // HAS_WIRED_LCD - -// -// SD Support -// -#ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION ONBOARD -#endif - -#if SD_CONNECTION_IS(ONBOARD) - #undef SDSS - #define SDSS 83 - #undef SD_DETECT_PIN - #define SD_DETECT_PIN 95 -#endif diff --git a/Marlin/src/pins/sensitive_pins.h b/Marlin/src/pins/sensitive_pins.h index 21ba87e8f6fb2..7ccb0339b27ea 100644 --- a/Marlin/src/pins/sensitive_pins.h +++ b/Marlin/src/pins/sensitive_pins.h @@ -63,81 +63,235 @@ #define _X_PINS X_STEP_PIN, X_DIR_PIN, _X_ENABLE_PIN _X_MIN _X_MAX _X_MS1 _X_MS2 _X_MS3 _X_CS -#if PIN_EXISTS(Y_MIN) - #define _Y_MIN Y_MIN_PIN, -#else - #define _Y_MIN -#endif -#if PIN_EXISTS(Y_MAX) - #define _Y_MAX Y_MAX_PIN, -#else - #define _Y_MAX -#endif -#if PIN_EXISTS(Y_CS) && AXIS_HAS_SPI(Y) - #define _Y_CS Y_CS_PIN, -#else - #define _Y_CS -#endif -#if PIN_EXISTS(Y_MS1) - #define _Y_MS1 Y_MS1_PIN, -#else - #define _Y_MS1 -#endif -#if PIN_EXISTS(Y_MS2) - #define _Y_MS2 Y_MS2_PIN, -#else - #define _Y_MS2 -#endif -#if PIN_EXISTS(Y_MS3) - #define _Y_MS3 Y_MS3_PIN, -#else - #define _Y_MS3 -#endif -#if PIN_EXISTS(Y_ENABLE) - #define _Y_ENABLE_PIN Y_ENABLE_PIN, -#else - #define _Y_ENABLE_PIN -#endif +#if HAS_Y_AXIS -#define _Y_PINS Y_STEP_PIN, Y_DIR_PIN, _Y_ENABLE_PIN _Y_MIN _Y_MAX _Y_MS1 _Y_MS2 _Y_MS3 _Y_CS + #if PIN_EXISTS(Y_MIN) + #define _Y_MIN Y_MIN_PIN, + #else + #define _Y_MIN + #endif + #if PIN_EXISTS(Y_MAX) + #define _Y_MAX Y_MAX_PIN, + #else + #define _Y_MAX + #endif + #if PIN_EXISTS(Y_CS) && AXIS_HAS_SPI(Y) + #define _Y_CS Y_CS_PIN, + #else + #define _Y_CS + #endif + #if PIN_EXISTS(Y_MS1) + #define _Y_MS1 Y_MS1_PIN, + #else + #define _Y_MS1 + #endif + #if PIN_EXISTS(Y_MS2) + #define _Y_MS2 Y_MS2_PIN, + #else + #define _Y_MS2 + #endif + #if PIN_EXISTS(Y_MS3) + #define _Y_MS3 Y_MS3_PIN, + #else + #define _Y_MS3 + #endif + #if PIN_EXISTS(Y_ENABLE) + #define _Y_ENABLE_PIN Y_ENABLE_PIN, + #else + #define _Y_ENABLE_PIN + #endif + + #define _Y_PINS Y_STEP_PIN, Y_DIR_PIN, _Y_ENABLE_PIN _Y_MIN _Y_MAX _Y_MS1 _Y_MS2 _Y_MS3 _Y_CS -#if PIN_EXISTS(Z_MIN) - #define _Z_MIN Z_MIN_PIN, -#else - #define _Z_MIN -#endif -#if PIN_EXISTS(Z_MAX) - #define _Z_MAX Z_MAX_PIN, -#else - #define _Z_MAX -#endif -#if PIN_EXISTS(Z_CS) && AXIS_HAS_SPI(Z) - #define _Z_CS Z_CS_PIN, #else - #define _Z_CS + + #define _Y_PINS + #endif -#if PIN_EXISTS(Z_MS1) - #define _Z_MS1 Z_MS1_PIN, + +#if HAS_Z_AXIS + + #if PIN_EXISTS(Z_MIN) + #define _Z_MIN Z_MIN_PIN, + #else + #define _Z_MIN + #endif + #if PIN_EXISTS(Z_MAX) + #define _Z_MAX Z_MAX_PIN, + #else + #define _Z_MAX + #endif + #if PIN_EXISTS(Z_CS) && AXIS_HAS_SPI(Z) + #define _Z_CS Z_CS_PIN, + #else + #define _Z_CS + #endif + #if PIN_EXISTS(Z_MS1) + #define _Z_MS1 Z_MS1_PIN, + #else + #define _Z_MS1 + #endif + #if PIN_EXISTS(Z_MS2) + #define _Z_MS2 Z_MS2_PIN, + #else + #define _Z_MS2 + #endif + #if PIN_EXISTS(Z_MS3) + #define _Z_MS3 Z_MS3_PIN, + #else + #define _Z_MS3 + #endif + #if PIN_EXISTS(Z_ENABLE) + #define _Z_ENABLE_PIN Z_ENABLE_PIN, + #else + #define _Z_ENABLE_PIN + #endif + + #define _Z_PINS Z_STEP_PIN, Z_DIR_PIN, _Z_ENABLE_PIN _Z_MIN _Z_MAX _Z_MS1 _Z_MS2 _Z_MS3 _Z_CS + #else - #define _Z_MS1 + + #define _Z_PINS + #endif -#if PIN_EXISTS(Z_MS2) - #define _Z_MS2 Z_MS2_PIN, + +#if LINEAR_AXES >= 4 + + #if PIN_EXISTS(I_MIN) + #define _I_MIN I_MIN_PIN, + #else + #define _I_MIN + #endif + #if PIN_EXISTS(I_MAX) + #define _I_MAX I_MAX_PIN, + #else + #define _I_MAX + #endif + #if PIN_EXISTS(I_CS) && AXIS_HAS_SPI(I) + #define _I_CS I_CS_PIN, + #else + #define _I_CS + #endif + #if PIN_EXISTS(I_MS1) + #define _I_MS1 I_MS1_PIN, + #else + #define _I_MS1 + #endif + #if PIN_EXISTS(I_MS2) + #define _I_MS2 I_MS2_PIN, + #else + #define _I_MS2 + #endif + #if PIN_EXISTS(I_MS3) + #define _I_MS3 I_MS3_PIN, + #else + #define _I_MS3 + #endif + #if PIN_EXISTS(I_ENABLE) + #define _I_ENABLE_PIN I_ENABLE_PIN, + #else + #define _I_ENABLE_PIN + #endif + + #define _I_PINS I_STEP_PIN, I_DIR_PIN, _I_ENABLE_PIN _I_MIN _I_MAX _I_MS1 _I_MS2 _I_MS3 _I_CS + #else - #define _Z_MS2 + + #define _I_PINS + #endif -#if PIN_EXISTS(Z_MS3) - #define _Z_MS3 Z_MS3_PIN, + +#if LINEAR_AXES >= 5 + + #if PIN_EXISTS(J_MIN) + #define _J_MIN J_MIN_PIN, + #else + #define _J_MIN + #endif + #if PIN_EXISTS(J_MAX) + #define _J_MAX J_MAX_PIN, + #else + #define _J_MAX + #endif + #if PIN_EXISTS(J_CS) && AXIS_HAS_SPI(J) + #define _J_CS J_CS_PIN, + #else + #define _J_CS + #endif + #if PIN_EXISTS(J_MS1) + #define _J_MS1 J_MS1_PIN, + #else + #define _J_MS1 + #endif + #if PIN_EXISTS(J_MS2) + #define _J_MS2 J_MS2_PIN, + #else + #define _J_MS2 + #endif + #if PIN_EXISTS(J_MS3) + #define _J_MS3 J_MS3_PIN, + #else + #define _J_MS3 + #endif + #if PIN_EXISTS(J_ENABLE) + #define _J_ENABLE_PIN J_ENABLE_PIN, + #else + #define _J_ENABLE_PIN + #endif + + #define _J_PINS J_STEP_PIN, J_DIR_PIN, _J_ENABLE_PIN _J_MIN _J_MAX _J_MS1 _J_MS2 _J_MS3 _J_CS + #else - #define _Z_MS3 + + #define _J_PINS + #endif -#if PIN_EXISTS(Z_ENABLE) - #define _Z_ENABLE_PIN Z_ENABLE_PIN, + +#if LINEAR_AXES >= 6 + + #if PIN_EXISTS(K_MIN) + #define _K_MIN K_MIN_PIN, + #else + #define _K_MIN + #endif + #if PIN_EXISTS(K_MAX) + #define _K_MAX K_MAX_PIN, + #else + #define _K_MAX + #endif + #if PIN_EXISTS(K_CS) && AXIS_HAS_SPI(K) + #define _K_CS K_CS_PIN, + #else + #define _K_CS + #endif + #if PIN_EXISTS(K_MS1) + #define _K_MS1 K_MS1_PIN, + #else + #define _K_MS1 + #endif + #if PIN_EXISTS(K_MS2) + #define _K_MS2 K_MS2_PIN, + #else + #define _K_MS2 + #endif + #if PIN_EXISTS(K_MS3) + #define _K_MS3 K_MS3_PIN, + #else + #define _K_MS3 + #endif + #if PIN_EXISTS(K_ENABLE) + #define _K_ENABLE_PIN K_ENABLE_PIN, + #else + #define _K_ENABLE_PIN + #endif + + #define _K_PINS K_STEP_PIN, K_DIR_PIN, _K_ENABLE_PIN _K_MIN _K_MAX _K_MS1 _K_MS2 _K_MS3 _K_CS + #else - #define _Z_ENABLE_PIN -#endif -#define _Z_PINS Z_STEP_PIN, Z_DIR_PIN, _Z_ENABLE_PIN _Z_MIN _Z_MAX _Z_MS1 _Z_MS2 _Z_MS3 _Z_CS + #define _K_PINS + +#endif // // Extruder Chip Select, Digital Micro-steps @@ -438,30 +592,32 @@ #define _H6_PINS #define _H7_PINS +#define DIO_PIN(P) TERN(TARGET_LPC1768, P, analogInputToDigitalPin(P)) + #if HAS_HOTEND #undef _H0_PINS - #define _H0_PINS HEATER_0_PIN, E0_AUTO_FAN_PIN, analogInputToDigitalPin(TEMP_0_PIN), + #define _H0_PINS HEATER_0_PIN, E0_AUTO_FAN_PIN, DIO_PIN(TEMP_0_PIN), #if HAS_MULTI_HOTEND #undef _H1_PINS - #define _H1_PINS HEATER_1_PIN, E1_AUTO_FAN_PIN, analogInputToDigitalPin(TEMP_1_PIN), + #define _H1_PINS HEATER_1_PIN, E1_AUTO_FAN_PIN, DIO_PIN(TEMP_1_PIN), #if HOTENDS > 2 #undef _H2_PINS - #define _H2_PINS HEATER_2_PIN, E2_AUTO_FAN_PIN, analogInputToDigitalPin(TEMP_2_PIN), + #define _H2_PINS HEATER_2_PIN, E2_AUTO_FAN_PIN, DIO_PIN(TEMP_2_PIN), #if HOTENDS > 3 #undef _H3_PINS - #define _H3_PINS HEATER_3_PIN, E3_AUTO_FAN_PIN, analogInputToDigitalPin(TEMP_3_PIN), + #define _H3_PINS HEATER_3_PIN, E3_AUTO_FAN_PIN, DIO_PIN(TEMP_3_PIN), #if HOTENDS > 4 #undef _H4_PINS - #define _H4_PINS HEATER_4_PIN, E4_AUTO_FAN_PIN, analogInputToDigitalPin(TEMP_4_PIN), + #define _H4_PINS HEATER_4_PIN, E4_AUTO_FAN_PIN, DIO_PIN(TEMP_4_PIN), #if HOTENDS > 5 #undef _H5_PINS - #define _H5_PINS HEATER_5_PIN, E5_AUTO_FAN_PIN, analogInputToDigitalPin(TEMP_5_PIN), + #define _H5_PINS HEATER_5_PIN, E5_AUTO_FAN_PIN, DIO_PIN(TEMP_5_PIN), #if HOTENDS > 6 #undef _H6_PINS - #define _H6_PINS HEATER_6_PIN, E6_AUTO_FAN_PIN, analogInputToDigitalPin(TEMP_6_PIN), + #define _H6_PINS HEATER_6_PIN, E6_AUTO_FAN_PIN, DIO_PIN(TEMP_6_PIN), #if HOTENDS > 7 #undef _H7_PINS - #define _H7_PINS HEATER_7_PIN, E7_AUTO_FAN_PIN, analogInputToDigitalPin(TEMP_7_PIN), + #define _H7_PINS HEATER_7_PIN, E7_AUTO_FAN_PIN, DIO_PIN(TEMP_7_PIN), #endif // HOTENDS > 7 #endif // HOTENDS > 6 #endif // HOTENDS > 5 @@ -670,13 +826,13 @@ #endif #if TEMP_SENSOR_BED && PINS_EXIST(TEMP_BED, HEATER_BED) - #define _BED_PINS HEATER_BED_PIN, analogInputToDigitalPin(TEMP_BED_PIN), + #define _BED_PINS HEATER_BED_PIN, DIO_PIN(TEMP_BED_PIN), #else #define _BED_PINS #endif #if TEMP_SENSOR_CHAMBER && PIN_EXISTS(TEMP_CHAMBER) - #define _CHAMBER_TEMP analogInputToDigitalPin(TEMP_CHAMBER_PIN), + #define _CHAMBER_TEMP DIO_PIN(TEMP_CHAMBER_PIN), #else #define _CHAMBER_TEMP #endif @@ -692,17 +848,15 @@ #endif #if TEMP_SENSOR_COOLER && PIN_EXISTS(TEMP_COOLER) - #define _COOLER_TEMP analogInputToDigitalPin(TEMP_COOLER_PIN), + #define _COOLER_TEMP DIO_PIN(TEMP_COOLER_PIN), #else #define _COOLER_TEMP #endif - #if TEMP_SENSOR_COOLER && PIN_EXISTS(COOLER) #define _COOLER COOLER_PIN, #else #define _COOLER #endif - #if TEMP_SENSOR_COOLER && PINS_EXIST(TEMP_COOLER, COOLER_AUTO_FAN) #define _COOLER_FAN COOLER_AUTO_FAN_PIN, #else @@ -713,10 +867,30 @@ #define HAL_SENSITIVE_PINS #endif -#define SENSITIVE_PINS { \ - _X_PINS _Y_PINS _Z_PINS _X2_PINS _Y2_PINS _Z2_PINS _Z3_PINS _Z4_PINS _Z_PROBE \ +#ifdef RUNTIME_ONLY_ANALOG_TO_DIGITAL + #define _SP_END +#else + #define _SP_END -2 + + // Move a regular pin in front to the end + template + struct OnlyPins : OnlyPins { }; + + // Remove a -1 from the front + template + struct OnlyPins<-1, D...> : OnlyPins { }; + + // Remove -2 from the front, emit the rest, cease propagation + template + struct OnlyPins<_SP_END, D...> { static constexpr size_t size = sizeof...(D); static constexpr pin_t table[sizeof...(D)] PROGMEM = { D... }; }; +#endif + +#define SENSITIVE_PINS \ + _X_PINS _Y_PINS _Z_PINS _I_PINS _J_PINS _K_PINS \ + _X2_PINS _Y2_PINS _Z2_PINS _Z3_PINS _Z4_PINS _Z_PROBE \ _E0_PINS _E1_PINS _E2_PINS _E3_PINS _E4_PINS _E5_PINS _E6_PINS _E7_PINS \ _H0_PINS _H1_PINS _H2_PINS _H3_PINS _H4_PINS _H5_PINS _H6_PINS _H7_PINS \ _PS_ON _FAN0 _FAN1 _FAN2 _FAN3 _FAN4 _FAN5 _FAN6 _FAN7 _FANC \ - _BED_PINS _COOLER _CHAMBER_TEMP _CHAMBER_HEATER _CHAMBER_FAN HAL_SENSITIVE_PINS \ -} + _BED_PINS _CHAMBER_TEMP _CHAMBER_HEATER _CHAMBER_FAN \ + _COOLER_TEMP _COOLER _COOLER_FAN HAL_SENSITIVE_PINS \ + _SP_END diff --git a/Marlin/src/pins/stm32f1/env_validate.h b/Marlin/src/pins/stm32f1/env_validate.h index 62ccf7edcc466..2e7b78517215d 100644 --- a/Marlin/src/pins/stm32f1/env_validate.h +++ b/Marlin/src/pins/stm32f1/env_validate.h @@ -21,6 +21,6 @@ */ #pragma once -#if NOT_TARGET(__STM32F1__) +#if NOT_TARGET(__STM32F1__, STM32F1) #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #endif diff --git a/Marlin/src/pins/stm32f1/pins_BEAST.h b/Marlin/src/pins/stm32f1/pins_BEAST.h index 05f77f10291db..2ace47822e163 100644 --- a/Marlin/src/pins/stm32f1/pins_BEAST.h +++ b/Marlin/src/pins/stm32f1/pins_BEAST.h @@ -36,34 +36,27 @@ // Ignore temp readings during development. //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 +// +// Limit Switches +// +#define X_STOP_PIN PD5 +#define Y_STOP_PIN PD6 +#define Z_STOP_PIN PD7 + // // Steppers // #define X_STEP_PIN PE0 #define X_DIR_PIN PE1 #define X_ENABLE_PIN PC0 -#define X_MIN_PIN PD5 -#define X_MAX_PIN -1 #define Y_STEP_PIN PE2 #define Y_DIR_PIN PE3 #define Y_ENABLE_PIN PC1 -#define Y_MIN_PIN PD6 -#define Y_MAX_PIN #define Z_STEP_PIN PE4 #define Z_DIR_PIN PE5 #define Z_ENABLE_PIN PC2 -#define Z_MIN_PIN PD7 -#define Z_MAX_PIN -1 - -#define Y2_STEP_PIN -1 -#define Y2_DIR_PIN -1 -#define Y2_ENABLE_PIN -1 - -#define Z2_STEP_PIN -1 -#define Z2_DIR_PIN -1 -#define Z2_ENABLE_PIN -1 #define E0_STEP_PIN PE6 #define E0_DIR_PIN PE7 @@ -87,9 +80,6 @@ #define SDSS PA15 #define LED_PIN PB2 -#define PS_ON_PIN -1 -#define KILL_PIN -1 - // // Heaters / Fans // @@ -98,8 +88,6 @@ #define HEATER_2_PIN PD14 #define HEATER_BED_PIN PB9 // BED -#define HEATER_BED2_PIN -1 // BED2 -#define HEATER_BED3_PIN -1 // BED3 #ifndef FAN_PIN #define FAN_PIN PB10 diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h index e76c77e70685d..a8be2cfc07301 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_CR6.h @@ -166,8 +166,6 @@ #if SD_CONNECTION_IS(ONBOARD) #define SD_DETECT_PIN PC4 - - #define ON_BOARD_SPI_DEVICE 1 // SPI1 #define ONBOARD_SD_CS_PIN PA4 // Chip select for "System" SD card #endif diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h index 50a533cde2b6e..9b71570b08389 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_E3_DIP.h @@ -21,9 +21,7 @@ */ #pragma once -#if NOT_TARGET(TARGET_STM32F1) - #error "Oops! Select an STM32F1 board in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "BTT SKR E3 DIP V1.x" @@ -278,6 +276,9 @@ #if SD_CONNECTION_IS(ONBOARD) #define SD_DETECT_PIN PC4 + #define SD_SCK_PIN PA5 + #define SD_MISO_PIN PA6 + #define SD_MOSI_PIN PA7 #elif SD_CONNECTION_IS(LCD) && BOTH(TOUCH_UI_FTDI_EVE, LCD_FYSETC_TFT81050) #define SD_DETECT_PIN PA15 #define SD_SS_PIN PA10 @@ -287,3 +288,4 @@ #define ONBOARD_SPI_DEVICE 1 // SPI1 #define ONBOARD_SD_CS_PIN PA4 // Chip select for "System" SD card +#define SDSS ONBOARD_SD_CS_PIN diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h index 58adc5853a4ef..5850f11ef0300 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_E3_common.h @@ -21,9 +21,7 @@ */ #pragma once -#if NOT_TARGET(__STM32F1__, STM32F1) - #error "Oops! Select an STM32F1 board in 'Tools > Board.'" -#endif +#include "env_validate.h" // Release PB3/PB4 (E0 STP/DIR) from JTAG pins #define DISABLE_JTAG @@ -282,11 +280,8 @@ #define ONBOARD_SPI_DEVICE 1 // SPI1 -> used only by HAL/STM32F1... #define ONBOARD_SD_CS_PIN PA4 // Chip select for "System" SD card -#define CUSTOM_SPI_PINS // TODO: needed because is the only way to set SPI for SD on STM32 (for now) -#if ENABLED(CUSTOM_SPI_PINS) - #define ENABLE_SPI1 - #define SDSS ONBOARD_SD_CS_PIN - #define SD_SCK_PIN PA5 - #define SD_MISO_PIN PA6 - #define SD_MOSI_PIN PA7 -#endif +#define ENABLE_SPI1 +#define SDSS ONBOARD_SD_CS_PIN +#define SD_SCK_PIN PA5 +#define SD_MISO_PIN PA6 +#define SD_MOSI_PIN PA7 diff --git a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h index 8668e1defd2d4..6b3d2832d08a3 100644 --- a/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h +++ b/Marlin/src/pins/stm32f1/pins_BTT_SKR_MINI_V1_1.h @@ -21,9 +21,7 @@ */ #pragma once -#if NOT_TARGET(TARGET_STM32F1) - #error "Oops! Select an STM32F1 board in 'Tools > Board.'" -#endif +#include "env_validate.h" #define BOARD_INFO_NAME "BTT SKR Mini V1.1" diff --git a/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h b/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h index 43dfdece44ae3..dc8b8c50f160f 100644 --- a/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h +++ b/Marlin/src/pins/stm32f1/pins_CCROBOT_MEEB_3DP.h @@ -21,9 +21,9 @@ */ #pragma once -#if NOT_TARGET(TARGET_STM32F1) - #error "Oops! Select an STM32F1 board in 'Tools > Board.'" -#elif HOTENDS > 1 || E_STEPPERS > 1 +#include "env_validate.h" + +#if HOTENDS > 1 || E_STEPPERS > 1 #error "CCROBOT-ONLINE MEEB_3DP only supports one hotend / E-stepper. Comment out this line to continue." #endif diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D.h b/Marlin/src/pins/stm32f1/pins_CHITU3D.h index dd6edf9024b67..c2025ba8c08f5 100644 --- a/Marlin/src/pins/stm32f1/pins_CHITU3D.h +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D.h @@ -38,47 +38,32 @@ // Ignore temp readings during development. //#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000 +// +// Limit Switches +// +#define X_STOP_PIN PG10 +#define Y_STOP_PIN PA12 +#define Z_STOP_PIN PA14 + // // Steppers // #define X_STEP_PIN PE5 #define X_DIR_PIN PE6 #define X_ENABLE_PIN PC13 -#define X_MIN_PIN PG10 -#define X_MAX_PIN -1 #define Y_STEP_PIN PE2 #define Y_DIR_PIN PE3 #define Y_ENABLE_PIN PE4 -#define Y_MIN_PIN PA12 -#define Y_MAX_PIN #define Z_STEP_PIN PB9 #define Z_DIR_PIN PE0 #define Z_ENABLE_PIN PE1 -#define Z_MIN_PIN PA14 -#define Z_MAX_PIN -1 - -#define Y2_STEP_PIN -1 -#define Y2_DIR_PIN -1 -#define Y2_ENABLE_PIN -1 - -#define Z2_STEP_PIN -1 -#define Z2_DIR_PIN -1 -#define Z2_ENABLE_PIN -1 #define E0_STEP_PIN PB4 #define E0_DIR_PIN PB5 #define E0_ENABLE_PIN PB8 -#define E1_STEP_PIN -1 -#define E1_DIR_PIN -1 -#define E1_ENABLE_PIN -1 - -#define E2_STEP_PIN -1 -#define E2_DIR_PIN -1 -#define E2_ENABLE_PIN -1 - // // Misc. Functions // @@ -114,8 +99,6 @@ // #define TEMP_BED_PIN PA0 // Analog Input #define TEMP_0_PIN PA1 // Analog Input -#define TEMP_1_PIN -1 // Analog Input -#define TEMP_2_PIN -1 // Analog Input // // LCD Pins diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h b/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h index d25a1f34f9fa9..8f5893e3b9ed2 100644 --- a/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D_V5.h @@ -150,26 +150,9 @@ #define HAS_LOGO_IN_FLASH 0 #elif ENABLED(TFT_COLOR_UI) // Color UI - #define TFT_DRIVER ILI9488 #define TFT_BUFFER_SIZE 14400 #endif -// XPT2046 Touch Screen calibration -#if ANY(TFT_LVGL_UI, TFT_COLOR_UI, TFT_CLASSIC_UI) - #ifndef TOUCH_CALIBRATION_X - #define TOUCH_CALIBRATION_X -17181 - #endif - #ifndef TOUCH_CALIBRATION_Y - #define TOUCH_CALIBRATION_Y 11434 - #endif - #ifndef TOUCH_OFFSET_X - #define TOUCH_OFFSET_X 501 - #endif - #ifndef TOUCH_OFFSET_Y - #define TOUCH_OFFSET_Y -9 - #endif -#endif - // SPI1(PA7)=LCD & SPI3(PB5)=STUFF, are not available // Needs to use SPI2 #define SPI_DEVICE 2 diff --git a/Marlin/src/pins/stm32f1/pins_CHITU3D_V6.h b/Marlin/src/pins/stm32f1/pins_CHITU3D_V6.h index 5afa6531170a1..df49da1095480 100644 --- a/Marlin/src/pins/stm32f1/pins_CHITU3D_V6.h +++ b/Marlin/src/pins/stm32f1/pins_CHITU3D_V6.h @@ -165,26 +165,9 @@ #define HAS_LOGO_IN_FLASH 0 #elif ENABLED(TFT_COLOR_UI) // Color UI - #define TFT_DRIVER ILI9488 #define TFT_BUFFER_SIZE 14400 #endif -// XPT2046 Touch Screen calibration -#if ANY(TFT_LVGL_UI, TFT_COLOR_UI, TFT_CLASSIC_UI) - #ifndef TOUCH_CALIBRATION_X - #define TOUCH_CALIBRATION_X -17181 - #endif - #ifndef TOUCH_CALIBRATION_Y - #define TOUCH_CALIBRATION_Y 11434 - #endif - #ifndef TOUCH_OFFSET_X - #define TOUCH_OFFSET_X 501 - #endif - #ifndef TOUCH_OFFSET_Y - #define TOUCH_OFFSET_Y -9 - #endif -#endif - // SPI1(PA7)=LCD & SPI3(PB5)=STUFF, are not available // so SPI2 is required. #define SPI_DEVICE 2 diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h index 421e33905829c..6b3c4ed8fae7b 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ +#pragma once /** * Creality 4.2.x (STM32F103RET6) board pin assignments diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h index 6585d40d45d57..d106c98e13600 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V4210.h @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ +#pragma once /** * CREALITY 4.2.10 (STM32F103) board pin assignments diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V427.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V427.h index 64ef046bd3ade..c327abee77966 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V427.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V427.h @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ +#pragma once /** * CREALITY v4.2.7 (STM32F103) board pin assignments diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V431.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V431.h index ff9f76054e6e7..e8ae84da8f9eb 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V431.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V431.h @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ +#pragma once /** * CREALITY v4.3.1 (STM32F103) board pin assignments diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V452.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V452.h index 9acbb42a88f46..ad4ddff0cea20 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V452.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V452.h @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ +#pragma once /** * Creality v4.5.2 (STM32F103RET6) board pin assignments diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V453.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V453.h index f990b2f7b4741..cdb87adece47d 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V453.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V453.h @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ +#pragma once /** * Creality v4.5.3 (STM32F103RET6) board pin assignments diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V45x.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V45x.h index c73c92080e805..39dccf1271afb 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V45x.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V45x.h @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ +#pragma once /** * Creality v4.5.2 and v4.5.3 (STM32F103RET6) board pin assignments diff --git a/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h b/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h index e33e029deb961..32d1937653d7e 100644 --- a/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h +++ b/Marlin/src/pins/stm32f1/pins_MALYAN_M200.h @@ -41,7 +41,7 @@ #define FLASH_EEPROM_EMULATION #endif -#define SDSS SD_SS_PIN +#define SDSS SD_SS_PIN // Also in HAL/STM32F1/spi_pins.h // Based on PWM timer usage, we have to use these timers and soft PWM for the fans // On STM32F103: @@ -53,9 +53,9 @@ // // Limit Switches // -#define X_MIN_PIN PB4 -#define Y_MIN_PIN PA15 -#define Z_MIN_PIN PB5 +#define X_STOP_PIN PB4 +#define Y_STOP_PIN PA15 +#define Z_STOP_PIN PB5 // // Steppers diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h index da7bdc79e50dc..b482065666fb2 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h @@ -176,8 +176,16 @@ // // SD Card // -#define SPI_DEVICE 2 +#define SPI_DEVICE 2 +#define ONBOARD_SPI_DEVICE 2 +#define SDSS SD_SS_PIN +#define SDCARD_CONNECTION ONBOARD #define SD_DETECT_PIN PC10 +#define ONBOARD_SD_CS_PIN SD_SS_PIN +#define NO_SD_HOST_DRIVE + +// TODO: This is the only way to set SPI for SD on STM32 (for now) +#define ENABLE_SPI2 #define SD_SCK_PIN PB13 #define SD_MISO_PIN PB14 #define SD_MOSI_PIN PB15 diff --git a/Marlin/src/pins/stm32f1/pins_MORPHEUS.h b/Marlin/src/pins/stm32f1/pins_MORPHEUS.h index 05e02c9e4df66..87919c12f4889 100644 --- a/Marlin/src/pins/stm32f1/pins_MORPHEUS.h +++ b/Marlin/src/pins/stm32f1/pins_MORPHEUS.h @@ -39,9 +39,9 @@ // // Limit Switches // -#define X_MIN_PIN PB14 -#define Y_MIN_PIN PB13 -#define Z_MIN_PIN PB12 +#define X_STOP_PIN PB14 +#define Y_STOP_PIN PB13 +#define Z_STOP_PIN PB12 // // Z Probe (when not Z_MIN_PIN) diff --git a/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h b/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h index d25ca1bd2ea73..7171de919d03e 100644 --- a/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h @@ -24,7 +24,7 @@ #include "env_validate.h" /** - * 21017 Victor Perez Marlin for stm32f1 test + * 10 Dec 2017 Victor Perez Marlin for stm32f1 test */ #define BOARD_INFO_NAME "STM3R Mini" diff --git a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h index 9fb13c84feb92..408048bfe249c 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h @@ -205,13 +205,10 @@ #define EXP2_10_PIN PA6 // HAL SPI1 pins -#define CUSTOM_SPI_PINS -#if ENABLED(CUSTOM_SPI_PINS) - #define SD_SCK_PIN EXP2_09_PIN // SPI1 SCLK - #define SD_SS_PIN EXP2_07_PIN // SPI1 SSEL - #define SD_MISO_PIN EXP2_10_PIN // SPI1 MISO - #define SD_MOSI_PIN EXP2_05_PIN // SPI1 MOSI -#endif +#define SD_SCK_PIN EXP2_09_PIN // SPI1 SCLK +#define SD_SS_PIN EXP2_07_PIN // SPI1 SSEL +#define SD_MISO_PIN EXP2_10_PIN // SPI1 MISO +#define SD_MOSI_PIN EXP2_05_PIN // SPI1 MOSI #define SDSS EXP2_07_PIN diff --git a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h index 621b136e1728a..a806611c18fda 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_E3_RRF.h @@ -29,58 +29,9 @@ #define BOARD_INFO_NAME "BTT E3 RRF" #endif -#define FPC2_PIN PB11 -#define FPC3_PIN PB10 -#define FPC4_PIN PE12 -#define FPC5_PIN PE13 -#define FPC6_PIN PE14 -#define FPC7_PIN PE15 -#define FPC8_PIN PA3 -#define FPC9_PIN PA2 -#define FPC10_PIN PA8 -#define FPC11_PIN PC15 -#define FPC12_PIN PC14 -#define FPC13_PIN PC13 -#define FPC14_PIN PE6 -#define FPC15_PIN PE5 -#define FPC16_PIN PE4 -#define FPC17_PIN PE3 - +// Add-on board for IDEX conversion //#define BTT_E3_RRF_IDEX_BOARD -#ifdef BTT_E3_RRF_IDEX_BOARD - - #define X2_ENABLE_PIN FPC13_PIN // X2EN - #define X2_STEP_PIN FPC11_PIN // X2STP - #define X2_DIR_PIN FPC10_PIN // X2DIR - #define X2_SERIAL_TX_PIN FPC12_PIN // X2UART - #define X2_SERIAL_RX_PIN FPC12_PIN // X2UART - #if X_HOME_TO_MIN - #define X_MAX_PIN FPC2_PIN // X2-STOP - #else - #define X_MIN_PIN FPC2_PIN // X2-STOP - #endif - - #define E1_ENABLE_PIN FPC7_PIN // E1EN - #define E1_STEP_PIN FPC5_PIN // E1STP - #define E1_DIR_PIN FPC4_PIN // E1DIR - #define E1_SERIAL_TX_PIN FPC6_PIN // E1UART - #define E1_SERIAL_RX_PIN FPC6_PIN // E1UART - - #ifndef FIL1_RUNOUT2_PIN - #define FIL_RUNOUT2_PIN FPC3_PIN // E1-STOP - #endif - - #define HEATER_1_PIN FPC16_PIN // "HE1" - - #define PT100_PIN FPC8_PIN // Analog Input "PT100"(INA826) - #define TEMP_1_PIN FPC9_PIN // Analog Input "TH1" - - #define FAN1_PIN FPC15_PIN // "FAN0" in IDEX board - #define FAN2_PIN FPC14_PIN // "FAN1" in IDEX board - -#endif - // Onboard I2C EEPROM #define I2C_EEPROM #define MARLIN_EEPROM_SIZE 0x1000 // 4KB @@ -97,6 +48,14 @@ #define Y_STOP_PIN PC1 // Y-STOP #define Z_STOP_PIN PC2 // Z-STOP +#if ENABLED(BTT_E3_RRF_IDEX_BOARD) + #if X2_USE_ENDSTOP == _XMAX_ + #define X_MAX_PIN FPC2_PIN // X2-STOP + #elif X2_USE_ENDSTOP == _XMIN_ + #define X_MIN_PIN FPC2_PIN // X2-STOP + #endif +#endif + // // Z Probe must be this pin // @@ -109,6 +68,10 @@ #define FIL_RUNOUT_PIN PC3 // E0-STOP #endif +#if !defined(FIL1_RUNOUT2_PIN) && ENABLED(BTT_E3_RRF_IDEX_BOARD) + #define FIL_RUNOUT2_PIN FPC3_PIN // E1-STOP +#endif + // // Power-loss Detection // @@ -135,6 +98,16 @@ #define E0_STEP_PIN PD12 #define E0_DIR_PIN PD13 +#if ENABLED(BTT_E3_RRF_IDEX_BOARD) + #define E1_ENABLE_PIN FPC7_PIN // E1EN + #define E1_STEP_PIN FPC5_PIN // E1STP + #define E1_DIR_PIN FPC4_PIN // E1DIR + + #define X2_ENABLE_PIN FPC13_PIN // X2EN + #define X2_STEP_PIN FPC11_PIN // X2STP + #define X2_DIR_PIN FPC10_PIN // X2DIR +#endif + /** * TMC2208/TMC2209 stepper drivers */ @@ -154,6 +127,14 @@ #define E0_SERIAL_TX_PIN PD11 #define E0_SERIAL_RX_PIN PD11 + #if ENABLED(BTT_E3_RRF_IDEX_BOARD) + #define X2_SERIAL_TX_PIN FPC12_PIN // X2UART + #define X2_SERIAL_RX_PIN FPC12_PIN // X2UART + + #define E1_SERIAL_TX_PIN FPC6_PIN // E1UART + #define E1_SERIAL_RX_PIN FPC6_PIN // E1UART + #endif + // Reduce baud rate to improve software serial reliability #define TMC_BAUD_RATE 19200 #endif @@ -164,19 +145,37 @@ #define TEMP_BED_PIN PA1 // Analog Input "TB" #define TEMP_0_PIN PA0 // Analog Input "TH0" +#if ENABLED(BTT_E3_RRF_IDEX_BOARD) + #define TEMP_1_PIN FPC9_PIN // Analog Input "TH1" + #define PT100_PIN FPC8_PIN // Analog Input "PT100" (INA826) +#endif + // // Heaters / Fans // #define HEATER_BED_PIN PB4 // "HB" #define HEATER_0_PIN PB3 // "HE0" +#if ENABLED(BTT_E3_RRF_IDEX_BOARD) + #define HEATER_1_PIN FPC16_PIN // "HE1" +#endif + #define FAN_PIN PB5 // "FAN0" -//#define FAN1_PIN PB6 // "FAN1" #ifndef CONTROLLER_FAN_PIN #define CONTROLLER_FAN_PIN PB6 // "FAN1" #endif +#if ENABLED(BTT_E3_RRF_IDEX_BOARD) + #define FAN1_PIN FPC15_PIN // "FAN0" in IDEX board + #define FAN2_PIN FPC14_PIN // "FAN1" in IDEX board +#else + //#define FAN1_PIN PB6 // "FAN1" +#endif + +// +// Misc. Functions +// #ifndef NEOPIXEL_PIN #define NEOPIXEL_PIN PB7 // LED driving pin #endif @@ -373,3 +372,22 @@ #define ESP_WIFI_MODULE_RESET_PIN PA4 #define ESP_WIFI_MODULE_ENABLE_PIN PA5 #define ESP_WIFI_MODULE_GPIO0_PIN PA6 + +#if ENABLED(BTT_E3_RRF_IDEX_BOARD) + #define FPC2_PIN PB11 + #define FPC3_PIN PB10 + #define FPC4_PIN PE12 + #define FPC5_PIN PE13 + #define FPC6_PIN PE14 + #define FPC7_PIN PE15 + #define FPC8_PIN PA3 + #define FPC9_PIN PA2 + #define FPC10_PIN PA8 + #define FPC11_PIN PC15 + #define FPC12_PIN PC14 + #define FPC13_PIN PC13 + #define FPC14_PIN PE6 + #define FPC15_PIN PE5 + #define FPC16_PIN PE4 + #define FPC17_PIN PE3 +#endif diff --git a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h index 70ac9a13c31d1..4438ed63acc4d 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h @@ -23,10 +23,10 @@ #include "env_validate.h" -#if HOTENDS > 8 || E_STEPPERS > 8 - #error "BIGTREE GTR V1.0 supports up to 8 hotends / E-steppers." -#elif HOTENDS > MAX_E_STEPPERS || E_STEPPERS > MAX_E_STEPPERS +#if E_STEPPERS > MAX_E_STEPPERS #error "Marlin extruder/hotends limit! Increase MAX_E_STEPPERS to continue." +#elif HOTENDS > 8 || E_STEPPERS > 8 + #error "BIGTREE GTR V1.0 supports up to 8 hotends / E-steppers." #endif #define BOARD_INFO_NAME "BTT GTR V1.0" @@ -357,8 +357,6 @@ #elif SD_CONNECTION_IS(ONBOARD) - // Instruct the STM32 HAL to override the default SPI pins from the variant.h file - #define CUSTOM_SPI_PINS #define SDSS PA4 #define SD_SS_PIN SDSS #define SD_SCK_PIN PA5 @@ -413,6 +411,7 @@ #define TOUCH_MOSI_PIN EXP1_08_PIN #define TOUCH_SCK_PIN EXP1_06_PIN #define TOUCH_CS_PIN EXP1_07_PIN + #define BTN_ENC EXP1_09_PIN #define BTN_EN1 EXP2_08_PIN #define BTN_EN2 EXP2_06_PIN diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h index 34fe1a824b3a2..e51e0a24bb021 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_0.h @@ -21,510 +21,6 @@ */ #pragma once -#include "env_validate.h" +#define BOARD_INFO_NAME "BTT OCTOPUS V1.0" -#ifndef BOARD_INFO_NAME - #define BOARD_INFO_NAME "BTT OCTOPUS V1.0" -#endif - -// Onboard I2C EEPROM -#define I2C_EEPROM -#define MARLIN_EEPROM_SIZE 0x8000 // 32KB (24C32A) -#define I2C_SCL_PIN PB8 -#define I2C_SDA_PIN PB9 - -// USB Flash Drive support -#define HAS_OTG_USB_HOST_SUPPORT - -// Avoid conflict with TIMER_TONE -#define STEP_TIMER 10 - -// -// Servos -#define SERVO0_PIN PB6 - -// -// Misc. Functions -// -#define LED_PIN PA13 - -// -// Trinamic Stallguard pins -// -#define X_DIAG_PIN PG6 // X-STOP -#define Y_DIAG_PIN PG9 // Y-STOP -#define Z_DIAG_PIN PG10 // Z-STOP -#define Z2_DIAG_PIN PG11 // Z2-STOP -#define E0_DIAG_PIN PG12 // E0DET -#define E1_DIAG_PIN PG13 // E1DET -#define E2_DIAG_PIN PG14 // E2DET -#define E3_DIAG_PIN PG15 // E3DET - -// Z Probe (when not Z_MIN_PIN) -// -#ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN PB7 -#endif - -// -// Limit Switches -// -#ifdef X_STALL_SENSITIVITY - #define X_STOP_PIN X_DIAG_PIN - #if X_HOME_TO_MIN - #define X_MAX_PIN E0_DIAG_PIN // E0DET - #else - #define X_MIN_PIN E0_DIAG_PIN // E0DET - #endif -#elif ENABLED(X_DUAL_ENDSTOPS) - #ifndef X_MIN_PIN - #define X_MIN_PIN X_DIAG_PIN // X-STOP - #endif - #ifndef X_MAX_PIN - #define X_MAX_PIN E0_DIAG_PIN // E0DET - #endif -#else - #define X_STOP_PIN X_DIAG_PIN // X-STOP -#endif - -#ifdef Y_STALL_SENSITIVITY - #define Y_STOP_PIN Y_DIAG_PIN - #if Y_HOME_TO_MIN - #define Y_MAX_PIN E1_DIAG_PIN // E1DET - #else - #define Y_MIN_PIN E1_DIAG_PIN // E1DET - #endif -#elif ENABLED(Y_DUAL_ENDSTOPS) - #ifndef Y_MIN_PIN - #define Y_MIN_PIN Y_DIAG_PIN // Y-STOP - #endif - #ifndef Y_MAX_PIN - #define Y_MAX_PIN E1_DIAG_PIN // E1DET - #endif -#else - #define Y_STOP_PIN Y_DIAG_PIN // Y-STOP -#endif - -#ifdef Z_STALL_SENSITIVITY - #define Z_STOP_PIN Z_DIAG_PIN - #if Z_HOME_TO_MIN - #define Z_MAX_PIN E2_DIAG_PIN // PWRDET - #else - #define Z_MIN_PIN E2_DIAG_PIN // PWRDET - #endif -#elif ENABLED(Z_MULTI_ENDSTOPS) - #ifndef Z_MIN_PIN - #define Z_MIN_PIN Z_DIAG_PIN // Z-STOP - #endif - #ifndef Z_MAX_PIN - #define Z_MAX_PIN E2_DIAG_PIN // PWRDET - #endif -#else - #define Z_STOP_PIN Z_DIAG_PIN // Z-STOP -#endif - -// -// Filament Runout Sensor -// -#define FIL_RUNOUT_PIN PG12 // E0DET -#define FIL_RUNOUT2_PIN PG13 // E1DET -#define FIL_RUNOUT3_PIN PG14 // E2DET -#define FIL_RUNOUT4_PIN PG15 // E3DET - -// -// Power Supply Control -// -#ifndef PS_ON_PIN - #define PS_ON_PIN PE11 // PS-ON -#endif - -// -// Power Loss Detection -// -#ifndef POWER_LOSS_PIN - #define POWER_LOSS_PIN PC0 // PWRDET -#endif - -// -// NeoPixel LED -// -#ifndef NEOPIXEL_PIN - #define NEOPIXEL_PIN PB0 -#endif - -// -// Steppers -// -#define X_STEP_PIN PF13 // MOTOR 0 -#define X_DIR_PIN PF12 -#define X_ENABLE_PIN PF14 -#ifndef X_CS_PIN - #define X_CS_PIN PC4 -#endif - -#define Y_STEP_PIN PG0 // MOTOR 1 -#define Y_DIR_PIN PG1 -#define Y_ENABLE_PIN PF15 -#ifndef Y_CS_PIN - #define Y_CS_PIN PD11 -#endif - -#define Z_STEP_PIN PF11 // MOTOR 2 -#define Z_DIR_PIN PG3 -#define Z_ENABLE_PIN PG5 -#ifndef Z_CS_PIN - #define Z_CS_PIN PC6 -#endif - -#define Z2_STEP_PIN PG4 // MOTOR 3 -#define Z2_DIR_PIN PC1 -#define Z2_ENABLE_PIN PA0 -#ifndef Z2_CS_PIN - #define Z2_CS_PIN PC7 -#endif - -#define E0_STEP_PIN PF9 // MOTOR 4 -#define E0_DIR_PIN PF10 -#define E0_ENABLE_PIN PG2 -#ifndef E0_CS_PIN - #define E0_CS_PIN PF2 -#endif - -#define E1_STEP_PIN PC13 // MOTOR 5 -#define E1_DIR_PIN PF0 -#define E1_ENABLE_PIN PF1 -#ifndef E1_CS_PIN - #define E1_CS_PIN PE4 -#endif - -#define E2_STEP_PIN PE2 // MOTOR 6 -#define E2_DIR_PIN PE3 -#define E2_ENABLE_PIN PD4 -#ifndef E2_CS_PIN - - #define E2_CS_PIN PE1 -#endif - -#define E3_STEP_PIN PE6 // MOTOR 7 -#define E3_DIR_PIN PA14 -#define E3_ENABLE_PIN PE0 -#ifndef E3_CS_PIN - #define E3_CS_PIN PD3 -#endif - -// -// Temperature Sensors -// -#define TEMP_BED_PIN PF3 // TB -#if TEMP_SENSOR_0 == 20 - #define TEMP_0_PIN PF8 // PT100 Connector -#else - #define TEMP_0_PIN PF4 // TH0 -#endif -#define TEMP_1_PIN PF5 // TH1 -#define TEMP_2_PIN PF6 // TH2 -#define TEMP_3_PIN PF7 // TH3 - -// -// Heaters / Fans -// -#define HEATER_BED_PIN PA1 // Hotbed -#define HEATER_0_PIN PA2 // Heater0 -#define HEATER_1_PIN PA3 // Heater1 -#define HEATER_2_PIN PB10 // Heater2 -#define HEATER_3_PIN PB11 // Heater3 - -#define FAN_PIN PA8 // Fan0 -#define FAN1_PIN PE5 // Fan1 -#define FAN2_PIN PD12 // Fan2 -#define FAN3_PIN PD13 // Fan3 -#define FAN4_PIN PD14 // Fan4 -#define FAN5_PIN PD15 // Fan5 - -// -// SD Support -// -#ifndef SDCARD_CONNECTION - #if HAS_WIRED_LCD - #define SDCARD_CONNECTION LCD - #else - #define SDCARD_CONNECTION ONBOARD - #endif -#endif - -// -// Software SPI pins for TMC2130 stepper drivers -// -#if ENABLED(TMC_USE_SW_SPI) - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PA7 - #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PA6 - #endif - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PA5 - #endif -#endif - -#if HAS_TMC_UART - /** - * TMC2208/TMC2209 stepper drivers - * - * Hardware serial communication ports. - * If undefined software serial is used according to the pins below - */ - //#define X_HARDWARE_SERIAL Serial1 - //#define X2_HARDWARE_SERIAL Serial1 - //#define Y_HARDWARE_SERIAL Serial1 - //#define Y2_HARDWARE_SERIAL Serial1 - //#define Z_HARDWARE_SERIAL Serial1 - //#define Z2_HARDWARE_SERIAL Serial1 - //#define E0_HARDWARE_SERIAL Serial1 - //#define E1_HARDWARE_SERIAL Serial1 - //#define E2_HARDWARE_SERIAL Serial1 - //#define E3_HARDWARE_SERIAL Serial1 - //#define E4_HARDWARE_SERIAL Serial1 - - // - // Software serial - // - #define X_SERIAL_TX_PIN PC4 - #define X_SERIAL_RX_PIN PC4 - - #define Y_SERIAL_TX_PIN PD11 - #define Y_SERIAL_RX_PIN PD11 - - #define Z_SERIAL_TX_PIN PC6 - #define Z_SERIAL_RX_PIN PC6 - - #define Z2_SERIAL_TX_PIN PC7 - #define Z2_SERIAL_RX_PIN PC7 - - #define E0_SERIAL_TX_PIN PF2 - #define E0_SERIAL_RX_PIN PF2 - - #define E1_SERIAL_TX_PIN PE4 - #define E1_SERIAL_RX_PIN PE4 - - #define E2_SERIAL_TX_PIN PE1 - #define E2_SERIAL_RX_PIN PE1 - - #define E3_SERIAL_TX_PIN PD3 - #define E3_SERIAL_RX_PIN PD3 - - // Reduce baud rate to improve software serial reliability - #define TMC_BAUD_RATE 19200 -#endif - -/** - * ______ ______ - * NC | 1 2 | GND 5V | 1 2 | GND - * RESET | 3 4 | PC15 (SD_DETECT) (LCD_D7) PE15 | 3 4 | PE14 (LCD_D6) - * (MOSI) PA7 | 5 6 PB1 (BTN_EN2) (LCD_D5) PE13 | 5 6 PE12 (LCD_D4) - * (SD_SS) PA4 | 7 8 | PB2 (BTN_EN1) (LCD_RS) PE10 | 7 8 | PE9 (LCD_EN) - * (SCK) PA5 | 9 10 | PA6 (MISO) (BTN_ENC) PE7 | 9 10 | PE8 (BEEPER) - * ------ ----- - * EXP2 EXP1 - */ - -#define EXP1_03_PIN PE15 -#define EXP1_04_PIN PE14 -#define EXP1_05_PIN PE13 -#define EXP1_06_PIN PE12 -#define EXP1_07_PIN PE10 -#define EXP1_08_PIN PE9 -#define EXP1_09_PIN PE7 -#define EXP1_10_PIN PE8 - -#define EXP2_03_PIN -1 -#define EXP2_04_PIN PC15 -#define EXP2_05_PIN PA7 -#define EXP2_06_PIN PB2 -#define EXP2_07_PIN PA4 -#define EXP2_08_PIN PB1 -#define EXP2_09_PIN PA5 -#define EXP2_10_PIN PA6 - -// -// Onboard SD card -// Must use soft SPI because Marlin's default hardware SPI is tied to LCD's EXP2 -// -#if SD_CONNECTION_IS(ONBOARD) - #define SDIO_SUPPORT // Use SDIO for onboard SD - #ifndef SD_DETECT_STATE - #define SD_DETECT_STATE HIGH - #elif SD_DETECT_STATE == LOW - #error "BOARD_BTT_OCTOPUS_V1_0 onboard SD requires SD_DETECT_STATE set to HIGH." - #endif - #define SD_DETECT_PIN PC14 -#elif SD_CONNECTION_IS(LCD) - - #define CUSTOM_SPI_PINS - #define SDSS PA4 - #define SD_SS_PIN SDSS - #define SD_SCK_PIN PA5 - #define SD_MISO_PIN PA6 - #define SD_MOSI_PIN PA7 - #define SD_DETECT_PIN PC15 - -#elif SD_CONNECTION_IS(CUSTOM_CABLE) - #error "CUSTOM_CABLE is not a supported SDCARD_CONNECTION for this board" -#endif - -#if ENABLED(BTT_MOTOR_EXPANSION) - /** - * ______ ______ - * NC | 1 2 | GND NC | 1 2 | GND - * NC | 3 4 | M1EN M2EN | 3 4 | M3EN - * M1STP | 5 6 M1DIR M1RX | 5 6 M1DIAG - * M2DIR | 7 8 | M2STP M2RX | 7 8 | M2DIAG - * M3DIR | 9 10 | M3STP M3RX | 9 10 | M3DIAG - * ------ ------ - * EXP2 EXP1 - */ - - // M1 on Driver Expansion Module - #define E4_STEP_PIN EXP2_05_PIN - #define E4_DIR_PIN EXP2_06_PIN - #define E4_ENABLE_PIN EXP2_04_PIN - #define E4_DIAG_PIN EXP1_06_PIN - #define E4_CS_PIN EXP1_05_PIN - #if HAS_TMC_UART - #define E4_SERIAL_TX_PIN EXP1_05_PIN - #define E4_SERIAL_RX_PIN EXP1_05_PIN - #endif - - // M2 on Driver Expansion Module - #define E5_STEP_PIN EXP2_08_PIN - #define E5_DIR_PIN EXP2_07_PIN - #define E5_ENABLE_PIN EXP1_03_PIN - #define E5_DIAG_PIN EXP1_08_PIN - #define E5_CS_PIN EXP1_07_PIN - #if HAS_TMC_UART - #define E5_SERIAL_TX_PIN EXP1_07_PIN - #define E5_SERIAL_RX_PIN EXP1_07_PIN - #endif - - // M3 on Driver Expansion Module - #define E6_STEP_PIN EXP2_10_PIN - #define E6_DIR_PIN EXP2_09_PIN - #define E6_ENABLE_PIN EXP1_04_PIN - #define E6_DIAG_PIN EXP1_10_PIN - #define E6_CS_PIN EXP1_09_PIN - #if HAS_TMC_UART - #define E6_SERIAL_TX_PIN EXP1_09_PIN - #define E6_SERIAL_RX_PIN EXP1_09_PIN - #endif - -#endif // BTT_MOTOR_EXPANSION - -// -// LCDs and Controllers -// -#if IS_TFTGLCD_PANEL - - #if ENABLED(TFTGLCD_PANEL_SPI) - #define TFTGLCD_CS EXP2_08_PIN - #endif - -#elif HAS_WIRED_LCD - - #define BEEPER_PIN EXP1_10_PIN - #define BTN_ENC EXP1_09_PIN - - #if ENABLED(CR10_STOCKDISPLAY) - - #define LCD_PINS_RS EXP1_04_PIN - - #define BTN_EN1 EXP1_08_PIN - #define BTN_EN2 EXP1_06_PIN - - #define LCD_PINS_ENABLE EXP1_03_PIN - #define LCD_PINS_D4 EXP1_05_PIN - - // CR10_STOCKDISPLAY default timing is too fast - #undef BOARD_ST7920_DELAY_1 - #undef BOARD_ST7920_DELAY_2 - #undef BOARD_ST7920_DELAY_3 - - #else - - #define LCD_PINS_RS EXP1_07_PIN - - #define BTN_EN1 EXP2_08_PIN - #define BTN_EN2 EXP2_06_PIN - - #define LCD_PINS_ENABLE EXP1_08_PIN - #define LCD_PINS_D4 EXP1_06_PIN - - #if ENABLED(FYSETC_MINI_12864) - #define DOGLCD_CS EXP1_08_PIN - #define DOGLCD_A0 EXP1_07_PIN - //#define LCD_BACKLIGHT_PIN -1 - #define LCD_RESET_PIN EXP1_06_PIN // Must be high or open for LCD to operate normally. - #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) - #ifndef RGB_LED_R_PIN - #define RGB_LED_R_PIN EXP1_05_PIN - #endif - #ifndef RGB_LED_G_PIN - #define RGB_LED_G_PIN EXP1_04_PIN - #endif - #ifndef RGB_LED_B_PIN - #define RGB_LED_B_PIN EXP1_03_PIN - #endif - #elif ENABLED(FYSETC_MINI_12864_2_1) - #define NEOPIXEL_PIN EXP1_05_PIN - #endif - #endif // !FYSETC_MINI_12864 - - #if IS_ULTIPANEL - #define LCD_PINS_D5 EXP1_05_PIN - #define LCD_PINS_D6 EXP1_04_PIN - #define LCD_PINS_D7 EXP1_03_PIN - - #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) - #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder - #endif - - #endif - - #endif -#endif // HAS_WIRED_LCD - -// Alter timing for graphical display -#if HAS_MARLINUI_U8GLIB - #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(120) // DELAY_NS(96) - #endif - #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(80) // DELAY_NS(48) - #endif - #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(580) // DELAY_NS(600) - #endif -#endif - -// -// WIFI -// - -/** - * ------- - * GND | 9 | | 8 | 3.3V - * (ESP-CS) PB12 | 10 | | 7 | PB15 (ESP-MOSI) - * 3.3V | 11 | | 6 | PB14 (ESP-MISO) - * (ESP-IO0) PD7 | 12 | | 5 | PB13 (ESP-CLK) - * (ESP-IO4) PD10 | 13 | | 4 | NC - * NC | 14 | | 3 | PE15 (ESP-EN) - * (ESP-RX) PD8 | 15 | | 2 | NC - * (ESP-TX) PD9 | 16 | | 1 | PE14 (ESP-RST) - * ------- - * WIFI - */ -#define ESP_WIFI_MODULE_COM 3 // Must also set either SERIAL_PORT or SERIAL_PORT_2 to this -#define ESP_WIFI_MODULE_BAUDRATE BAUDRATE // Must use same BAUDRATE as SERIAL_PORT & SERIAL_PORT_2 -#define ESP_WIFI_MODULE_RESET_PIN PG7 -#define ESP_WIFI_MODULE_ENABLE_PIN PG8 -#define ESP_WIFI_MODULE_GPIO0_PIN PD7 -#define ESP_WIFI_MODULE_GPIO4_PIN PD10 +#include "pins_BTT_OCTOPUS_V1_common.h" diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_1.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_1.h new file mode 100644 index 0000000000000..93240c16b8f86 --- /dev/null +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_1.h @@ -0,0 +1,26 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 + +#define BOARD_INFO_NAME "BTT OCTOPUS V1.1" + +#include "pins_BTT_OCTOPUS_V1_common.h" diff --git a/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h new file mode 100644 index 0000000000000..2cf1ee1447e70 --- /dev/null +++ b/Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h @@ -0,0 +1,525 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2021 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 "env_validate.h" + +// Onboard I2C EEPROM +#define I2C_EEPROM +#define MARLIN_EEPROM_SIZE 0x8000 // 32KB (24C32A) +#define I2C_SCL_PIN PB8 +#define I2C_SDA_PIN PB9 + +// USB Flash Drive support +#define HAS_OTG_USB_HOST_SUPPORT + +// Avoid conflict with TIMER_TONE +#define STEP_TIMER 10 + +// +// Servos +#define SERVO0_PIN PB6 + +// +// Misc. Functions +// +#define LED_PIN PA13 + +// +// Trinamic Stallguard pins +// +#define X_DIAG_PIN PG6 // X-STOP +#define Y_DIAG_PIN PG9 // Y-STOP +#define Z_DIAG_PIN PG10 // Z-STOP +#define Z2_DIAG_PIN PG11 // Z2-STOP +#define E0_DIAG_PIN PG12 // E0DET +#define E1_DIAG_PIN PG13 // E1DET +#define E2_DIAG_PIN PG14 // E2DET +#define E3_DIAG_PIN PG15 // E3DET + +// Z Probe (when not Z_MIN_PIN) +// +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN PB7 +#endif + +// +// Limit Switches +// +#ifdef X_STALL_SENSITIVITY + #define X_STOP_PIN X_DIAG_PIN + #if X_HOME_TO_MIN + #define X_MAX_PIN E0_DIAG_PIN // E0DET + #else + #define X_MIN_PIN E0_DIAG_PIN // E0DET + #endif +#elif ENABLED(X_DUAL_ENDSTOPS) + #ifndef X_MIN_PIN + #define X_MIN_PIN X_DIAG_PIN // X-STOP + #endif + #ifndef X_MAX_PIN + #define X_MAX_PIN E0_DIAG_PIN // E0DET + #endif +#else + #define X_STOP_PIN X_DIAG_PIN // X-STOP +#endif + +#ifdef Y_STALL_SENSITIVITY + #define Y_STOP_PIN Y_DIAG_PIN + #if Y_HOME_TO_MIN + #define Y_MAX_PIN E1_DIAG_PIN // E1DET + #else + #define Y_MIN_PIN E1_DIAG_PIN // E1DET + #endif +#elif ENABLED(Y_DUAL_ENDSTOPS) + #ifndef Y_MIN_PIN + #define Y_MIN_PIN Y_DIAG_PIN // Y-STOP + #endif + #ifndef Y_MAX_PIN + #define Y_MAX_PIN E1_DIAG_PIN // E1DET + #endif +#else + #define Y_STOP_PIN Y_DIAG_PIN // Y-STOP +#endif + +#ifdef Z_STALL_SENSITIVITY + #define Z_STOP_PIN Z_DIAG_PIN + #if Z_HOME_TO_MIN + #define Z_MAX_PIN E2_DIAG_PIN // PWRDET + #else + #define Z_MIN_PIN E2_DIAG_PIN // PWRDET + #endif +#elif ENABLED(Z_MULTI_ENDSTOPS) + #ifndef Z_MIN_PIN + #define Z_MIN_PIN Z_DIAG_PIN // Z-STOP + #endif + #ifndef Z_MAX_PIN + #define Z_MAX_PIN E2_DIAG_PIN // PWRDET + #endif +#else + #define Z_STOP_PIN Z_DIAG_PIN // Z-STOP +#endif + +// +// Filament Runout Sensor +// +#define FIL_RUNOUT_PIN PG12 // E0DET +#define FIL_RUNOUT2_PIN PG13 // E1DET +#define FIL_RUNOUT3_PIN PG14 // E2DET +#define FIL_RUNOUT4_PIN PG15 // E3DET + +// +// Power Supply Control +// +#ifndef PS_ON_PIN + #define PS_ON_PIN PE11 // PS-ON +#endif + +// +// Power Loss Detection +// +#ifndef POWER_LOSS_PIN + #define POWER_LOSS_PIN PC0 // PWRDET +#endif + +// +// NeoPixel LED +// +#ifndef NEOPIXEL_PIN + #define NEOPIXEL_PIN PB0 +#endif + +// +// Steppers +// +#define X_STEP_PIN PF13 // MOTOR 0 +#define X_DIR_PIN PF12 +#define X_ENABLE_PIN PF14 +#ifndef X_CS_PIN + #define X_CS_PIN PC4 +#endif + +#define Y_STEP_PIN PG0 // MOTOR 1 +#define Y_DIR_PIN PG1 +#define Y_ENABLE_PIN PF15 +#ifndef Y_CS_PIN + #define Y_CS_PIN PD11 +#endif + +#define Z_STEP_PIN PF11 // MOTOR 2 +#define Z_DIR_PIN PG3 +#define Z_ENABLE_PIN PG5 +#ifndef Z_CS_PIN + #define Z_CS_PIN PC6 +#endif + +#define Z2_STEP_PIN PG4 // MOTOR 3 +#define Z2_DIR_PIN PC1 +#define Z2_ENABLE_PIN PA0 +#ifndef Z2_CS_PIN + #define Z2_CS_PIN PC7 +#endif + +#define E0_STEP_PIN PF9 // MOTOR 4 +#define E0_DIR_PIN PF10 +#define E0_ENABLE_PIN PG2 +#ifndef E0_CS_PIN + #define E0_CS_PIN PF2 +#endif + +#define E1_STEP_PIN PC13 // MOTOR 5 +#define E1_DIR_PIN PF0 +#define E1_ENABLE_PIN PF1 +#ifndef E1_CS_PIN + #define E1_CS_PIN PE4 +#endif + +#define E2_STEP_PIN PE2 // MOTOR 6 +#define E2_DIR_PIN PE3 +#define E2_ENABLE_PIN PD4 +#ifndef E2_CS_PIN + + #define E2_CS_PIN PE1 +#endif + +#define E3_STEP_PIN PE6 // MOTOR 7 +#define E3_DIR_PIN PA14 +#define E3_ENABLE_PIN PE0 +#ifndef E3_CS_PIN + #define E3_CS_PIN PD3 +#endif + +// +// Temperature Sensors +// +#define TEMP_BED_PIN PF3 // TB +#if TEMP_SENSOR_0 == 20 + #define TEMP_0_PIN PF8 // PT100 Connector +#else + #define TEMP_0_PIN PF4 // TH0 +#endif +#define TEMP_1_PIN PF5 // TH1 +#define TEMP_2_PIN PF6 // TH2 +#define TEMP_3_PIN PF7 // TH3 + +// +// Heaters / Fans +// +#define HEATER_BED_PIN PA1 // Hotbed +#define HEATER_0_PIN PA2 // Heater0 +#define HEATER_1_PIN PA3 // Heater1 +#define HEATER_2_PIN PB10 // Heater2 +#define HEATER_3_PIN PB11 // Heater3 + +#define FAN_PIN PA8 // Fan0 +#define FAN1_PIN PE5 // Fan1 +#define FAN2_PIN PD12 // Fan2 +#define FAN3_PIN PD13 // Fan3 +#define FAN4_PIN PD14 // Fan4 +#define FAN5_PIN PD15 // Fan5 + +// +// SD Support +// +#ifndef SDCARD_CONNECTION + #if HAS_WIRED_LCD + #define SDCARD_CONNECTION LCD + #else + #define SDCARD_CONNECTION ONBOARD + #endif +#endif + +// +// Software SPI pins for TMC2130 stepper drivers +// +#if ENABLED(TMC_USE_SW_SPI) + #ifndef TMC_SW_MOSI + #define TMC_SW_MOSI PA7 + #endif + #ifndef TMC_SW_MISO + #define TMC_SW_MISO PA6 + #endif + #ifndef TMC_SW_SCK + #define TMC_SW_SCK PA5 + #endif +#endif + +#if HAS_TMC_UART + /** + * TMC2208/TMC2209 stepper drivers + * + * Hardware serial communication ports. + * If undefined software serial is used according to the pins below + */ + //#define X_HARDWARE_SERIAL Serial1 + //#define X2_HARDWARE_SERIAL Serial1 + //#define Y_HARDWARE_SERIAL Serial1 + //#define Y2_HARDWARE_SERIAL Serial1 + //#define Z_HARDWARE_SERIAL Serial1 + //#define Z2_HARDWARE_SERIAL Serial1 + //#define E0_HARDWARE_SERIAL Serial1 + //#define E1_HARDWARE_SERIAL Serial1 + //#define E2_HARDWARE_SERIAL Serial1 + //#define E3_HARDWARE_SERIAL Serial1 + //#define E4_HARDWARE_SERIAL Serial1 + + // + // Software serial + // + #define X_SERIAL_TX_PIN PC4 + #define X_SERIAL_RX_PIN PC4 + + #define Y_SERIAL_TX_PIN PD11 + #define Y_SERIAL_RX_PIN PD11 + + #define Z_SERIAL_TX_PIN PC6 + #define Z_SERIAL_RX_PIN PC6 + + #define Z2_SERIAL_TX_PIN PC7 + #define Z2_SERIAL_RX_PIN PC7 + + #define E0_SERIAL_TX_PIN PF2 + #define E0_SERIAL_RX_PIN PF2 + + #define E1_SERIAL_TX_PIN PE4 + #define E1_SERIAL_RX_PIN PE4 + + #define E2_SERIAL_TX_PIN PE1 + #define E2_SERIAL_RX_PIN PE1 + + #define E3_SERIAL_TX_PIN PD3 + #define E3_SERIAL_RX_PIN PD3 + + // Reduce baud rate to improve software serial reliability + #define TMC_BAUD_RATE 19200 +#endif + +/** + * ______ ______ + * NC | 1 2 | GND 5V | 1 2 | GND + * RESET | 3 4 | PC15 (SD_DETECT) (LCD_D7) PE15 | 3 4 | PE14 (LCD_D6) + * (MOSI) PA7 | 5 6 PB1 (BTN_EN2) (LCD_D5) PE13 | 5 6 PE12 (LCD_D4) + * (SD_SS) PA4 | 7 8 | PB2 (BTN_EN1) (LCD_RS) PE10 | 7 8 | PE9 (LCD_EN) + * (SCK) PA5 | 9 10 | PA6 (MISO) (BTN_ENC) PE7 | 9 10 | PE8 (BEEPER) + * ------ ----- + * EXP2 EXP1 + */ + +#define EXP1_03_PIN PE15 +#define EXP1_04_PIN PE14 +#define EXP1_05_PIN PE13 +#define EXP1_06_PIN PE12 +#define EXP1_07_PIN PE10 +#define EXP1_08_PIN PE9 +#define EXP1_09_PIN PE7 +#define EXP1_10_PIN PE8 + +#define EXP2_03_PIN -1 +#define EXP2_04_PIN PC15 +#define EXP2_05_PIN PA7 +#define EXP2_06_PIN PB2 +#define EXP2_07_PIN PA4 +#define EXP2_08_PIN PB1 +#define EXP2_09_PIN PA5 +#define EXP2_10_PIN PA6 + +// +// Onboard SD card +// Must use soft SPI because Marlin's default hardware SPI is tied to LCD's EXP2 +// +#if SD_CONNECTION_IS(ONBOARD) + #define SDIO_SUPPORT // Use SDIO for onboard SD + #ifndef SD_DETECT_STATE + #define SD_DETECT_STATE HIGH + #elif SD_DETECT_STATE == LOW + #error "BOARD_BTT_OCTOPUS_V1_0 onboard SD requires SD_DETECT_STATE set to HIGH." + #endif + #define SD_DETECT_PIN PC14 +#elif SD_CONNECTION_IS(LCD) + + #define SDSS PA4 + #define SD_SS_PIN SDSS + #define SD_SCK_PIN PA5 + #define SD_MISO_PIN PA6 + #define SD_MOSI_PIN PA7 + #define SD_DETECT_PIN PC15 + +#elif SD_CONNECTION_IS(CUSTOM_CABLE) + #error "CUSTOM_CABLE is not a supported SDCARD_CONNECTION for this board" +#endif + +#if ENABLED(BTT_MOTOR_EXPANSION) + /** + * ______ ______ + * NC | 1 2 | GND NC | 1 2 | GND + * NC | 3 4 | M1EN M2EN | 3 4 | M3EN + * M1STP | 5 6 M1DIR M1RX | 5 6 M1DIAG + * M2DIR | 7 8 | M2STP M2RX | 7 8 | M2DIAG + * M3DIR | 9 10 | M3STP M3RX | 9 10 | M3DIAG + * ------ ------ + * EXP2 EXP1 + */ + + // M1 on Driver Expansion Module + #define E4_STEP_PIN EXP2_05_PIN + #define E4_DIR_PIN EXP2_06_PIN + #define E4_ENABLE_PIN EXP2_04_PIN + #define E4_DIAG_PIN EXP1_06_PIN + #define E4_CS_PIN EXP1_05_PIN + #if HAS_TMC_UART + #define E4_SERIAL_TX_PIN EXP1_05_PIN + #define E4_SERIAL_RX_PIN EXP1_05_PIN + #endif + + // M2 on Driver Expansion Module + #define E5_STEP_PIN EXP2_08_PIN + #define E5_DIR_PIN EXP2_07_PIN + #define E5_ENABLE_PIN EXP1_03_PIN + #define E5_DIAG_PIN EXP1_08_PIN + #define E5_CS_PIN EXP1_07_PIN + #if HAS_TMC_UART + #define E5_SERIAL_TX_PIN EXP1_07_PIN + #define E5_SERIAL_RX_PIN EXP1_07_PIN + #endif + + // M3 on Driver Expansion Module + #define E6_STEP_PIN EXP2_10_PIN + #define E6_DIR_PIN EXP2_09_PIN + #define E6_ENABLE_PIN EXP1_04_PIN + #define E6_DIAG_PIN EXP1_10_PIN + #define E6_CS_PIN EXP1_09_PIN + #if HAS_TMC_UART + #define E6_SERIAL_TX_PIN EXP1_09_PIN + #define E6_SERIAL_RX_PIN EXP1_09_PIN + #endif + +#endif // BTT_MOTOR_EXPANSION + +// +// LCDs and Controllers +// +#if IS_TFTGLCD_PANEL + + #if ENABLED(TFTGLCD_PANEL_SPI) + #define TFTGLCD_CS EXP2_08_PIN + #endif + +#elif HAS_WIRED_LCD + + #define BEEPER_PIN EXP1_10_PIN + #define BTN_ENC EXP1_09_PIN + + #if ENABLED(CR10_STOCKDISPLAY) + + #define LCD_PINS_RS EXP1_04_PIN + + #define BTN_EN1 EXP1_08_PIN + #define BTN_EN2 EXP1_06_PIN + + #define LCD_PINS_ENABLE EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN + + // CR10_STOCKDISPLAY default timing is too fast + #undef BOARD_ST7920_DELAY_1 + #undef BOARD_ST7920_DELAY_2 + #undef BOARD_ST7920_DELAY_3 + + #else + + #define LCD_PINS_RS EXP1_07_PIN + + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN + + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN + + #if ENABLED(FYSETC_MINI_12864) + #define DOGLCD_CS EXP1_08_PIN + #define DOGLCD_A0 EXP1_07_PIN + //#define LCD_BACKLIGHT_PIN -1 + #define LCD_RESET_PIN EXP1_06_PIN // Must be high or open for LCD to operate normally. + #if EITHER(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #ifndef RGB_LED_R_PIN + #define RGB_LED_R_PIN EXP1_05_PIN + #endif + #ifndef RGB_LED_G_PIN + #define RGB_LED_G_PIN EXP1_04_PIN + #endif + #ifndef RGB_LED_B_PIN + #define RGB_LED_B_PIN EXP1_03_PIN + #endif + #elif ENABLED(FYSETC_MINI_12864_2_1) + #define NEOPIXEL_PIN EXP1_05_PIN + #endif + #endif // !FYSETC_MINI_12864 + + #if IS_ULTIPANEL + #define LCD_PINS_D5 EXP1_05_PIN + #define LCD_PINS_D6 EXP1_04_PIN + #define LCD_PINS_D7 EXP1_03_PIN + + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif + + #endif + + #endif +#endif // HAS_WIRED_LCD + +// Alter timing for graphical display +#if HAS_MARLINUI_U8GLIB + #ifndef BOARD_ST7920_DELAY_1 + #define BOARD_ST7920_DELAY_1 DELAY_NS(120) // DELAY_NS(96) + #endif + #ifndef BOARD_ST7920_DELAY_2 + #define BOARD_ST7920_DELAY_2 DELAY_NS(80) // DELAY_NS(48) + #endif + #ifndef BOARD_ST7920_DELAY_3 + #define BOARD_ST7920_DELAY_3 DELAY_NS(580) // DELAY_NS(600) + #endif +#endif + +// +// WIFI +// + +/** + * ------- + * GND | 9 | | 8 | 3.3V + * (ESP-CS) PB12 | 10 | | 7 | PB15 (ESP-MOSI) + * 3.3V | 11 | | 6 | PB14 (ESP-MISO) + * (ESP-IO0) PD7 | 12 | | 5 | PB13 (ESP-CLK) + * (ESP-IO4) PD10 | 13 | | 4 | NC + * NC | 14 | | 3 | PE15 (ESP-EN) + * (ESP-RX) PD8 | 15 | | 2 | NC + * (ESP-TX) PD9 | 16 | | 1 | PE14 (ESP-RST) + * ------- + * WIFI + */ +#define ESP_WIFI_MODULE_COM 3 // Must also set either SERIAL_PORT or SERIAL_PORT_2 to this +#define ESP_WIFI_MODULE_BAUDRATE BAUDRATE // Must use same BAUDRATE as SERIAL_PORT & SERIAL_PORT_2 +#define ESP_WIFI_MODULE_RESET_PIN PG7 +#define ESP_WIFI_MODULE_ENABLE_PIN PG8 +#define ESP_WIFI_MODULE_GPIO0_PIN PD7 +#define ESP_WIFI_MODULE_GPIO4_PIN PD10 diff --git a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h index 5e2f88190d730..d465bb23c71e2 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h @@ -348,7 +348,6 @@ #elif SD_CONNECTION_IS(LCD) - #define CUSTOM_SPI_PINS #define SDSS PA4 #define SD_SS_PIN SDSS #define SD_SCK_PIN PA5 @@ -502,13 +501,13 @@ // Alter timing for graphical display #if HAS_MARLINUI_U8GLIB #ifndef BOARD_ST7920_DELAY_1 - #define BOARD_ST7920_DELAY_1 DELAY_NS(96) + #define BOARD_ST7920_DELAY_1 DELAY_NS(120) #endif #ifndef BOARD_ST7920_DELAY_2 - #define BOARD_ST7920_DELAY_2 DELAY_NS(48) + #define BOARD_ST7920_DELAY_2 DELAY_NS(80) #endif #ifndef BOARD_ST7920_DELAY_3 - #define BOARD_ST7920_DELAY_3 DELAY_NS(600) + #define BOARD_ST7920_DELAY_3 DELAY_NS(580) #endif #endif diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h index 726e9a6586265..5a056b97cdfa7 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3.h @@ -190,7 +190,9 @@ #define FIL_RUNOUT2_PIN MT_DET_2 #endif -#define POWER_LOSS_PIN PW_DET +#ifndef POWER_LOSS_PIN + #define POWER_LOSS_PIN PW_DET +#endif #define PS_ON_PIN PW_OFF // @@ -217,37 +219,31 @@ // // detect pin dont work when ONBOARD and NO_SD_HOST_DRIVE disabled #if SD_CONNECTION_IS(ONBOARD) - #define CUSTOM_SPI_PINS // TODO: needed because is the only way to set SPI3 for SD on STM32 (by now) - #if ENABLED(CUSTOM_SPI_PINS) - #define ENABLE_SPI3 - #define SD_SS_PIN -1 - #define SDSS PC9 - #define SD_SCK_PIN PC10 - #define SD_MISO_PIN PC11 - #define SD_MOSI_PIN PC12 - #define SD_DETECT_PIN PD12 - #endif + #define ENABLE_SPI3 + #define SD_SS_PIN -1 + #define SDSS PC9 + #define SD_SCK_PIN PC10 + #define SD_MISO_PIN PC11 + #define SD_MOSI_PIN PC12 + #define SD_DETECT_PIN PD12 #endif // // LCD SD // #if SD_CONNECTION_IS(LCD) - #define CUSTOM_SPI_PINS - #if ENABLED(CUSTOM_SPI_PINS) - #define ENABLE_SPI1 - #define SDSS PE10 - #define SD_SCK_PIN PA5 - #define SD_MISO_PIN PA6 - #define SD_MOSI_PIN PA7 - #define SD_DETECT_PIN PE12 - #endif + #define ENABLE_SPI1 + #define SDSS PE10 + #define SD_SCK_PIN PA5 + #define SD_MISO_PIN PA6 + #define SD_MOSI_PIN PA7 + #define SD_DETECT_PIN PE12 #endif // // LCD / Controller #define SPI_FLASH -#define HAS_SPI_FLASH 1 +#define HAS_SPI_FLASH 1 #define SPI_DEVICE 2 #define SPI_FLASH_SIZE 0x1000000 #if ENABLED(SPI_FLASH) diff --git a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h index 1000326dad8ca..2b0df002d394a 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_ROBIN_PRO_V2.h @@ -31,7 +31,7 @@ #define BOARD_INFO_NAME "MKS Robin PRO V2" // Avoid conflict with TIMER_TONE -#define STEP_TIMER 10 +#define STEP_TIMER 10 // Use one of these or SDCard-based Emulation will be used //#define SRAM_EEPROM_EMULATION // Use BackSRAM-based EEPROM emulation @@ -50,7 +50,7 @@ // // Note: MKS Robin board is using SPI2 interface. // -//#define SPI_MODULE 2 +//#define SPI_MODULE 2 // // Servos @@ -203,7 +203,7 @@ //#define LED_PIN PB2 #ifndef SDCARD_CONNECTION - #define SDCARD_CONNECTION ONBOARD + #define SDCARD_CONNECTION ONBOARD #endif //#define USE_NEW_SPI_API 1 @@ -214,21 +214,17 @@ // // detect pin dont work when ONBOARD and NO_SD_HOST_DRIVE disabled #if !defined(SDCARD_CONNECTION) || SDCARD_CONNECTION == ONBOARD - #define CUSTOM_SPI_PINS - #if ENABLED(CUSTOM_SPI_PINS) - - #if USE_NEW_SPI_API - #define SD_SPI MARLIN_SPI(HardwareSPI3, PC9) - #else - #define ENABLE_SPI3 - #define SD_SS_PIN -1 - #define SDSS PC9 - #define SD_SCK_PIN PC10 - #define SD_MISO_PIN PC11 - #define SD_MOSI_PIN PC12 - #endif - #define SD_DETECT_PIN PD12 + #if USE_NEW_SPI_API + #define SD_SPI MARLIN_SPI(HardwareSPI3, PC9) + #else + #define ENABLE_SPI3 + #define SD_SS_PIN -1 + #define SDSS PC9 + #define SD_SCK_PIN PC10 + #define SD_MISO_PIN PC11 + #define SD_MOSI_PIN PC12 #endif + #define SD_DETECT_PIN PD12 #endif /* @@ -236,22 +232,19 @@ // LCD SD // #if SDCARD_CONNECTION == LCD - #define CUSTOM_SPI_PINS - #if ENABLED(CUSTOM_SPI_PINS) - #define ENABLE_SPI1 - #define SDSS PE10 - #define SD_SCK_PIN PA5 - #define SD_MISO_PIN PA6 - #define SD_MOSI_PIN PA7 - #define SD_DETECT_PIN PE12 - #endif + #define ENABLE_SPI1 + #define SDSS PE10 + #define SD_SCK_PIN PA5 + #define SD_MISO_PIN PA6 + #define SD_MOSI_PIN PA7 + #define SD_DETECT_PIN PE12 #endif */ // // LCD / Controller #define SPI_FLASH -#define HAS_SPI_FLASH 1 +#define HAS_SPI_FLASH 1 #define SPI_DEVICE 2 #define SPI_FLASH_SIZE 0x1000000 #if ENABLED(SPI_FLASH) diff --git a/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h b/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h index dc02fd02eac65..5f8ffe975b8d7 100644 --- a/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h +++ b/Marlin/src/pins/stm32f4/pins_STEVAL_3DP001V1.h @@ -173,7 +173,6 @@ // // Misc functions // -#define SDSS 16 // PA4 SPI_CS #define LED_PIN -1 // 9 // PE1 green LED Heart beat #define PS_ON_PIN -1 #define KILL_PIN -1 @@ -245,7 +244,6 @@ #ifndef SDIO_SUPPORT #define SOFTWARE_SPI // Use soft SPI for onboard SD - #undef SDSS #define SDSS SDIO_D3_PIN #define SD_SCK_PIN SDIO_CK_PIN #define SD_MISO_PIN SDIO_D0_PIN @@ -253,6 +251,10 @@ #endif #endif +#ifndef SDSS + #define SDSS 16 // PA4 SPI_CS +#endif + // OTG // 30 // PA11 OTG_DM // 31 // PA12 OTG_DP diff --git a/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h b/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h index 7b3685d08e7a3..cb038fe737027 100644 --- a/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h +++ b/Marlin/src/pins/teensy2/pins_PRINTRBOARD.h @@ -116,7 +116,6 @@ // // Misc. Functions // -#define SDSS 26 // B6 SDCS #define FILWIDTH_PIN 2 // Analog Input // @@ -142,7 +141,6 @@ #define BTN_EN2 3 // D3 RX1 JP2-7 #define BTN_ENC 45 // F7 TDI JP2-12 - #undef SDSS #define SDSS 43 // F5 TMS JP2-8 #define STAT_LED_RED_PIN 12 // C2 JP11-14 @@ -153,7 +151,7 @@ #define BTN_EN1 3 // D3 RX1 JP2-7 #define BTN_EN2 2 // D2 TX1 JP2-5 #define BTN_ENC 41 // F3 JP2-4 - #undef SDSS + #define SDSS 38 // F0 B-THERM connector - use SD card on Panelolu2 #else @@ -165,3 +163,7 @@ #endif #endif // IS_ULTRA_LCD && IS_NEWPANEL + +#ifndef SDSS + #define SDSS 26 // B6 SDCS +#endif diff --git a/Marlin/src/pins/teensy2/pins_TEENSYLU.h b/Marlin/src/pins/teensy2/pins_TEENSYLU.h index f551d802cfb28..535ce534d437d 100644 --- a/Marlin/src/pins/teensy2/pins_TEENSYLU.h +++ b/Marlin/src/pins/teensy2/pins_TEENSYLU.h @@ -18,6 +18,7 @@ * You should have received a copy of the GNU General Public License * along with this program. If not, see . */ +#pragma once /** * Rev C 2 JUN 2017 diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 405da103de739..19b2f04bfda86 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -59,6 +59,7 @@ // extern +PGMSTR(M21_STR, "M21"); PGMSTR(M23_STR, "M23 %s"); PGMSTR(M24_STR, "M24"); @@ -120,13 +121,12 @@ uint8_t CardReader::workDirDepth; #endif // SDCARD_SORT_ALPHA -#if SHARED_VOLUME_IS(USB_FLASH_DRIVE) || ENABLED(USB_FLASH_DRIVE_SUPPORT) - DiskIODriver_USBFlash CardReader::media_usbFlashDrive; +#if HAS_USB_FLASH_DRIVE + DiskIODriver_USBFlash CardReader::media_driver_usbFlash; #endif -#if NEED_SD2CARD_SDIO - DiskIODriver_SDIO CardReader::media_sdio; -#elif NEED_SD2CARD_SPI - DiskIODriver_SPI_SD CardReader::media_sd_spi; + +#if NEED_SD2CARD_SDIO || NEED_SD2CARD_SPI + CardReader::sdcard_driver_t CardReader::media_driver_sdcard; #endif DiskIODriver* CardReader::driver = nullptr; @@ -143,12 +143,10 @@ uint32_t CardReader::filesize, CardReader::sdpos; CardReader::CardReader() { changeMedia(& - #if SHARED_VOLUME_IS(SD_ONBOARD) - media_sd_spi - #elif SHARED_VOLUME_IS(USB_FLASH_DRIVE) || ENABLED(USB_FLASH_DRIVE_SUPPORT) - media_usbFlashDrive + #if HAS_USB_FLASH_DRIVE && !SHARED_VOLUME_IS(SD_ONBOARD) + media_driver_usbFlash #else - TERN(SDIO_SUPPORT, media_sdio, media_sd_spi) + media_driver_sdcard #endif ); diff --git a/Marlin/src/sd/cardreader.h b/Marlin/src/sd/cardreader.h index 35d762742164c..943cdae7418f1 100644 --- a/Marlin/src/sd/cardreader.h +++ b/Marlin/src/sd/cardreader.h @@ -235,12 +235,13 @@ class CardReader { #endif #if SHARED_VOLUME_IS(USB_FLASH_DRIVE) || ENABLED(USB_FLASH_DRIVE_SUPPORT) - static DiskIODriver_USBFlash media_usbFlashDrive; + #define HAS_USB_FLASH_DRIVE 1 + static DiskIODriver_USBFlash media_driver_usbFlash; #endif - #if NEED_SD2CARD_SDIO - static DiskIODriver_SDIO media_sdio; - #elif NEED_SD2CARD_SPI - static DiskIODriver_SPI_SD media_sd_spi; + + #if NEED_SD2CARD_SDIO || NEED_SD2CARD_SPI + typedef TERN(NEED_SD2CARD_SDIO, DiskIODriver_SDIO, DiskIODriver_SPI_SD) sdcard_driver_t; + static sdcard_driver_t media_driver_sdcard; #endif private: diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.cpp b/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.cpp index a84a683204133..1aeef1703fecc 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.cpp +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.cpp @@ -956,12 +956,6 @@ uint8_t BulkOnly::HandleUsbError(uint8_t error, uint8_t index) { return ((error && !count) ? MASS_ERR_GENERAL_USB_ERROR : MASS_ERR_SUCCESS); } -#if MS_WANT_PARSER - uint8_t BulkOnly::Transaction(CommandBlockWrapper *pcbw, uint16_t buf_size, void *buf) { - return Transaction(CommandBlockWrapper *pcbw, uint16_t buf_size, void *buf, 0); - } -#endif - /** * For driver use only. * @@ -972,9 +966,7 @@ uint8_t BulkOnly::HandleUsbError(uint8_t error, uint8_t index) { * @return */ uint8_t BulkOnly::Transaction(CommandBlockWrapper *pcbw, uint16_t buf_size, void *buf - #if MS_WANT_PARSER - , uint8_t flags - #endif + OPTARG(MS_WANT_PARSER, uint8_t flags/*=0*/) ) { #if MS_WANT_PARSER uint16_t bytes = (pcbw->dCBWDataTransferLength > buf_size) ? buf_size : pcbw->dCBWDataTransferLength; diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.h b/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.h index 25df006e513d1..aafb91624b00e 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.h @@ -553,10 +553,7 @@ class BulkOnly : public USBDeviceConfig, public UsbConfigXtracter { bool IsValidCSW(CommandStatusWrapper *pcsw, CommandBlockWrapperBase *pcbw); uint8_t ClearEpHalt(uint8_t index); - #if MS_WANT_PARSER - uint8_t Transaction(CommandBlockWrapper *cbw, uint16_t bsize, void *buf, uint8_t flags); - #endif - uint8_t Transaction(CommandBlockWrapper *cbw, uint16_t bsize, void *buf); + uint8_t Transaction(CommandBlockWrapper *cbw, uint16_t bsize, void *buf OPTARG(MS_WANT_PARSER, uint8_t flags=0)); uint8_t HandleUsbError(uint8_t error, uint8_t index); uint8_t HandleSCSIError(uint8_t status); }; diff --git a/README.md b/README.md index 764206c110510..6106c333e77f5 100644 --- a/README.md +++ b/README.md @@ -79,7 +79,7 @@ Regular users can open and close their own issues, but only the administrators c - Victor Oliveira [[@rhapsodyv](https://github.com/rhapsodyv)] - Brazil - Chris Pepper [[@p3p](https://github.com/p3p)] - UK - Jason Smith [[@sjasonsmith](https://github.com/sjasonsmith)] - USA - - Luu Lac [[@sjasonsmith](https://github.com/sjasonsmith)] - USA + - Luu Lac [[@shitcreek](https://github.com/shitcreek)] - USA - Bob Kuhn [[@Bob-the-Kuhn](https://github.com/Bob-the-Kuhn)] - USA - Erik van der Zalm [[@ErikZalm](https://github.com/ErikZalm)] - Netherlands   [![Flattr Erik](https://api.flattr.com/button/flattr-badge-large.png)](https://flattr.com/submit/auto?user_id=ErikZalm&url=https://github.com/MarlinFirmware/Marlin&title=Marlin&language=&tags=github&category=software) diff --git a/buildroot/bin/mftest b/buildroot/bin/mftest index ea7472c5da1c3..e0c1d8f38d2d6 100755 --- a/buildroot/bin/mftest +++ b/buildroot/bin/mftest @@ -37,7 +37,7 @@ env shortcuts: tree due esp lin lpc|lpc8 lpc9 m128 m256|mega stm|f1 f4 f7 s6 tee TESTPATH=buildroot/tests STATE_FILE="./.pio/.mftestrc" -SED=$(which gsed || which sed) +SED=$(which gsed sed | head -n1) shopt -s extglob nocasematch diff --git a/buildroot/bin/opt_disable b/buildroot/bin/opt_disable index 18ec03aa9432c..0444e1b773e04 100755 --- a/buildroot/bin/opt_disable +++ b/buildroot/bin/opt_disable @@ -3,7 +3,7 @@ # exit on first failure set -e -SED=$(which gsed || which sed) +SED=$(which gsed sed | head -n1) for opt in "$@" ; do DID=0 ; FOUND=0 diff --git a/buildroot/bin/opt_enable b/buildroot/bin/opt_enable index d341ee9bd3ea9..f9be82cbd1f95 100755 --- a/buildroot/bin/opt_enable +++ b/buildroot/bin/opt_enable @@ -3,7 +3,7 @@ # exit on first failure set -e -SED=$(which gsed || which sed) +SED=$(which gsed sed | head -n1) for opt in "$@" ; do DID=0 ; FOUND=0 diff --git a/buildroot/bin/opt_set b/buildroot/bin/opt_set index 3f67d78900537..b9935512a4b84 100755 --- a/buildroot/bin/opt_set +++ b/buildroot/bin/opt_set @@ -3,7 +3,7 @@ # exit on first failure set -e -SED=$(which gsed || which sed) +SED=$(which gsed sed | head -n1) while [[ $# > 1 ]]; do DID=0 diff --git a/buildroot/bin/pins_set b/buildroot/bin/pins_set index 860c64940f388..158c5224e6d3e 100755 --- a/buildroot/bin/pins_set +++ b/buildroot/bin/pins_set @@ -6,6 +6,6 @@ NAM=${PINPATH[1]} PIN=$2 VAL=$3 -SED=$(which gsed || which sed) +SED=$(which gsed sed | head -n1) eval "${SED} -i '/^[[:blank:]]*\(\/\/\)*[[:blank:]]*\(#define \+${PIN}\b\).*$/{s//\2 ${VAL}/;h};\${x;/./{x;q0};x;q9}' Marlin/src/pins/$DIR/pins_${NAM}.h" || (echo "ERROR: pins_set Can't find ${PIN}" >&2 && exit 9) diff --git a/buildroot/share/PlatformIO/boards/marlin_BigTree_Octopus_v1.json b/buildroot/share/PlatformIO/boards/marlin_BigTree_Octopus_v1.json index a583b5783ff22..ea2515407900f 100644 --- a/buildroot/share/PlatformIO/boards/marlin_BigTree_Octopus_v1.json +++ b/buildroot/share/PlatformIO/boards/marlin_BigTree_Octopus_v1.json @@ -4,7 +4,7 @@ "extra_flags": "-DSTM32F446xx", "f_cpu": "180000000L", "mcu": "stm32f446zet6", - "variant": "MARLIN_BIGTREE_OCTOPUS_V1_0" + "variant": "MARLIN_BIGTREE_OCTOPUS_V1" }, "connectivity": [ "can" diff --git a/buildroot/share/PlatformIO/ldscripts/STM32F103RE_SKR_E3_DIP.ld b/buildroot/share/PlatformIO/ldscripts/STM32F103RE_SKR_E3_DIP.ld deleted file mode 100644 index 248b7781cf78b..0000000000000 --- a/buildroot/share/PlatformIO/ldscripts/STM32F103RE_SKR_E3_DIP.ld +++ /dev/null @@ -1,14 +0,0 @@ -MEMORY -{ - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K - 40 - rom (rx) : ORIGIN = 0x08007000, LENGTH = 512K - 28K - 4K -} - -/* Provide memory region aliases for common.inc */ -REGION_ALIAS("REGION_TEXT", rom); -REGION_ALIAS("REGION_DATA", ram); -REGION_ALIAS("REGION_BSS", ram); -REGION_ALIAS("REGION_RODATA", rom); - -/* Let common.inc handle the real work. */ -INCLUDE common.inc diff --git a/buildroot/share/PlatformIO/ldscripts/STM32F103RC_SKR_MINI_512K.ld b/buildroot/share/PlatformIO/ldscripts/STM32F103RE_SKR_MINI_512K.ld similarity index 100% rename from buildroot/share/PlatformIO/ldscripts/STM32F103RC_SKR_MINI_512K.ld rename to buildroot/share/PlatformIO/ldscripts/STM32F103RE_SKR_MINI_512K.ld diff --git a/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py b/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py index f64f928787e7c..5a09dd3d14c43 100644 --- a/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py +++ b/buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py @@ -8,10 +8,10 @@ # Custom HEX from ELF env.AddPostAction( - join("$BUILD_DIR","${PROGNAME}.elf"), + join("$BUILD_DIR", "${PROGNAME}.elf"), env.VerboseAction(" ".join([ "$OBJCOPY", "-O ihex", "$TARGET", # TARGET=.pio/build/fysetc_STM32F1/firmware.elf - "\"" + join("$BUILD_DIR","${PROGNAME}.hex") + "\"", # Note: $BUILD_DIR is a full path + "\"" + join("$BUILD_DIR", "${PROGNAME}.hex") + "\"", # Note: $BUILD_DIR is a full path ]), "Building $TARGET")) # In-line command with arguments diff --git a/buildroot/share/PlatformIO/scripts/generic_create_variant.py b/buildroot/share/PlatformIO/scripts/generic_create_variant.py index 3290dcea192bc..7f76ef94262c2 100644 --- a/buildroot/share/PlatformIO/scripts/generic_create_variant.py +++ b/buildroot/share/PlatformIO/scripts/generic_create_variant.py @@ -28,7 +28,7 @@ else: platform_name = PackageSpec(platform_packages[0]).name -if platform_name in [ "usb-host-msc", "usb-host-msc-cdc-msc", "tool-stm32duino" ]: +if platform_name in [ "usb-host-msc", "usb-host-msc-cdc-msc", "usb-host-msc-cdc-msc-2", "usb-host-msc-cdc-msc-3", "tool-stm32duino" ]: platform_name = "framework-arduinoststm32" FRAMEWORK_DIR = platform.get_package_dir(platform_name) diff --git a/buildroot/share/PlatformIO/scripts/lerdge.py b/buildroot/share/PlatformIO/scripts/lerdge.py index 55f0a65acecf3..5c35c19e7df2f 100644 --- a/buildroot/share/PlatformIO/scripts/lerdge.py +++ b/buildroot/share/PlatformIO/scripts/lerdge.py @@ -27,11 +27,12 @@ def encrypt_file(input, output_file, file_length): output_file.write(input_file) return -# Encrypt ${PROGNAME}.bin and save it as build.firmware +# Encrypt ${PROGNAME}.bin and save it with the name given in build.encrypt def encrypt(source, target, env): - print("Encrypting to:", board.get("build.firmware")) + fwname = board.get("build.encrypt") + print("Encrypting %s to %s" % (target[0].path, fwname)) firmware = open(target[0].path, "rb") - renamed = open(target[0].dir.path + "/" + board.get("build.firmware"), "wb") + renamed = open(target[0].dir.path + "/" + fwname, "wb") length = os.path.getsize(target[0].path) encrypt_file(firmware, renamed, length) @@ -39,8 +40,8 @@ def encrypt(source, target, env): firmware.close() renamed.close() -if 'firmware' in board.get("build").keys(): - marlin.add_post_action(encrypt); +if 'encrypt' in board.get("build").keys(): + marlin.add_post_action(encrypt); else: - print("You need to define output file via board_build.firmware = 'filename' parameter") - exit(1); + print("LERDGE builds require output file via board_build.encrypt = 'filename' parameter") + exit(1); diff --git a/buildroot/share/PlatformIO/scripts/marlin.py b/buildroot/share/PlatformIO/scripts/marlin.py index d83ebceee2449..23c1b957426ca 100644 --- a/buildroot/share/PlatformIO/scripts/marlin.py +++ b/buildroot/share/PlatformIO/scripts/marlin.py @@ -7,10 +7,12 @@ from SCons.Script import DefaultEnvironment env = DefaultEnvironment() +from os.path import join + def copytree(src, dst, symlinks=False, ignore=None): for item in os.listdir(src): - s = os.path.join(src, item) - d = os.path.join(dst, item) + s = join(src, item) + d = join(dst, item) if os.path.isdir(s): shutil.copytree(s, d, symlinks, ignore) else: @@ -64,7 +66,7 @@ def encrypt_mks(source, target, env, new_name): renamed.close() def add_post_action(action): - env.AddPostAction("$BUILD_DIR/${PROGNAME}.bin", action); + env.AddPostAction(join("$BUILD_DIR", "${PROGNAME}.bin"), action); # Apply customizations for a MKS Robin def prepare_robin(address, ldname, fwname): diff --git a/buildroot/share/PlatformIO/scripts/mks_encrypt.py b/buildroot/share/PlatformIO/scripts/mks_encrypt.py index 0c622704e75cc..bd3548ab36a2f 100644 --- a/buildroot/share/PlatformIO/scripts/mks_encrypt.py +++ b/buildroot/share/PlatformIO/scripts/mks_encrypt.py @@ -2,27 +2,28 @@ # buildroot/share/PlatformIO/scripts/mks_encrypt.py # # Apply encryption and save as 'build.firmware' for these environments: -# - env:mks_robin_stm32 +# - env:mks_robin +# - env:mks_robin_e3 # - env:flsun_hispeedv1 -# - env:mks_robin_nano35_stm32 +# - env:mks_robin_nano35 # Import("env") from SCons.Script import DefaultEnvironment board = DefaultEnvironment().BoardConfig() -if 'firmware' in board.get("build").keys(): +if 'encrypt' in board.get("build").keys(): import marlin - # Encrypt ${PROGNAME}.bin and save it as build.firmware + # Encrypt ${PROGNAME}.bin and save it with the name given in build.encrypt def encrypt(source, target, env): - marlin.encrypt_mks(source, target, env, board.get("build.firmware")) + marlin.encrypt_mks(source, target, env, board.get("build.encrypt")) marlin.add_post_action(encrypt); else: import sys - print("You need to define output file via board_build.firmware = 'filename' parameter", file=sys.stderr) + print("You need to define output file via board_build.encrypt = 'filename' parameter", file=sys.stderr) env.Exit(1); diff --git a/buildroot/share/PlatformIO/scripts/openblt.py b/buildroot/share/PlatformIO/scripts/openblt.py index 01cd9c9ef2ab6..6e71ca9eb8122 100644 --- a/buildroot/share/PlatformIO/scripts/openblt.py +++ b/buildroot/share/PlatformIO/scripts/openblt.py @@ -6,10 +6,13 @@ Import("env") -env.AddPostAction( - "$BUILD_DIR/${PROGNAME}.elf", - env.VerboseAction(" ".join([ - "$OBJCOPY", "-O", "srec", - "\"$BUILD_DIR/${PROGNAME}.elf\"", "\"$BUILD_DIR/${PROGNAME}.srec\"" - ]), "Building " + join("$BUILD_DIR", "${PROGNAME}.srec")) -) +board = env.BoardConfig() +board_keys = board.get("build").keys() +if 'encrypt' in board_keys: + env.AddPostAction( + join("$BUILD_DIR", "${PROGNAME}.bin"), + env.VerboseAction(" ".join([ + "$OBJCOPY", "-O", "srec", + "\"$BUILD_DIR/${PROGNAME}.elf\"", "\"" + join("$BUILD_DIR", board.get("build.encrypt")) + "\"" + ]), "Building $TARGET") + ) diff --git a/buildroot/share/PlatformIO/scripts/stm32_bootloader.py b/buildroot/share/PlatformIO/scripts/stm32_bootloader.py index b2b5daadb604f..eb28b901d2675 100644 --- a/buildroot/share/PlatformIO/scripts/stm32_bootloader.py +++ b/buildroot/share/PlatformIO/scripts/stm32_bootloader.py @@ -1,23 +1,18 @@ # # stm32_bootloader.py # -import os,sys,shutil,marlin +import os,sys,marlin Import("env") from SCons.Script import DefaultEnvironment board = DefaultEnvironment().BoardConfig() -# -# Copy the firmware.bin file to build.firmware, no encryption -# -def noencrypt(source, target, env): - firmware = os.path.join(target[0].dir.path, board.get("build.firmware")) - shutil.copy(target[0].path, firmware) +board_keys = board.get("build").keys() # # For build.offset define LD_FLASH_OFFSET, used by ldscript.ld # -if 'offset' in board.get("build").keys(): +if 'offset' in board_keys: LD_FLASH_OFFSET = board.get("build.offset") marlin.relocate_vtab(LD_FLASH_OFFSET) @@ -35,9 +30,13 @@ def noencrypt(source, target, env): env["LINKFLAGS"][i] = "-Wl,--defsym=LD_MAX_DATA_SIZE=" + str(maximum_ram_size - 40) # -# Only copy the file if there's no encrypt +# For build.rename simply rename the firmware file. # -board_keys = board.get("build").keys() -if 'firmware' in board_keys and ('encrypt' not in board_keys or board.get("build.encrypt") == 'No'): - import marlin - marlin.add_post_action(noencrypt) +if 'rename' in board_keys: + + def rename_target(source, target, env): + firmware = os.path.join(target[0].dir.path, board.get("build.rename")) + import shutil + shutil.copy(target[0].path, firmware) + + marlin.add_post_action(rename_target) diff --git a/buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py b/buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py new file mode 100644 index 0000000000000..2be5a202efeda --- /dev/null +++ b/buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py @@ -0,0 +1,23 @@ +# +# stm32_serialbuffer.py +# +Import("env") + +# Marlin has `RX_BUFFER_SIZE` and `TX_BUFFER_SIZE` to configure the +# buffer size for receiving and transmitting data respectively. +# Stm32duino uses another set of defines for the same purpose, +# so we get the values from the Marlin configuration and set +# them in `SERIAL_RX_BUFFER_SIZE` and `SERIAL_TX_BUFFER_SIZE`. +# It is not possible to change the values at runtime, they must +# be set with build flags. +# +# The script will set the value as the default one (64 bytes) +# or the user-configured one, whichever is higher. +mf = env["MARLIN_FEATURES"] +rxBuf = str(max(64, int(mf["RX_BUFFER_SIZE"]) if "RX_BUFFER_SIZE" in mf else 0)) +txBuf = str(max(64, int(mf["TX_BUFFER_SIZE"]) if "TX_BUFFER_SIZE" in mf else 0)) + +build_flags = env.get('BUILD_FLAGS') +build_flags.append("-DSERIAL_RX_BUFFER_SIZE=" + rxBuf) +build_flags.append("-DSERIAL_TX_BUFFER_SIZE=" + txBuf) +env.Replace(BUILD_FLAGS=build_flags) diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/variant.h index ecc319f47ce06..59a7f24527ba5 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/variant.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_BTT002/variant.h @@ -264,6 +264,11 @@ extern "C" { #define PIN_SERIAL_RX PA10 #define PIN_SERIAL_TX PA9 +// Serial Pins for the MMU2 +#define ENABLE_HWSERIAL4 +#define PIN_SERIAL4_RX PC11 +#define PIN_SERIAL4_TX PC10 + #ifdef __cplusplus } // extern "C" #endif diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/PeripheralPins.c b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/PeripheralPins.c similarity index 99% rename from buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/PeripheralPins.c rename to buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/PeripheralPins.c index 333bef3db2c26..2ad0bb864cf10 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/PeripheralPins.c +++ b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/PeripheralPins.c @@ -88,7 +88,7 @@ const PinMap PinMap_ADC[] = { // {PC_4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC2_IN14 // {PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15 // {PC_5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC2_IN15 - + }; #endif @@ -214,7 +214,7 @@ const PinMap PinMap_PWM[] = { //{PF_7, TIM11, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1 //{PF_8, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1 //{PF_9, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 - + //176 pins mcu, 140 gpio //{PH_10, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1 //{PH_6, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 1, 0)}, // TIM12_CH1 @@ -393,12 +393,12 @@ const PinMap PinMap_USB_OTG_FS[] = { #endif #ifdef HAL_PCD_MODULE_ENABLED -const PinMap PinMap_USB_OTG_HS[] = { +const PinMap PinMap_USB_OTG_HS[] = { //{PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_ID //{PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_HS_VBUS {PB_14, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DM {PB_15, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DP - + /*#error "USB in HS mode isn't supported by the board" {PA_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D0 {PB_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D1 diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/PinNamesVar.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/PinNamesVar.h similarity index 100% rename from buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/PinNamesVar.h rename to buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/PinNamesVar.h diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/hal_conf_extra.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/hal_conf_extra.h similarity index 100% rename from buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/hal_conf_extra.h rename to buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/hal_conf_extra.h diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/ldscript.ld similarity index 100% rename from buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/ldscript.ld rename to buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/ldscript.ld diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/variant.cpp b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/variant.cpp similarity index 100% rename from buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/variant.cpp rename to buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/variant.cpp diff --git a/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/variant.h similarity index 100% rename from buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1_0/variant.h rename to buildroot/share/PlatformIO/variants/MARLIN_BIGTREE_OCTOPUS_V1/variant.h diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/ldscript.ld index 80bb1d2bb7923..f8eb971a6ced9 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/ldscript.ld +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/ldscript.ld @@ -102,7 +102,7 @@ SECTIONS . = ALIGN(4); } >FLASH - .ARM.extab : { + .ARM.extab : { . = ALIGN(4); *(.ARM.extab* .gnu.linkonce.armextab.*) . = ALIGN(4); @@ -146,7 +146,7 @@ SECTIONS _sidata = LOADADDR(.data); /* Initialized data sections into "RAM" Ram type memory */ - .data : + .data : { . = ALIGN(4); _sdata = .; /* create a global symbol at data start */ @@ -157,7 +157,7 @@ SECTIONS _edata = .; /* define a global symbol at data end */ } >RAM AT> FLASH - + /* Uninitialized data section into "RAM" Ram type memory */ . = ALIGN(4); .bss : @@ -185,7 +185,7 @@ SECTIONS . = ALIGN(8); } >RAM - + /* Remove information from the compiler libraries */ /DISCARD/ : diff --git a/buildroot/share/git/mfconfig b/buildroot/share/git/mfconfig index 592ecfa603ef4..70642a5d39cb3 100755 --- a/buildroot/share/git/mfconfig +++ b/buildroot/share/git/mfconfig @@ -52,7 +52,7 @@ if [[ $ACTION == "manual" ]]; then git checkout $IMPORT || exit # Reset from the latest complete state - #git reset --hard master + #git reset --hard bugfix-2.0.x cp "$MARLINREPO/Marlin/"Configuration*.h "$CDEF/" #git add . && git commit -m "Changes from Marlin ($(date '+%Y-%m-%d %H:%M'))." @@ -99,8 +99,8 @@ if [[ $ACTION == "init" ]]; then # DEBUG: Commit the original config files for comparison ((COMMIT_STEPS)) && git add . >/dev/null && git commit -m "Commit for comparison" >/dev/null - # Init Cartesian configurations to default - echo "- Initializing configs to default state..." + # Init Cartesian/SCARA/TPARA configurations to default + echo "- Initializing Cartesian/SCARA/TPARA configs to default state..." find "$CEXA" -name $BC ! -path */delta/* -print0 \ | while read -d $'\0' F ; do cp "$CDEF/$BC" "$F" ; done @@ -108,7 +108,7 @@ if [[ $ACTION == "init" ]]; then | while read -d $'\0' F ; do cp "$CDEF/$AC" "$F" ; done # DEBUG: Commit the reset for review - ((COMMIT_STEPS)) && git add . >/dev/null && git commit -m "Reset Cartesian/SCARA configs..." >/dev/null + ((COMMIT_STEPS)) && git add . >/dev/null && git commit -m "Reset Cartesian/SCARA/TPARA configs..." >/dev/null # Create base Delta configurations cp "$CDEF"/* "$CEXA/delta/generic" @@ -121,25 +121,35 @@ if [[ $ACTION == "init" ]]; then # DEBUG: Commit Generic Delta changes for review ((COMMIT_STEPS)) && git add . >/dev/null && git commit -m "Apply Generic Delta..." >/dev/null + # Reset all Delta configs to the generic version find "$CEXA/delta" -name $BC ! -path */generic/* -print0 \ | while read -d $'\0' F ; do cp "$CEXA/delta/generic/$BC" "$F" ; done find "$CEXA/delta" -name $AC ! -path */generic/* -print0 \ | while read -d $'\0' F ; do cp "$CEXA/delta/generic/$AC" "$F" ; done - # DEBUG: Commit the reset for review + # DEBUG: Commit the Delta reset for review ((COMMIT_STEPS)) && git add . >/dev/null && git commit -m "Reset Delta configs..." >/dev/null - # SCARA configurations + # Reset all SCARA configs to the default cartesian find "$CEXA/SCARA" -name $BC \ | while read -d $'\0' F ; do cp "$CDEF/$BC" "$F" ; done find "$CEXA/SCARA" -name $AC \ | while read -d $'\0' F ; do cp "$CDEF/$AC" "$F" ; done - # DEBUG: Commit the reset for review or... + # DEBUG: Commit the SCARA reset for review ((COMMIT_STEPS)) && git add . >/dev/null && git commit -m "Reset SCARA..." >/dev/null + # Reset all TPARA configs to the default cartesian + find "$CEXA/TPARA" -name $BC \ + | while read -d $'\0' F ; do cp "$CDEF/$BC" "$F" ; done + find "$CEXA/TPARA" -name $AC \ + | while read -d $'\0' F ; do cp "$CDEF/$AC" "$F" ; done + + # DEBUG: Commit the TPARA reset for review + ((COMMIT_STEPS)) && git add . >/dev/null && git commit -m "Reset TPARA..." >/dev/null + # Update the %VERSION% in the README.md file - SED=$(which gsed || which sed) + SED=$(which gsed sed | head -n1) VERS=$( echo $EXPORT | $SED 's/release-//' ) eval "${SED} -E -i~ -e 's/%VERSION%/$VERS/g' README.md" rm -f README.md~ diff --git a/buildroot/tests/BIGTREE_BTT002 b/buildroot/tests/BIGTREE_BTT002 index ba13e3eafd69a..7288c5ef52607 100755 --- a/buildroot/tests/BIGTREE_BTT002 +++ b/buildroot/tests/BIGTREE_BTT002 @@ -16,5 +16,11 @@ opt_set MOTHERBOARD BOARD_BTT_BTT002_V1_0 \ Y_DRIVER_TYPE TMC2130 exec_test $1 $2 "BigTreeTech BTT002 Default Configuration plus TMC steppers" "$3" +# +# A test with Probe Temperature Compensation enabled +# +use_example_configs Prusa/MK3S-BigTreeTech-BTT002 +exec_test $1 $2 "BigTreeTech BTT002 with Prusa MK3S and related options" "$3" + # clean up restore_configs diff --git a/buildroot/tests/BIGTREE_GTR_V1_0 b/buildroot/tests/BIGTREE_GTR_V1_0 index 24293a49325a8..58cbe4a142bae 100755 --- a/buildroot/tests/BIGTREE_GTR_V1_0 +++ b/buildroot/tests/BIGTREE_GTR_V1_0 @@ -20,11 +20,12 @@ exec_test $1 $2 "BigTreeTech GTR | 8 Extruders | Auto-Fan | Mixed TMC Drivers | restore_configs opt_set MOTHERBOARD BOARD_BTT_GTR_V1_0 SERIAL_PORT -1 \ - EXTRUDERS 6 TEMP_SENSOR_1 1 TEMP_SENSOR_2 1 TEMP_SENSOR_3 1 TEMP_SENSOR_4 1 TEMP_SENSOR_5 1 \ - NUM_Z_STEPPER_DRIVERS 3 \ - DEFAULT_Kp_LIST '{ 22.2, 20.0, 21.0, 19.0, 18.0, 17.0 }' DEFAULT_Ki_LIST '{ 1.08 }' DEFAULT_Kd_LIST '{ 114.0, 112.0, 110.0, 108.0 }' -opt_enable TOOLCHANGE_FILAMENT_SWAP TOOLCHANGE_MIGRATION_FEATURE TOOLCHANGE_FS_INIT_BEFORE_SWAP TOOLCHANGE_FS_PRIME_FIRST_USED PID_PARAMS_PER_HOTEND -exec_test $1 $2 "BigTreeTech GTR | 6 Extruders | Triple Z" "$3" + EXTRUDERS 5 TEMP_SENSOR_1 1 TEMP_SENSOR_2 1 TEMP_SENSOR_3 1 TEMP_SENSOR_4 1 \ + NUM_Z_STEPPER_DRIVERS 4 \ + DEFAULT_Kp_LIST '{ 22.2, 20.0, 21.0, 19.0, 18.0 }' DEFAULT_Ki_LIST '{ 1.08 }' DEFAULT_Kd_LIST '{ 114.0, 112.0, 110.0, 108.0 }' +opt_enable TOOLCHANGE_FILAMENT_SWAP TOOLCHANGE_MIGRATION_FEATURE TOOLCHANGE_FS_INIT_BEFORE_SWAP TOOLCHANGE_FS_PRIME_FIRST_USED \ + PID_PARAMS_PER_HOTEND Z_MULTI_ENDSTOPS +exec_test $1 $2 "BigTreeTech GTR | 6 Extruders | Quad Z + Endstops" "$3" restore_configs opt_set MOTHERBOARD BOARD_BTT_GTR_V1_0 SERIAL_PORT -1 \ diff --git a/buildroot/tests/DUE b/buildroot/tests/DUE index d1601edf5ab70..9eb2157428e46 100755 --- a/buildroot/tests/DUE +++ b/buildroot/tests/DUE @@ -18,13 +18,13 @@ opt_enable S_CURVE_ACCELERATION EEPROM_SETTINGS GCODE_MACROS \ ASSISTED_TRAMMING ASSISTED_TRAMMING_WIZARD REPORT_TRAMMING_MM ASSISTED_TRAMMING_WAIT_POSITION \ EEPROM_SETTINGS SDSUPPORT BINARY_FILE_TRANSFER \ BLINKM PCA9533 PCA9632 RGB_LED RGB_LED_R_PIN RGB_LED_G_PIN RGB_LED_B_PIN LED_CONTROL_MENU \ - NEOPIXEL_LED CASE_LIGHT_ENABLE CASE_LIGHT_USE_NEOPIXEL CASE_LIGHT_USE_RGB_LED CASE_LIGHT_MENU \ + NEOPIXEL_LED NEOPIXEL_PIN CASE_LIGHT_ENABLE CASE_LIGHT_USE_NEOPIXEL CASE_LIGHT_USE_RGB_LED CASE_LIGHT_MENU \ NOZZLE_PARK_FEATURE ADVANCED_PAUSE_FEATURE FILAMENT_RUNOUT_DISTANCE_MM FILAMENT_RUNOUT_SENSOR \ AUTO_BED_LEVELING_BILINEAR Z_MIN_PROBE_REPEATABILITY_TEST DEBUG_LEVELING_FEATURE \ SKEW_CORRECTION SKEW_CORRECTION_FOR_Z SKEW_CORRECTION_GCODE CALIBRATION_GCODE \ BACKLASH_COMPENSATION BACKLASH_GCODE BAUD_RATE_GCODE BEZIER_CURVE_SUPPORT \ FWRETRACT ARC_SUPPORT ARC_P_CIRCLES CNC_WORKSPACE_PLANES CNC_COORDINATE_SYSTEMS \ - PSU_CONTROL AUTO_POWER_CONTROL \ + PSU_CONTROL AUTO_POWER_CONTROL E_DUAL_STEPPER_DRIVERS \ PIDTEMPBED SLOW_PWM_HEATERS THERMAL_PROTECTION_CHAMBER \ PINS_DEBUGGING MAX7219_DEBUG M114_DETAIL \ EXTENSIBLE_UI @@ -38,10 +38,9 @@ restore_configs opt_set MOTHERBOARD BOARD_RADDS NUM_Z_STEPPER_DRIVERS 3 opt_enable USE_XMAX_PLUG USE_YMAX_PLUG ENDSTOPPULLUPS BLTOUCH AUTO_BED_LEVELING_BILINEAR \ Z_STEPPER_AUTO_ALIGN Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS Z_SAFE_HOMING - #TOUCH_UI_FTDI_EVE LCD_ALEPHOBJECTS_CLCD_UI OTHER_PIN_LAYOUT pins_set ramps/RAMPS X_MAX_PIN -1 pins_set ramps/RAMPS Y_MAX_PIN -1 -exec_test $1 $2 "RADDS with ABL (Bilinear), Triple Z Axis, Z_STEPPER_AUTO_ALIGN" "$3" +exec_test $1 $2 "RADDS with ABL (Bilinear), Triple Z Axis, Z_STEPPER_AUTO_ALIGN, E_DUAL_STEPPER_DRIVERS" "$3" # # Test SWITCHING_EXTRUDER diff --git a/buildroot/tests/LPC1768 b/buildroot/tests/LPC1768 index 92fda54483467..b4e489d310182 100755 --- a/buildroot/tests/LPC1768 +++ b/buildroot/tests/LPC1768 @@ -14,8 +14,10 @@ set -e #exec_test $1 $2 "Default Configuration" "$3" restore_configs -opt_set MOTHERBOARD BOARD_RAMPS_14_RE_ARM_EFB NEOPIXEL_PIN P1_16 SERIAL_PORT_3 3 -opt_enable VIKI2 SDSUPPORT SDCARD_READONLY SERIAL_PORT_2 NEOPIXEL_LED +opt_set MOTHERBOARD BOARD_RAMPS_14_RE_ARM_EFB SERIAL_PORT_3 3 \ + NEOPIXEL_TYPE NEO_GRB RGB_LED_R_PIN P2_12 RGB_LED_G_PIN P1_23 RGB_LED_B_PIN P1_22 RGB_LED_W_PIN P1_24 +opt_enable FYSETC_MINI_12864_2_1 SDSUPPORT SDCARD_READONLY SERIAL_PORT_2 RGBW_LED E_DUAL_STEPPER_DRIVERS \ + NEOPIXEL_LED NEOPIXEL_IS_SEQUENTIAL NEOPIXEL_STARTUP_TEST NEOPIXEL_BKGD_INDEX_FIRST NEOPIXEL_BKGD_INDEX_LAST NEOPIXEL_BKGD_COLOR NEOPIXEL_BKGD_ALWAYS_ON exec_test $1 $2 "ReARM EFB VIKI2, SDSUPPORT, 2 Serial ports (USB CDC + UART0), NeoPixel" "$3" #restore_configs diff --git a/buildroot/tests/STM32F103RC_btt_USB_stm32 b/buildroot/tests/STM32F103RC_btt_USB_maple similarity index 71% rename from buildroot/tests/STM32F103RC_btt_USB_stm32 rename to buildroot/tests/STM32F103RC_btt_USB_maple index 8381de0ea6e40..eeb460911acb2 100755 --- a/buildroot/tests/STM32F103RC_btt_USB_stm32 +++ b/buildroot/tests/STM32F103RC_btt_USB_maple @@ -1,6 +1,6 @@ #!/usr/bin/env bash # -# Build tests for STM32F103RC BigTreeTech (SKR Mini v1.1) +# Build tests for STM32F103RC BigTreeTech (SKR Mini v1.1) with LibMaple STM32F1 HAL # # exit on first failure @@ -10,7 +10,7 @@ set -e # Build with the default configurations # restore_configs -opt_set MOTHERBOARD BOARD_BTT_SKR_MINI_V1_1 SERIAL_PORT 1 SERIAL_PORT_2 -1 +opt_set MOTHERBOARD BOARD_BTT_SKR_MINI_V1_1 SERIAL_PORT 1 SERIAL_PORT_2 -1 BAUDRATE_2 115200 exec_test $1 $2 "BigTreeTech SKR Mini v1.1 - Basic Configuration" "$3" # clean up diff --git a/buildroot/tests/STM32F103RC_btt_stm32 b/buildroot/tests/STM32F103RC_btt_maple similarity index 84% rename from buildroot/tests/STM32F103RC_btt_stm32 rename to buildroot/tests/STM32F103RC_btt_maple index e76060aee82fc..e74e5902132ca 100755 --- a/buildroot/tests/STM32F103RC_btt_stm32 +++ b/buildroot/tests/STM32F103RC_btt_maple @@ -1,6 +1,6 @@ #!/usr/bin/env bash # -# Build tests for STM32F103RC BigTreeTech (SKR Mini E3) +# Build tests for STM32F103RC BigTreeTech (SKR Mini E3) with LibMaple STM32F1 HAL # # exit on first failure diff --git a/buildroot/tests/mega1280 b/buildroot/tests/mega1280 index 8b16b1dbc822b..d8cefbaf8145c 100755 --- a/buildroot/tests/mega1280 +++ b/buildroot/tests/mega1280 @@ -47,7 +47,9 @@ exec_test $1 $2 "RAMPS | DELTA | RRD LCD | DELTA_AUTO_CALIBRATION | DELTA_CALIBR # # Delta Config (generic) + ABL bilinear + BLTOUCH use_example_configs delta/generic -opt_set LCD_LANGUAGE cz +opt_set LCD_LANGUAGE cz \ + Z_MIN_PROBE_ENDSTOP_INVERTING false \ + Z_MIN_ENDSTOP_INVERTING false opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER DELTA_CALIBRATION_MENU AUTO_BED_LEVELING_BILINEAR BLTOUCH exec_test $1 $2 "DELTA | RRD LCD | ABL Bilinear | BLTOUCH" "$3" diff --git a/buildroot/tests/mega2560 b/buildroot/tests/mega2560 index 22832920ee5c2..09323889694b0 100755 --- a/buildroot/tests/mega2560 +++ b/buildroot/tests/mega2560 @@ -20,8 +20,8 @@ opt_set MOTHERBOARD BOARD_AZTEEG_X3_PRO LCD_LANGUAGE fr SAVED_POSITIONS 4 \ EXTRUDERS 5 TEMP_SENSOR_1 1 TEMP_SENSOR_2 5 TEMP_SENSOR_3 20 TEMP_SENSOR_4 1000 TEMP_SENSOR_BED 1 opt_enable AUTO_BED_LEVELING_UBL RESTORE_LEVELING_AFTER_G28 DEBUG_LEVELING_FEATURE G26_MESH_VALIDATION ENABLE_LEVELING_FADE_HEIGHT SKEW_CORRECTION \ REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER LIGHTWEIGHT_UI STATUS_MESSAGE_SCROLLING SHOW_CUSTOM_BOOTSCREEN BOOT_MARLIN_LOGO_SMALL \ - SDSUPPORT SDCARD_SORT_ALPHA USB_FLASH_DRIVE_SUPPORT AUTO_REPORT_SD_STATUS SCROLL_LONG_FILENAMES CANCEL_OBJECTS SOUND_MENU_ITEM \ - EEPROM_SETTINGS EEPROM_CHITCHAT GCODE_MACROS CUSTOM_MENU_MAIN FREEZE_FEATURE \ + SDSUPPORT SDCARD_SORT_ALPHA USB_FLASH_DRIVE_SUPPORT AUTO_REPORT_SD_STATUS SCROLL_LONG_FILENAMES MEDIA_MENU_AT_TOP \ + EEPROM_SETTINGS EEPROM_CHITCHAT GCODE_MACROS CUSTOM_MENU_MAIN FREEZE_FEATURE CANCEL_OBJECTS SOUND_MENU_ITEM \ MULTI_NOZZLE_DUPLICATION CLASSIC_JERK LIN_ADVANCE EXTRA_LIN_ADVANCE_K QUICK_HOME \ LCD_SET_PROGRESS_MANUALLY PRINT_PROGRESS_SHOW_DECIMALS SHOW_REMAINING_TIME \ BABYSTEPPING BABYSTEP_XY NANODLP_Z_SYNC I2C_POSITION_ENCODERS M114_DETAIL @@ -68,7 +68,8 @@ exec_test $1 $2 "Multiple runout sensors (x5) | Distinct runout states" "$3" # restore_configs opt_set MOTHERBOARD BOARD_AZTEEG_X3_PRO MIXING_STEPPERS 5 LCD_LANGUAGE ru \ - NUM_RUNOUT_SENSORS E_STEPPERS FIL_RUNOUT2_PIN 16 FIL_RUNOUT3_PIN 17 FIL_RUNOUT4_PIN 4 FIL_RUNOUT5_PIN 5 + NUM_RUNOUT_SENSORS E_STEPPERS REDUNDANT_PART_COOLING_FAN 1 \ + FIL_RUNOUT2_PIN 16 FIL_RUNOUT3_PIN 17 FIL_RUNOUT4_PIN 4 FIL_RUNOUT5_PIN 5 opt_enable MIXING_EXTRUDER GRADIENT_MIX GRADIENT_VTOOL CR10_STOCKDISPLAY \ USE_CONTROLLER_FAN CONTROLLER_FAN_EDITABLE CONTROLLER_FAN_IGNORE_Z \ FILAMENT_RUNOUT_SENSOR ADVANCED_PAUSE_FEATURE NOZZLE_PARK_FEATURE @@ -171,10 +172,12 @@ exec_test $1 $2 "Azteeg X3 | Mixing Extruder (x5) | Gradient Mix | Greek" "$3" # Test Laser features with 12864 LCD # restore_configs -opt_set MOTHERBOARD BOARD_RAMPS_14_EFB LCD_LANGUAGE en TEMP_SENSOR_COOLER 1 EXTRUDERS 0 TEMP_SENSOR_1 0 SERIAL_PORT_2 2 \ +opt_set MOTHERBOARD BOARD_RAMPS_14_EFB EXTRUDERS 0 LCD_LANGUAGE en TEMP_SENSOR_COOLER 1 TEMP_SENSOR_1 0 SERIAL_PORT_2 2 \ DEFAULT_AXIS_STEPS_PER_UNIT '{ 80, 80, 400 }' \ DEFAULT_MAX_FEEDRATE '{ 300, 300, 5 }' \ - DEFAULT_MAX_ACCELERATION '{ 3000, 3000, 100 }' + DEFAULT_MAX_ACCELERATION '{ 3000, 3000, 100 }' \ + MANUAL_FEEDRATE '{ 50*60, 50*60, 4*60 }' \ + AXIS_RELATIVE_MODES '{ false, false, false }' opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER SDSUPPORT EEPROM_SETTINGS EEPROM_BOOT_SILENT EEPROM_AUTO_INIT \ LASER_FEATURE AIR_EVACUATION AIR_EVACUATION_PIN AIR_ASSIST AIR_ASSIST_PIN LASER_COOLANT_FLOW_METER MEATPACK_ON_SERIAL_PORT_1 @@ -184,12 +187,14 @@ exec_test $1 $2 "REPRAP MEGA2560 RAMPS | Laser Feature | Air Evacuation | Air As # Test Laser features with 44780 LCD # restore_configs -opt_set MOTHERBOARD BOARD_RAMPS_14_EFB LCD_LANGUAGE en TEMP_SENSOR_COOLER 1 EXTRUDERS 0 TEMP_SENSOR_1 0 \ +opt_set MOTHERBOARD BOARD_RAMPS_14_EFB EXTRUDERS 0 LCD_LANGUAGE en TEMP_SENSOR_COOLER 1 TEMP_SENSOR_1 0 \ DEFAULT_AXIS_STEPS_PER_UNIT '{ 80, 80, 400 }' \ DEFAULT_MAX_FEEDRATE '{ 300, 300, 5 }' \ - DEFAULT_MAX_ACCELERATION '{ 3000, 3000, 100 }' + DEFAULT_MAX_ACCELERATION '{ 3000, 3000, 100 }' \ + MANUAL_FEEDRATE '{ 50*60, 50*60, 4*60 }' \ + AXIS_RELATIVE_MODES '{ false, false, false }' opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT EEPROM_SETTINGS EEPROM_BOOT_SILENT EEPROM_AUTO_INIT \ - LASER_FEATURE AIR_EVACUATION AIR_EVACUATION_PIN AIR_ASSIST AIR_ASSIST_PIN LASER_COOLANT_FLOW_METER + LASER_FEATURE AIR_EVACUATION AIR_EVACUATION_PIN AIR_ASSIST AIR_ASSIST_PIN LASER_COOLANT_FLOW_METER I2C_AMMETER exec_test $1 $2 "REPRAP MEGA2560 RAMPS | Laser Feature | Air Evacuation | Air Assist | Cooler | Flowmeter | 44780 LCD " "$3" diff --git a/buildroot/tests/mks_robin b/buildroot/tests/mks_robin index 652147f867078..e250dceca255f 100755 --- a/buildroot/tests/mks_robin +++ b/buildroot/tests/mks_robin @@ -1,22 +1,13 @@ #!/usr/bin/env bash # -# Build tests for MKS Robin -# (STM32F1 genericSTM32F103ZE) +# Build tests for MKS Robin (HAL/STM32) # # exit on first failure set -e use_example_configs Mks/Robin -exec_test $1 $2 "MKS Robin config (FSMC Color UI)" "$3" - -# -# MKS Robin LVGL FSMC -# -use_example_configs Mks/Robin -opt_disable TFT_CLASSIC_UI TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 -opt_enable TFT_LVGL_UI TFT_RES_480x320 -exec_test $1 $2 "MKS Robin nano v1.2 LVGL FSMC" "$3" +exec_test $1 $2 "MKS Robin base configuration" "$3" # cleanup restore_configs diff --git a/buildroot/tests/mks_robin_maple b/buildroot/tests/mks_robin_maple new file mode 100755 index 0000000000000..fcb51183076e6 --- /dev/null +++ b/buildroot/tests/mks_robin_maple @@ -0,0 +1,22 @@ +#!/usr/bin/env bash +# +# Build tests for MKS Robin with LibMaple STM32F1 HAL +# (STM32F1 genericSTM32F103ZE) +# + +# exit on first failure +set -e + +use_example_configs Mks/Robin +exec_test $1 $2 "MKS Robin config (FSMC Color UI)" "$3" + +# +# MKS Robin LVGL FSMC +# +use_example_configs Mks/Robin +opt_disable TFT_CLASSIC_UI TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 +opt_enable TFT_LVGL_UI TFT_RES_480x320 +exec_test $1 $2 "MKS Robin nano v1.2 LVGL FSMC" "$3" + +# cleanup +restore_configs diff --git a/buildroot/tests/mks_robin_nano35 b/buildroot/tests/mks_robin_nano35 index c54cd36655f99..08917446927ea 100755 --- a/buildroot/tests/mks_robin_nano35 +++ b/buildroot/tests/mks_robin_nano35 @@ -24,15 +24,24 @@ opt_disable TFT_INTERFACE_FSMC opt_enable TFT_INTERFACE_SPI exec_test $1 $2 "MKS Robin v2 nano Emulated DOGM SPI" "$3" +# +# MKS Robin nano v1.2 LVGL FSMC +# +# use_example_configs Mks/Robin +# opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO +# opt_disable TFT_CLASSIC_UI TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 +# opt_enable TFT_LVGL_UI TFT_RES_480x320 +# exec_test $1 $2 "MKS Robin nano v1.2 LVGL FSMC" "$3" + # # MKS Robin v2 nano LVGL SPI # (Robin v2 nano has no FSMC interface) # -use_example_configs Mks/Robin -opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 -opt_disable TFT_INTERFACE_FSMC TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 SERIAL_PORT_2 -opt_enable TFT_INTERFACE_SPI TFT_LVGL_UI TFT_RES_480x320 MKS_WIFI_MODULE -exec_test $1 $2 "MKS Robin v2 nano LVGL SPI w/ WiFi" "$3" +# use_example_configs Mks/Robin +# opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 +# opt_disable TFT_INTERFACE_FSMC TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 +# opt_enable TFT_INTERFACE_SPI TFT_LVGL_UI TFT_RES_480x320 +# exec_test $1 $2 "MKS Robin v2 nano LVGL SPI" "$3" # # MKS Robin v2 nano New Color UI 480x320 SPI @@ -42,27 +51,17 @@ use_example_configs Mks/Robin opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 opt_disable TFT_INTERFACE_FSMC TFT_RES_320x240 opt_enable TFT_INTERFACE_SPI TFT_RES_480x320 -opt_enable BINARY_FILE_TRANSFER -exec_test $1 $2 "MKS Robin v2 nano New Color UI 480x320 SPI + BINARY_FILE_TRANSFER" "$3" +exec_test $1 $2 "MKS Robin v2 nano New Color UI 480x320 SPI" "$3" # # MKS Robin v2 nano LVGL SPI + TMC # (Robin v2 nano has no FSMC interface) # -use_example_configs Mks/Robin -opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 X_DRIVER_TYPE TMC2209 Y_DRIVER_TYPE TMC2209 -opt_disable TFT_INTERFACE_FSMC TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 -opt_enable TFT_INTERFACE_SPI TFT_LVGL_UI TFT_RES_480x320 -exec_test $1 $2 "MKS Robin v2 nano LVGL SPI + TMC" "$3" - -# -# MKS Robin v2 nano New Color UI 480x320 SPI Without Touch Screen -# -use_example_configs Mks/Robin -opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 -opt_disable TFT_INTERFACE_FSMC TFT_RES_320x240 TOUCH_SCREEN -opt_enable TFT_INTERFACE_SPI TFT_RES_480x320 TFT_COLOR_UI -exec_test $1 $2 "MKS Robin v2 nano New Color UI 480x320 SPI without TOUCH_SCREEN" "$3" +# use_example_configs Mks/Robin +# opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 X_DRIVER_TYPE TMC2209 Y_DRIVER_TYPE TMC2209 +# opt_disable TFT_INTERFACE_FSMC TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 +# opt_enable TFT_INTERFACE_SPI TFT_LVGL_UI TFT_RES_480x320 +# exec_test $1 $2 "MKS Robin v2 nano LVGL SPI + TMC" "$3" # cleanup restore_configs diff --git a/buildroot/tests/mks_robin_nano35_maple b/buildroot/tests/mks_robin_nano35_maple new file mode 100755 index 0000000000000..f1549a8103dec --- /dev/null +++ b/buildroot/tests/mks_robin_nano35_maple @@ -0,0 +1,68 @@ +#!/usr/bin/env bash +# +# Build tests for MKS Robin nano with LibMaple STM32F1 HAL +# (STM32F1 genericSTM32F103VE) +# + +# exit on first failure +set -e + +# +# MKS Robin nano v1.2 Emulated DOGM FSMC +# +use_example_configs Mks/Robin +opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO +exec_test $1 $2 "MKS Robin nano v1.2 Emulated DOGM FSMC" "$3" + +# +# MKS Robin v2 nano Emulated DOGM SPI +# (Robin v2 nano has no FSMC interface) +# +use_example_configs Mks/Robin +opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 +opt_disable TFT_INTERFACE_FSMC +opt_enable TFT_INTERFACE_SPI +exec_test $1 $2 "MKS Robin v2 nano Emulated DOGM SPI" "$3" + +# +# MKS Robin v2 nano LVGL SPI +# (Robin v2 nano has no FSMC interface) +# +use_example_configs Mks/Robin +opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 +opt_disable TFT_INTERFACE_FSMC TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 SERIAL_PORT_2 +opt_enable TFT_INTERFACE_SPI TFT_LVGL_UI TFT_RES_480x320 MKS_WIFI_MODULE +exec_test $1 $2 "MKS Robin v2 nano LVGL SPI w/ WiFi" "$3" + +# +# MKS Robin v2 nano New Color UI 480x320 SPI +# (Robin v2 nano has no FSMC interface) +# +use_example_configs Mks/Robin +opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 +opt_disable TFT_INTERFACE_FSMC TFT_RES_320x240 +opt_enable TFT_INTERFACE_SPI TFT_RES_480x320 +opt_enable BINARY_FILE_TRANSFER +exec_test $1 $2 "MKS Robin v2 nano New Color UI 480x320 SPI + BINARY_FILE_TRANSFER" "$3" + +# +# MKS Robin v2 nano LVGL SPI + TMC +# (Robin v2 nano has no FSMC interface) +# +use_example_configs Mks/Robin +opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 X_DRIVER_TYPE TMC2209 Y_DRIVER_TYPE TMC2209 +opt_disable TFT_INTERFACE_FSMC TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 +opt_enable TFT_INTERFACE_SPI TFT_LVGL_UI TFT_RES_480x320 +exec_test $1 $2 "MKS Robin v2 nano LVGL SPI + TMC" "$3" + +# +# MKS Robin v2 nano New Color UI 480x320 SPI Without Touch Screen +# +use_example_configs Mks/Robin +opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 +opt_disable TFT_INTERFACE_FSMC TFT_RES_320x240 TOUCH_SCREEN +opt_enable TFT_INTERFACE_SPI TFT_RES_480x320 TFT_COLOR_UI +exec_test $1 $2 "MKS Robin v2 nano New Color UI 480x320 SPI without TOUCH_SCREEN" "$3" + +# cleanup +restore_configs diff --git a/buildroot/tests/mks_robin_nano35_stm32 b/buildroot/tests/mks_robin_nano35_stm32 deleted file mode 100755 index 08917446927ea..0000000000000 --- a/buildroot/tests/mks_robin_nano35_stm32 +++ /dev/null @@ -1,67 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for MKS Robin nano -# (STM32F1 genericSTM32F103VE) -# - -# exit on first failure -set -e - -# -# MKS Robin nano v1.2 Emulated DOGM FSMC -# -use_example_configs Mks/Robin -opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO -exec_test $1 $2 "MKS Robin nano v1.2 Emulated DOGM FSMC" "$3" - -# -# MKS Robin v2 nano Emulated DOGM SPI -# (Robin v2 nano has no FSMC interface) -# -use_example_configs Mks/Robin -opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 -opt_disable TFT_INTERFACE_FSMC -opt_enable TFT_INTERFACE_SPI -exec_test $1 $2 "MKS Robin v2 nano Emulated DOGM SPI" "$3" - -# -# MKS Robin nano v1.2 LVGL FSMC -# -# use_example_configs Mks/Robin -# opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO -# opt_disable TFT_CLASSIC_UI TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 -# opt_enable TFT_LVGL_UI TFT_RES_480x320 -# exec_test $1 $2 "MKS Robin nano v1.2 LVGL FSMC" "$3" - -# -# MKS Robin v2 nano LVGL SPI -# (Robin v2 nano has no FSMC interface) -# -# use_example_configs Mks/Robin -# opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 -# opt_disable TFT_INTERFACE_FSMC TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 -# opt_enable TFT_INTERFACE_SPI TFT_LVGL_UI TFT_RES_480x320 -# exec_test $1 $2 "MKS Robin v2 nano LVGL SPI" "$3" - -# -# MKS Robin v2 nano New Color UI 480x320 SPI -# (Robin v2 nano has no FSMC interface) -# -use_example_configs Mks/Robin -opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 -opt_disable TFT_INTERFACE_FSMC TFT_RES_320x240 -opt_enable TFT_INTERFACE_SPI TFT_RES_480x320 -exec_test $1 $2 "MKS Robin v2 nano New Color UI 480x320 SPI" "$3" - -# -# MKS Robin v2 nano LVGL SPI + TMC -# (Robin v2 nano has no FSMC interface) -# -# use_example_configs Mks/Robin -# opt_set MOTHERBOARD BOARD_MKS_ROBIN_NANO_V2 X_DRIVER_TYPE TMC2209 Y_DRIVER_TYPE TMC2209 -# opt_disable TFT_INTERFACE_FSMC TFT_COLOR_UI TOUCH_SCREEN TFT_RES_320x240 -# opt_enable TFT_INTERFACE_SPI TFT_LVGL_UI TFT_RES_480x320 -# exec_test $1 $2 "MKS Robin v2 nano LVGL SPI + TMC" "$3" - -# cleanup -restore_configs diff --git a/buildroot/tests/mks_robin_stm32 b/buildroot/tests/mks_robin_stm32 deleted file mode 100755 index e250dceca255f..0000000000000 --- a/buildroot/tests/mks_robin_stm32 +++ /dev/null @@ -1,13 +0,0 @@ -#!/usr/bin/env bash -# -# Build tests for MKS Robin (HAL/STM32) -# - -# exit on first failure -set -e - -use_example_configs Mks/Robin -exec_test $1 $2 "MKS Robin base configuration" "$3" - -# cleanup -restore_configs diff --git a/buildroot/tests/rambo b/buildroot/tests/rambo index 9869b96b34785..27c277865bb7d 100755 --- a/buildroot/tests/rambo +++ b/buildroot/tests/rambo @@ -22,7 +22,7 @@ opt_enable USE_ZMAX_PLUG REPRAP_DISCOUNT_SMART_CONTROLLER LCD_PROGRESS_BAR LCD_P PREHEAT_BEFORE_PROBING PROBING_HEATERS_OFF PROBING_FANS_OFF PROBING_STEPPERS_OFF WAIT_FOR_BED_HEATER \ EEPROM_SETTINGS SDSUPPORT SD_REPRINT_LAST_SELECTED_FILE BINARY_FILE_TRANSFER \ BLINKM PCA9533 PCA9632 RGB_LED RGB_LED_R_PIN RGB_LED_G_PIN RGB_LED_B_PIN LED_CONTROL_MENU \ - NEOPIXEL_LED CASE_LIGHT_ENABLE CASE_LIGHT_USE_NEOPIXEL CASE_LIGHT_MENU \ + NEOPIXEL_LED NEOPIXEL_PIN CASE_LIGHT_ENABLE CASE_LIGHT_USE_NEOPIXEL CASE_LIGHT_MENU \ PID_PARAMS_PER_HOTEND PID_AUTOTUNE_MENU PID_EDIT_MENU LCD_SHOW_E_TOTAL \ PRINTCOUNTER SERVICE_NAME_1 SERVICE_INTERVAL_1 LEVEL_BED_CORNERS LEVEL_CENTER_TOO \ NOZZLE_PARK_FEATURE FILAMENT_RUNOUT_SENSOR FILAMENT_RUNOUT_DISTANCE_MM \ @@ -48,6 +48,7 @@ opt_set MOTHERBOARD BOARD_RAMBO \ DEFAULT_AXIS_STEPS_PER_UNIT '{ 80, 80, 4000 }' \ DEFAULT_MAX_FEEDRATE '{ 300, 300, 5 }' \ DEFAULT_MAX_ACCELERATION '{ 3000, 3000, 100 }' \ + MANUAL_FEEDRATE '{ 50*60, 50*60, 4*60 }' \ AXIS_RELATIVE_MODES '{ false, false, false }' \ LEVEL_CORNERS_LEVELING_ORDER '{ LF, RF }' opt_enable USE_XMAX_PLUG USE_YMAX_PLUG USE_ZMAX_PLUG \ @@ -66,6 +67,7 @@ opt_set MOTHERBOARD BOARD_RAMBO EXTRUDERS 0 TEMP_SENSOR_BED 1 \ DEFAULT_AXIS_STEPS_PER_UNIT '{ 80, 80, 4000 }' \ DEFAULT_MAX_FEEDRATE '{ 300, 300, 5 }' \ DEFAULT_MAX_ACCELERATION '{ 3000, 3000, 100 }' \ + MANUAL_FEEDRATE '{ 50*60, 50*60, 4*60 }' \ AXIS_RELATIVE_MODES '{ false, false, false }' opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER exec_test $1 $2 "Rambo heated bed only" "$3" @@ -112,10 +114,10 @@ opt_set MOTHERBOARD BOARD_RAMBO \ FAN_MIN_PWM 50 FAN_KICKSTART_TIME 100 \ XY_FREQUENCY_LIMIT 15 opt_enable COREYX USE_XMAX_PLUG MIXING_EXTRUDER GRADIENT_MIX \ - BABYSTEPPING BABYSTEP_DISPLAY_TOTAL FILAMENT_LCD_DISPLAY \ + BABYSTEPPING BABYSTEP_DISPLAY_TOTAL FILAMENT_LCD_DISPLAY FILAMENT_WIDTH_SENSOR \ REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER MENU_ADDAUTOSTART SDSUPPORT SDCARD_SORT_ALPHA \ ENDSTOP_NOISE_THRESHOLD FAN_SOFT_PWM \ - FIX_MOUNTED_PROBE AUTO_BED_LEVELING_LINEAR DEBUG_LEVELING_FEATURE FILAMENT_WIDTH_SENSOR PROBE_OFFSET_WIZARD \ + FIX_MOUNTED_PROBE PROBING_ESTEPPERS_OFF AUTO_BED_LEVELING_LINEAR DEBUG_LEVELING_FEATURE PROBE_OFFSET_WIZARD \ Z_SAFE_HOMING SHOW_TEMP_ADC_VALUES HOME_Y_BEFORE_X EMERGENCY_PARSER \ SD_ABORT_ON_ENDSTOP_HIT HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT ADVANCED_OK M114_DETAIL \ VOLUMETRIC_DEFAULT_ON NO_WORKSPACE_OFFSETS EXTRA_FAN_SPEED FWRETRACT \ diff --git a/config/README.md b/config/README.md index 940604b921edc..8fb23a946e80f 100644 --- a/config/README.md +++ b/config/README.md @@ -1,3 +1,3 @@ # Where have all the configurations gone? -## https://github.com/MarlinFirmware/Configurations/archive/release-2.0.8.1.zip +## https://github.com/MarlinFirmware/Configurations/archive/release-2.0.9.1.zip diff --git a/ini/esp32.ini b/ini/esp32.ini index 1aee88f69233b..fcfa8296087a2 100644 --- a/ini/esp32.ini +++ b/ini/esp32.ini @@ -24,6 +24,6 @@ monitor_speed = 250000 #board_build.flash_mode = qio [env:FYSETC_E4] -platform = espressif32@1.11.2 +platform = espressif32@2.1.0 extends = env:esp32 board_build.partitions = default_16MB.csv diff --git a/ini/features.ini b/ini/features.ini index 2b69daa88aebf..a1e96884474fd 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -30,12 +30,13 @@ HAS_L64XX = Arduino-L6470@0.8.0 NEOPIXEL_LED = adafruit/Adafruit NeoPixel@~1.8.0 src_filter=+ TEMP_.+_IS_MAX31865 = Adafruit MAX31865 library@~1.1.0 +I2C_AMMETER = peterus/INA226Lib@1.1.2 USES_LIQUIDCRYSTAL = fmalpartida/LiquidCrystal@1.5.0 USES_LIQUIDCRYSTAL_I2C = marcoschwartz/LiquidCrystal_I2C@1.1.4 USES_LIQUIDTWI2 = LiquidTWI2@1.2.7 HAS_WIRED_LCD = src_filter=+ HAS_MARLINUI_HD44780 = src_filter=+ -HAS_MARLINUI_U8GLIB = U8glib-HAL@~0.4.4 +HAS_MARLINUI_U8GLIB = U8glib-HAL@~0.4.5 src_filter=+ HAS_(FSMC|SPI|LTDC)_TFT = src_filter=+ + + HAS_FSMC_TFT = src_filter=+ + @@ -61,7 +62,7 @@ HAS_MENU_DELTA_CALIBRATE = src_filter=+ LCD_INFO_MENU = src_filter=+ HAS_MENU_JOB_RECOVERY = src_filter=+ -HAS_MULTI_LANGUAGE = src_filter=+ +HAS_MULTI_LANGUAGE = src_filter=+ + HAS_MENU_LED = src_filter=+ HAS_MENU_MEDIA = src_filter=+ HAS_MENU_MIXER = src_filter=+ @@ -165,7 +166,7 @@ HAS_USER_THERMISTORS = src_filter=+ SD_ABORT_ON_ENDSTOP_HIT = src_filter=+ BAUD_RATE_GCODE = src_filter=+ HAS_SMART_EFF_MOD = src_filter=+ -COOLANT_CONTROL = src_filter=+ +COOLANT_CONTROL|AIR_ASSIST = src_filter=+ AIR_EVACUATION = src_filter=+ HAS_SOFTWARE_ENDSTOPS = src_filter=+ HAS_DUPLICATION_MODE = src_filter=+ @@ -186,7 +187,9 @@ AUTO_REPORT_POSITION = src_filter=+ REPETIER_GCODE_M360 = src_filter=+ HAS_GCODE_M876 = src_filter=+ HAS_RESUME_CONTINUE = src_filter=+ +HAS_STATUS_MESSAGE = src_filter=+ HAS_LCD_CONTRAST = src_filter=+ +HAS_BUZZER = src_filter=+ LCD_SET_PROGRESS_MANUALLY = src_filter=+ TOUCH_SCREEN_CALIBRATION = src_filter=+ ARC_SUPPORT = src_filter=+ diff --git a/ini/stm32f1-maple.ini b/ini/stm32f1-maple.ini new file mode 100644 index 0000000000000..25ebfb64b625a --- /dev/null +++ b/ini/stm32f1-maple.ini @@ -0,0 +1,343 @@ +# +# Marlin Firmware +# PlatformIO Configuration File +# + +################################# +# +# STM32F1 Architecture with LibMaple STM32F1 HAL +# +# Naming Example: STM32F103RCT6 +# +# F : Foundation (sometimes High Performance F2/F4) +# 1 : Cortex M1 core +# 03 : Line/Features +# R : 64 or 66 pins (V:100, Z:144, I:176) +# C : 256KB Flash-memory (D:384KB, E:512KB, G:1024KB) +# T : LQFP package +# 6 : -40...85°C (7: ...105°C) +# +################################# + +# +# HAL/STM32F1 Common Environment values +# +[common_stm32f1] +platform = ststm32@~12.1 +board_build.core = maple +build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py + ${common.build_flags} + -DARDUINO_ARCH_STM32 +build_unflags = -std=gnu11 -std=gnu++11 +src_filter = ${common.default_src_filter} + +lib_ignore = SPI, FreeRTOS701, FreeRTOS821 +lib_deps = ${common.lib_deps} + SoftwareSerialM +platform_packages = tool-stm32duino +extra_scripts = ${common.extra_scripts} + pre:buildroot/share/PlatformIO/scripts/fix_framework_weakness.py + +# +# STM32F103RC +# +[common_STM32F103RC_maple] +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +board = genericSTM32F103RC +monitor_speed = 115200 + +# +# MEEB_3DP (STM32F103RCT6 with 512K) +# +[env:STM32F103RC_meeb] +platform = ${common_stm32f1.platform} +extends = common_STM32F103RC_maple +board = marlin_MEEB_3DP +build_flags = ${common_stm32f1.build_flags} + -DDEBUG_LEVEL=0 + -DSS_TIMER=4 + -DSTM32_FLASH_SIZE=512 + -DHSE_VALUE=12000000U + -DUSE_USB_COMPOSITE + -DVECT_TAB_OFFSET=0x2000 + -DGENERIC_BOOTLOADER +extra_scripts = ${common_stm32f1.extra_scripts} + pre:buildroot/share/PlatformIO/scripts/STM32F1_create_variant.py + buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py +lib_deps = ${common.lib_deps} + SoftwareSerialM + USBComposite for STM32F1@0.91 +custom_marlin.NEOPIXEL_LED = Adafruit NeoPixel=https://github.com/ccccmagicboy/Adafruit_NeoPixel#meeb_3dp_use +debug_tool = stlink +upload_protocol = dfu + +# +# FYSETC STM32F103RC +# +[env:STM32F103RC_fysetc] +platform = ${common_stm32f1.platform} +extends = common_STM32F103RC_maple +extra_scripts = ${common_stm32f1.extra_scripts} + buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py +build_flags = ${common_stm32f1.build_flags} -DDEBUG_LEVEL=0 +lib_ldf_mode = chain +debug_tool = stlink +upload_protocol = serial + +# +# BigTree SKR Mini V1.1 / SKR Mini E3 & MZ (STM32F103RCT6 ARM Cortex-M3) +# +# STM32F103RC_btt_maple ............. RCT6 with 256K +# STM32F103RC_btt_USB_maple ......... RCT6 with 256K (USB mass storage) +# +[env:STM32F103RC_btt_maple] +platform = ${common_stm32f1.platform} +extends = common_STM32F103RC_maple +board_build.address = 0x08007000 +board_build.ldscript = STM32F103RC_SKR_MINI_256K.ld +extra_scripts = ${common_stm32f1.extra_scripts} + buildroot/share/PlatformIO/scripts/custom_board.py +build_flags = ${common_stm32f1.build_flags} + -DDEBUG_LEVEL=0 -DSS_TIMER=4 +monitor_speed = 115200 + +[env:STM32F103RC_btt_USB_maple] +platform = ${common_stm32f1.platform} +extends = env:STM32F103RC_btt_maple +build_flags = ${env:STM32F103RC_btt_maple.build_flags} -DUSE_USB_COMPOSITE +lib_deps = ${env:STM32F103RC_btt_maple.lib_deps} + USBComposite for STM32F1@0.91 + +# +# Generic STM32F103RE environment +# +[env:STM32F103RE_maple] +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +board = genericSTM32F103RE +monitor_speed = 115200 + +# +# Creality (STM32F103RET6) +# +[env:STM32F103RET6_creality_maple] +platform = ${common_stm32f1.platform} +extends = env:STM32F103RE_maple +build_flags = ${common_stm32f1.build_flags} -DTEMP_TIMER_CHAN=4 +board_build.address = 0x08007000 +board_build.ldscript = creality.ld +extra_scripts = ${common_stm32f1.extra_scripts} + pre:buildroot/share/PlatformIO/scripts/random-bin.py + buildroot/share/PlatformIO/scripts/custom_board.py +debug_tool = jlink +upload_protocol = jlink + +# +# BigTree SKR Mini E3 V2.0 & DIP / SKR CR6 (STM32F103RET6 ARM Cortex-M3) +# +# STM32F103RE_btt_maple ............. RET6 +# STM32F103RE_btt_USB_maple ......... RET6 (USB mass storage) +# +[env:STM32F103RE_btt_maple] +platform = ${common_stm32f1.platform} +extends = env:STM32F103RE_maple +board_build.address = 0x08007000 +board_build.ldscript = STM32F103RE_SKR_MINI_512K.ld +extra_scripts = ${common_stm32f1.extra_scripts} + buildroot/share/PlatformIO/scripts/custom_board.py +build_flags = ${common_stm32f1.build_flags} -DDEBUG_LEVEL=0 -DSS_TIMER=4 +debug_tool = stlink +upload_protocol = stlink + +[env:STM32F103RE_btt_USB_maple] +platform = ${common_stm32f1.platform} +extends = env:STM32F103RE_btt_maple +build_flags = ${env:STM32F103RE_btt_maple.build_flags} -DUSE_USB_COMPOSITE +lib_deps = ${common_stm32f1.lib_deps} + USBComposite for STM32F1@0.91 + +# +# Geeetech GTM32 (STM32F103VET6) +# +[env:STM32F103VE_GTM32] +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +board = genericSTM32F103VE +build_flags = ${common_stm32f1.build_flags} + -ffunction-sections -fdata-sections -nostdlib -MMD + -DMCU_STM32F103VE -DARDUINO_GENERIC_STM32F103V -DARDUINO_ARCH_STM32F1 -DBOARD_generic_stm32f103v + -DDEBUG_LEVEL=DEBUG_NONE -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG=1 -DVECT_TAB_ADDR=0x8000000 + -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 +upload_protocol = serial + +# +# Longer 3D board in Alfawise U20 (STM32F103VET6) +# +[env:STM32F103VE_longer] +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +board = genericSTM32F103VE +board_build.address = 0x08010000 +board_build.ldscript = STM32F103VE_longer.ld +extra_scripts = ${common_stm32f1.extra_scripts} + buildroot/share/PlatformIO/scripts/custom_board.py + buildroot/share/PlatformIO/scripts/STM32F103VE_longer.py +build_flags = ${common_stm32f1.build_flags} + -DMCU_STM32F103VE -DSTM32F1xx -USERIAL_USB -DU20 -DTS_V12 +build_unflags = ${common_stm32f1.build_unflags} + -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG=1 -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 + +# +# MKS Robin Mini (STM32F103VET6) +# +[env:mks_robin_mini] +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +board = genericSTM32F103VE +extra_scripts = ${common_stm32f1.extra_scripts} + buildroot/share/PlatformIO/scripts/mks_robin_mini.py +build_flags = ${common_stm32f1.build_flags} + -DMCU_STM32F103VE + +# +# MKS Robin Nano (STM32F103VET6) +# +[env:mks_robin_nano35_maple] +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +board = genericSTM32F103VE +extra_scripts = ${common_stm32f1.extra_scripts} + buildroot/share/PlatformIO/scripts/mks_robin_nano35.py +build_flags = ${common_stm32f1.build_flags} + -DMCU_STM32F103VE -DSS_TIMER=4 +debug_tool = jlink +upload_protocol = jlink + +# +# MKS Robin (STM32F103ZET6) +# +[env:mks_robin_maple] +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +board = genericSTM32F103ZE +extra_scripts = ${common_stm32f1.extra_scripts} + buildroot/share/PlatformIO/scripts/mks_robin.py +build_flags = ${common_stm32f1.build_flags} + -DSS_TIMER=4 -DSTM32_XL_DENSITY + +# +# MKS Robin Pro (STM32F103ZET6) +# +[env:mks_robin_pro] +platform = ${common_stm32f1.platform} +extends = env:mks_robin_maple +extra_scripts = ${common_stm32f1.extra_scripts} + buildroot/share/PlatformIO/scripts/mks_robin_pro.py + +# +# TRIGORILLA PRO (STM32F103ZET6) +# +[env:trigorilla_pro] +platform = ${common_stm32f1.platform} +extends = env:mks_robin_maple +extra_scripts = ${common_stm32f1.extra_scripts} + +# +# MKS Robin E3D (STM32F103RCT6) and +# MKS Robin E3 with TMC2209 +# +[env:mks_robin_e3_maple] +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +board = genericSTM32F103RC +extra_scripts = ${common_stm32f1.extra_scripts} + buildroot/share/PlatformIO/scripts/mks_robin_e3.py +build_flags = ${common_stm32f1.build_flags} + -DDEBUG_LEVEL=0 -DSS_TIMER=4 + +# +# MKS Robin E3p (STM32F103VET6) +# - LVGL UI +# +[env:mks_robin_e3p] +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +board = genericSTM32F103VE +extra_scripts = ${common_stm32f1.extra_scripts} + buildroot/share/PlatformIO/scripts/mks_robin_e3p.py +build_flags = ${common_stm32f1.build_flags} + -DMCU_STM32F103VE -DSS_TIMER=4 +debug_tool = jlink +upload_protocol = jlink + +# +# MKS Robin Lite/Lite2 (STM32F103RCT6) +# +[env:mks_robin_lite] +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +board = genericSTM32F103RC +extra_scripts = ${common_stm32f1.extra_scripts} + buildroot/share/PlatformIO/scripts/mks_robin_lite.py + +# +# MKS ROBIN LITE3 (STM32F103RCT6) +# +[env:mks_robin_lite3] +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +board = genericSTM32F103RC +extra_scripts = ${common_stm32f1.extra_scripts} + buildroot/share/PlatformIO/scripts/mks_robin_lite3.py + +# +# JGAurora A5S A1 (STM32F103ZET6) +# +[env:jgaurora_a5s_a1] +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +board = genericSTM32F103ZE +board_build.address = 0x0800A000 +board_build.ldscript = jgaurora_a5s_a1.ld +extra_scripts = ${common_stm32f1.extra_scripts} + buildroot/share/PlatformIO/scripts/custom_board.py + buildroot/share/PlatformIO/scripts/jgaurora_a5s_a1_with_bootloader.py +build_flags = ${common_stm32f1.build_flags} + -DSTM32F1xx -DSTM32_XL_DENSITY + +# +# Malyan M200 (STM32F103CB) +# +[env:STM32F103CB_malyan_maple] +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +board = marlin_malyanM200 +build_flags = ${common_stm32f1.build_flags} + -DMCU_STM32F103CB -D__STM32F1__=1 -std=c++1y -DSERIAL_USB -ffunction-sections -fdata-sections + -Wl,--gc-sections -DDEBUG_LEVEL=0 -D__MARLIN_FIRMWARE__ +lib_ignore = ${common_stm32f1.lib_ignore} + SoftwareSerialM + +# +# Chitu boards like Tronxy X5s (STM32F103ZET6) +# +[env:chitu_f103] +platform = ${common_stm32f1.platform} +extends = common_stm32f1 +board = marlin_CHITU_F103 +extra_scripts = pre:buildroot/share/PlatformIO/scripts/common-dependencies.py + pre:buildroot/share/PlatformIO/scripts/STM32F1_create_variant.py + buildroot/share/PlatformIO/scripts/chitu_crypt.py +build_flags = ${common_stm32f1.build_flags} + -DSTM32F1xx -DSTM32_XL_DENSITY +build_unflags = ${common_stm32f1.build_unflags} + -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG= -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 + +# +# Some Chitu V5 boards have a problem with GPIO init. +# Use this target if G28 or G29 are always failing. +# +[env:chitu_v5_gpio_init] +platform = ${common_stm32f1.platform} +extends = env:chitu_f103 +build_flags = ${env:chitu_f103.build_flags} -DCHITU_V5_Z_MIN_BUGFIX diff --git a/ini/stm32f1.ini b/ini/stm32f1.ini index 6a234bdc97245..3f09a45c7ba91 100644 --- a/ini/stm32f1.ini +++ b/ini/stm32f1.ini @@ -5,7 +5,7 @@ ################################# # -# STM32F1 Architecture +# STM32F1 Architecture with unified STM32 HAL # # Naming Example: STM32F103RCT6 # @@ -31,123 +31,10 @@ build_flags = ${common.build_flags} -DADC_RESOLUTION=12 build_unflags = -std=gnu++11 src_filter = ${common.default_src_filter} + + +extra_scripts = ${common.extra_scripts} + pre:buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py -# -# HAL/STM32F1 Common Environment values -# -[common_stm32f1] -platform = ststm32@~12.1 -board_build.core = maple -build_flags = !python Marlin/src/HAL/STM32F1/build_flags.py - ${common.build_flags} - -DARDUINO_ARCH_STM32 -build_unflags = -std=gnu11 -std=gnu++11 -src_filter = ${common.default_src_filter} + -lib_ignore = SPI, FreeRTOS701, FreeRTOS821 -lib_deps = ${common.lib_deps} - SoftwareSerialM -platform_packages = tool-stm32duino -extra_scripts = ${common.extra_scripts} - pre:buildroot/share/PlatformIO/scripts/fix_framework_weakness.py - -# -# STM32F103RC -# -[env:STM32F103RC] -platform = ${common_stm32f1.platform} -extends = common_stm32f1 -board = genericSTM32F103RC -monitor_speed = 115200 - -# -# MEEB_3DP (STM32F103RCT6 with 512K) -# -[env:STM32F103RC_meeb] -platform = ${common_stm32f1.platform} -extends = common_stm32f1 -board = marlin_MEEB_3DP -build_flags = ${common_stm32f1.build_flags} - -DDEBUG_LEVEL=0 - -DSS_TIMER=4 - -DSTM32_FLASH_SIZE=512 - -DHSE_VALUE=12000000U - -DUSE_USB_COMPOSITE - -DVECT_TAB_OFFSET=0x2000 - -DGENERIC_BOOTLOADER -extra_scripts = ${common_stm32f1.extra_scripts} - pre:buildroot/share/PlatformIO/scripts/STM32F1_create_variant.py - buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py -lib_deps = ${common.lib_deps} - SoftwareSerialM - USBComposite for STM32F1@0.91 -custom_marlin.NEOPIXEL_LED = Adafruit NeoPixel=https://github.com/ccccmagicboy/Adafruit_NeoPixel#meeb_3dp_use -debug_tool = stlink -upload_protocol = dfu - -# -# STM32F103RC_fysetc -# -[env:STM32F103RC_fysetc] -platform = ${common_stm32f1.platform} -extends = env:STM32F103RC -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/STM32F103RC_fysetc.py -build_flags = ${common_stm32f1.build_flags} -DDEBUG_LEVEL=0 -lib_ldf_mode = chain -debug_tool = stlink -upload_protocol = serial - -# -# BigTree SKR Mini V1.1 / SKR mini E3 / SKR E3 DIP (STM32F103RCT6 ARM Cortex-M3) -# -# STM32F103RC_btt ............. RCT6 with 256K -# STM32F103RC_btt_USB ......... RCT6 with 256K (USB mass storage) -# STM32F103RC_btt_512K ........ RCT6 with 512K -# STM32F103RC_btt_512K_USB .... RCT6 with 512K (USB mass storage) -# -# WARNING! If you have an SKR Mini v1.1 or an SKR Mini E3 1.0 / 1.2 / 2.0 / DIP -# and experience a printer freeze, re-flash Marlin using the regular (non-512K) -# build option. 256K chips may be re-branded 512K chips, but this means the -# upper 256K is sketchy, and failure is very likely. -# - -[env:STM32F103RC_btt] -platform = ${common_stm32f1.platform} -extends = env:STM32F103RC -board_build.address = 0x08007000 -board_build.ldscript = STM32F103RC_SKR_MINI_256K.ld -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/custom_board.py -build_flags = ${common_stm32f1.build_flags} - -DDEBUG_LEVEL=0 -DSS_TIMER=4 -monitor_speed = 115200 - -[env:STM32F103RC_btt_USB] -platform = ${common_stm32f1.platform} -extends = env:STM32F103RC_btt -build_flags = ${env:STM32F103RC_btt.build_flags} -DUSE_USB_COMPOSITE -lib_deps = ${env:STM32F103RC_btt.lib_deps} - USBComposite for STM32F1@0.91 - -[env:STM32F103RC_btt_512K] -platform = ${common_stm32f1.platform} -extends = env:STM32F103RC_btt -board_build.ldscript = STM32F103RC_SKR_MINI_512K.ld -board_upload.maximum_size=524288 -build_flags = ${env:STM32F103RC_btt.build_flags} -DSTM32_FLASH_SIZE=512 - -[env:STM32F103RC_btt_512K_USB] -platform = ${common_stm32f1.platform} -extends = env:STM32F103RC_btt_512K -build_flags = ${env:STM32F103RC_btt_512K.build_flags} -DUSE_USB_COMPOSITE -lib_deps = ${env:STM32F103RC_btt_512K.lib_deps} - USBComposite for STM32F1@0.91 - -# -# STM32 HAL version of STM32F103RC_btt envs -# - -[env:STM32F103RC_stm32] +[common_STM32F103RC] platform = ${common_stm32.platform} extends = common_stm32 board = genericSTM32F103RC @@ -155,148 +42,67 @@ monitor_speed = 115200 board_build.core = stm32 board_build.variant = MARLIN_F103Rx board_build.ldscript = ldscript.ld -extra_scripts = ${common.extra_scripts} +extra_scripts = ${common_stm32.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py buildroot/share/PlatformIO/scripts/stm32_bootloader.py -[env:STM32F103RC_btt_stm32] -platform = ${common_stm32.platform} -extends = env:STM32F103RC_stm32 -build_flags = ${common_stm32.build_flags} -DDEBUG_LEVEL=0 -DTIMER_SERVO=TIM5 -board_build.offset = 0x7000 -board_build.encrypt = No -board_build.firmware = firmware.bin -board_upload.offset_address = 0x08007000 - -[env:STM32F103RC_btt_USB_stm32] -extends = env:STM32F103RC_btt_stm32 -platform = ${common_stm32.platform} -platform_packages = framework-arduinoststm32@https://github.com/rhapsodyv/Arduino_Core_STM32/archive/usb-host-msc-cdc-msc.zip -build_unflags = ${common_stm32.build_unflags} -DUSBD_USE_CDC -build_flags = ${env:STM32F103RC_btt_stm32.build_flags} ${env:stm32_flash_drive.build_flags} - -DUSBCON - -DUSE_USBHOST_HS - -DUSBD_IRQ_PRIO=5 - -DUSBD_IRQ_SUBPRIO=6 - -DUSE_USB_HS_IN_FS - -DUSBD_USE_CDC_MSC - -[env:STM32F103RC_btt_512K_stm32] -platform = ${common_stm32.platform} -extends = env:STM32F103RC_btt_stm32 -board_upload.maximum_size = 524288 -build_flags = ${env:STM32F103RC_btt_stm32.build_flags} -DLD_MAX_DATA_SIZE=524288 -DSTM32_FLASH_SIZE=512 - -[env:STM32F103RC_btt_512K_USB_stm32] -platform = ${common_stm32.platform} -extends = env:STM32F103RC_btt_USB_stm32 -board_upload.maximum_size = 524288 -build_flags = ${env:STM32F103RC_btt_USB_stm32.build_flags} -DLD_MAX_DATA_SIZE=524288 -DSTM32_FLASH_SIZE=512 - # # STM32F103RE # [env:STM32F103RE] -platform = ${common_stm32f1.platform} -extends = common_stm32f1 +platform = ${common_stm32.platform} +extends = common_stm32 board = genericSTM32F103RE monitor_speed = 115200 # -# STM32F103RE_btt ............. RET6 -# STM32F103RE_btt_USB ......... RET6 (USB mass storage) +# STM32F103VE # -[env:STM32F103RE_btt] -platform = ${common_stm32f1.platform} -extends = env:STM32F103RE -board_build.address = 0x08007000 -board_build.ldscript = STM32F103RE_SKR_E3_DIP.ld -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/custom_board.py -build_flags = ${common_stm32f1.build_flags} -DDEBUG_LEVEL=0 -DSS_TIMER=4 -debug_tool = stlink -upload_protocol = stlink - -[env:STM32F103RE_btt_USB] -platform = ${common_stm32f1.platform} -extends = env:STM32F103RE_btt -build_flags = ${env:STM32F103RE_btt.build_flags} -DUSE_USB_COMPOSITE -lib_deps = ${common_stm32f1.lib_deps} - USBComposite for STM32F1@0.91 +[env:STM32F103VE] +platform = ${common_stm32.platform} +extends = common_stm32 +board = genericSTM32F103VE +monitor_speed = 115200 # -# Geeetech GTM32 (STM32F103VET6) -# -[env:STM32F103VE_GTM32] -platform = ${common_stm32f1.platform} -extends = common_stm32f1 -board = genericSTM32F103VE -build_flags = ${common_stm32f1.build_flags} - -ffunction-sections -fdata-sections -nostdlib -MMD - -DMCU_STM32F103VE -DARDUINO_GENERIC_STM32F103V -DARDUINO_ARCH_STM32F1 -DBOARD_generic_stm32f103v - -DDEBUG_LEVEL=DEBUG_NONE -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG=1 -DVECT_TAB_ADDR=0x8000000 - -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 -upload_protocol = serial - +# STM32F103ZE # -# Longer 3D board in Alfawise U20 (STM32F103VET6) -# -[env:STM32F103VE_longer] -platform = ${common_stm32f1.platform} -extends = common_stm32f1 -board = genericSTM32F103VE -board_build.address = 0x08010000 -board_build.ldscript = STM32F103VE_longer.ld -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/custom_board.py - buildroot/share/PlatformIO/scripts/STM32F103VE_longer.py -build_flags = ${common_stm32f1.build_flags} - -DMCU_STM32F103VE -DSTM32F1xx -USERIAL_USB -DU20 -DTS_V12 -build_unflags = ${common_stm32f1.build_unflags} - -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG=1 -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 +[env:STM32F103ZE] +platform = ${common_stm32.platform} +extends = common_stm32 +board = genericSTM32F103ZE +monitor_speed = 115200 # -# MKS Robin Mini (STM32F103VET6) -# -[env:mks_robin_mini] -platform = ${common_stm32f1.platform} -extends = common_stm32f1 -board = genericSTM32F103VE -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/mks_robin_mini.py -build_flags = ${common_stm32f1.build_flags} - -DMCU_STM32F103VE - +# BigTree SKR Mini V1.1 / SKR Mini E3 & MZ (STM32F103RCT6 ARM Cortex-M3) # -# MKS Robin Nano (STM32F103VET6) +# STM32F103RC_btt ............. RCT6 with 256K +# STM32F103RC_btt_USB ......... RCT6 with 256K (USB mass storage) # -[env:mks_robin_nano35] -platform = ${common_stm32f1.platform} -extends = common_stm32f1 -board = genericSTM32F103VE -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/mks_robin_nano35.py -build_flags = ${common_stm32f1.build_flags} - -DMCU_STM32F103VE -DSS_TIMER=4 -debug_tool = jlink -upload_protocol = jlink +[env:STM32F103RC_btt] +platform = ${common_stm32.platform} +extends = common_STM32F103RC +build_flags = ${common_stm32.build_flags} -DDEBUG_LEVEL=0 -DTIMER_SERVO=TIM5 +board_build.offset = 0x7000 +board_upload.offset_address = 0x08007000 -# -# MKS Robin (STM32F103ZET6) -# -[env:mks_robin] -platform = ${common_stm32f1.platform} -extends = common_stm32f1 -board = genericSTM32F103ZE -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/mks_robin.py -build_flags = ${common_stm32f1.build_flags} - -DSS_TIMER=4 -DSTM32_XL_DENSITY +[env:STM32F103RC_btt_USB] +extends = env:STM32F103RC_btt +platform = ${common_stm32.platform} +platform_packages = framework-arduinoststm32@https://github.com/rhapsodyv/Arduino_Core_STM32/archive/usb-host-msc-cdc-msc-3.zip +build_unflags = ${common_stm32.build_unflags} -DUSBD_USE_CDC +build_flags = ${env:STM32F103RC_btt.build_flags} ${env:stm32_flash_drive.build_flags} + -DUSBCON + -DUSE_USB_FS + -DUSBD_IRQ_PRIO=5 + -DUSBD_IRQ_SUBPRIO=6 + -DUSBD_USE_CDC_MSC +# # MKS Robin (STM32F103ZET6) # Uses HAL STM32 to support Marlin UI for TFT screen with optional touch panel # -[env:mks_robin_stm32] +[env:mks_robin] platform = ${common_stm32.platform} extends = common_stm32 board = genericSTM32F103ZE @@ -304,152 +110,94 @@ board_build.core = stm32 board_build.variant = MARLIN_F103Zx board_build.ldscript = ldscript.ld board_build.offset = 0x7000 -board_build.encrypt = Yes -board_build.firmware = Robin.bin +board_build.encrypt = Robin.bin build_flags = ${common_stm32.build_flags} -DENABLE_HWSERIAL3 -DTIMER_SERIAL=TIM5 build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC -extra_scripts = ${common.extra_scripts} +extra_scripts = ${common_stm32.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py buildroot/share/PlatformIO/scripts/stm32_bootloader.py buildroot/share/PlatformIO/scripts/mks_encrypt.py lib_deps = # -# MKS Robin Pro (STM32F103ZET6) -# -[env:mks_robin_pro] -platform = ${common_stm32f1.platform} -extends = env:mks_robin -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/mks_robin_pro.py - -# -# TRIGORILLA PRO (STM32F103ZET6) -# -[env:trigorilla_pro] -platform = ${common_stm32f1.platform} -extends = env:mks_robin -extra_scripts = ${common_stm32f1.extra_scripts} - -# -# MKS Robin E3D (STM32F103RCT6) and -# MKS Robin E3 with TMC2209 +# MKS Robin E3/E3D (STM32F103RCT6) with TMC2209 # [env:mks_robin_e3] -platform = ${common_stm32f1.platform} -extends = common_stm32f1 -board = genericSTM32F103RC -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/mks_robin_e3.py -build_flags = ${common_stm32f1.build_flags} - -DDEBUG_LEVEL=0 -DSS_TIMER=4 - -# -# MKS Robin E3p (STM32F103VET6) -# - LVGL UI -# -[env:mks_robin_e3p] -platform = ${common_stm32f1.platform} -extends = common_stm32f1 -board = genericSTM32F103VE -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/mks_robin_e3p.py -build_flags = ${common_stm32f1.build_flags} - -DMCU_STM32F103VE -DSS_TIMER=4 -debug_tool = jlink -upload_protocol = jlink - -# -# MKS Robin Lite/Lite2 (STM32F103RCT6) -# -[env:mks_robin_lite] -platform = ${common_stm32f1.platform} -extends = common_stm32f1 -board = genericSTM32F103RC -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/mks_robin_lite.py - -# -# MKS ROBIN LITE3 (STM32F103RCT6) -# -[env:mks_robin_lite3] -platform = ${common_stm32f1.platform} -extends = common_stm32f1 -board = genericSTM32F103RC -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/mks_robin_lite3.py - -# -# JGAurora A5S A1 (STM32F103ZET6) -# -[env:jgaurora_a5s_a1] -platform = ${common_stm32f1.platform} -extends = common_stm32f1 -board = genericSTM32F103ZE -board_build.address = 0x0800A000 -board_build.ldscript = jgaurora_a5s_a1.ld -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/custom_board.py - buildroot/share/PlatformIO/scripts/jgaurora_a5s_a1_with_bootloader.py -build_flags = ${common_stm32f1.build_flags} - -DSTM32F1xx -DSTM32_XL_DENSITY +platform = ${common_stm32.platform} +extends = common_STM32F103RC +build_flags = ${common_stm32.build_flags} + -DDEBUG_LEVEL=0 -DTIMER_SERVO=TIM5 +build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC +monitor_speed = 115200 +board_build.offset = 0x5000 +board_build.encrypt = Robin_e3.bin +board_upload.offset_address = 0x08005000 +debug_tool = stlink +extra_scripts = ${common_STM32F103RC.extra_scripts} + buildroot/share/PlatformIO/scripts/mks_encrypt.py # -# Malyan M200 (STM32F103CB) +# Creality (STM32F103RET6) # -[env:STM32F103CB_malyan] -platform = ${common_stm32f1.platform} -extends = common_stm32f1 -board = marlin_malyanM200 -build_flags = ${common_stm32f1.build_flags} - -DMCU_STM32F103CB -D__STM32F1__=1 -std=c++1y -DSERIAL_USB -ffunction-sections -fdata-sections - -Wl,--gc-sections -DDEBUG_LEVEL=0 -D__MARLIN_FIRMWARE__ -lib_ignore = ${common_stm32f1.lib_ignore} - SoftwareSerialM +[env:STM32F103RET6_creality] +platform = ${common_stm32.platform} +extends = common_stm32 +build_flags = ${common_stm32.build_flags} -DMCU_STM32F103RE -DHAL_SD_MODULE_ENABLED -DSS_TIMER=4 -DTIMER_SERVO=TIM5 -DENABLE_HWSERIAL3 -DTRANSFER_CLOCK_DIV=8 +board = genericSTM32F103RE +monitor_speed = 115200 +board_build.core = stm32 +board_build.variant = MARLIN_F103Rx +board_build.offset = 0x7000 +board_build.ldscript = ldscript.ld +board_upload.offset_address = 0x08007000 +build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC +extra_scripts = ${common.extra_scripts} + pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py + pre:buildroot/share/PlatformIO/scripts/random-bin.py + buildroot/share/PlatformIO/scripts/stm32_bootloader.py +debug_tool = jlink +upload_protocol = jlink # -# Chitu boards like Tronxy X5s (STM32F103ZET6) -# -[env:chitu_f103] -platform = ${common_stm32f1.platform} -extends = common_stm32f1 -board = marlin_CHITU_F103 -extra_scripts = pre:buildroot/share/PlatformIO/scripts/common-dependencies.py - pre:buildroot/share/PlatformIO/scripts/STM32F1_create_variant.py - buildroot/share/PlatformIO/scripts/chitu_crypt.py -build_flags = ${common_stm32f1.build_flags} - -DSTM32F1xx -DSTM32_XL_DENSITY -build_unflags = ${common_stm32f1.build_unflags} - -DCONFIG_MAPLE_MINI_NO_DISABLE_DEBUG= -DERROR_LED_PORT=GPIOE -DERROR_LED_PIN=6 - +# BigTree SKR Mini E3 V2.0 & DIP / SKR CR6 (STM32F103RET6 ARM Cortex-M3) # -# Some Chitu V5 boards have a problem with GPIO init. -# Use this target if G28 or G29 are always failing. +# STM32F103RE_btt ............. RET6 +# STM32F103RE_btt_USB ......... RET6 (USB mass storage) # -[env:chitu_v5_gpio_init] -platform = ${common_stm32f1.platform} -extends = env:chitu_f103 -build_flags = ${env:chitu_f103.build_flags} -DCHITU_V5_Z_MIN_BUGFIX +[env:STM32F103RE_btt] +platform = ${common_stm32.platform} +extends = common_stm32 +build_flags = ${common_stm32.build_flags} -DMCU_STM32F103RE -DHAL_SD_MODULE_ENABLED -DSS_TIMER=4 -DTIMER_SERVO=TIM5 -DENABLE_HWSERIAL3 -DTRANSFER_CLOCK_DIV=8 +board = genericSTM32F103RE +monitor_speed = 115200 +board_build.core = stm32 +board_build.variant = MARLIN_F103Rx +board_build.offset = 0x7000 +board_build.ldscript = ldscript.ld +board_upload.offset_address = 0x08007000 +build_unflags = ${common_stm32.build_unflags} +extra_scripts = ${common.extra_scripts} + pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py + buildroot/share/PlatformIO/scripts/stm32_bootloader.py +debug_tool = jlink +upload_protocol = jlink -# -# Creality (STM32F103RET6) -# -[env:STM32F103RET6_creality] -platform = ${env:STM32F103RE.platform} -extends = env:STM32F103RE -build_flags = ${env:STM32F103RE.build_flags} -DTEMP_TIMER_CHAN=4 -board_build.address = 0x08007000 -board_build.ldscript = creality.ld -extra_scripts = ${env:STM32F103RE.extra_scripts} - pre:buildroot/share/PlatformIO/scripts/random-bin.py - buildroot/share/PlatformIO/scripts/custom_board.py -debug_tool = jlink -upload_protocol = jlink +[env:STM32F103RE_btt_USB] +extends = env:STM32F103RE_btt +platform = ${common_stm32.platform} +platform_packages = framework-arduinoststm32@https://github.com/rhapsodyv/Arduino_Core_STM32/archive/usb-host-msc-cdc-msc-3.zip +build_unflags = ${common_stm32.build_unflags} -DUSBD_USE_CDC +build_flags = ${env:STM32F103RE_btt.build_flags} ${env:stm32_flash_drive.build_flags} + -DUSBCON + -DUSE_USB_FS + -DUSBD_IRQ_PRIO=5 + -DUSBD_IRQ_SUBPRIO=6 + -DUSBD_USE_CDC_MSC # -# FLSUN QQS Pro (STM32F103VET6) using hal STM32 +# FLSUN QQS Pro (STM32F103VET6) # board Hispeedv1 # [env:flsun_hispeedv1] @@ -461,19 +209,18 @@ board_build.core = stm32 board_build.variant = MARLIN_F103Vx board_build.ldscript = ldscript.ld board_build.offset = 0x7000 -board_build.firmware = Robin_mini.bin -board_build.encrypt = Yes +board_build.encrypt = Robin_mini.bin board_upload.offset_address = 0x08007000 build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC -extra_scripts = ${common.extra_scripts} +extra_scripts = ${common_stm32.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py buildroot/share/PlatformIO/scripts/stm32_bootloader.py buildroot/share/PlatformIO/scripts/mks_encrypt.py # -# MKS Robin Nano V1.2 and V2 using hal STM32 +# MKS Robin Nano V1.2 and V2 # -[env:mks_robin_nano35_stm32] +[env:mks_robin_nano35] platform = ${common_stm32.platform} extends = common_stm32 build_flags = ${common_stm32.build_flags} -DMCU_STM32F103VE -DSS_TIMER=4 -DENABLE_HWSERIAL3 @@ -482,13 +229,12 @@ board_build.core = stm32 board_build.variant = MARLIN_F103Vx board_build.ldscript = ldscript.ld board_build.offset = 0x7000 -board_build.encrypt = Yes -board_build.firmware = Robin_nano35.bin +board_build.encrypt = Robin_nano35.bin board_upload.offset_address = 0x08007000 build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC debug_tool = jlink upload_protocol = jlink -extra_scripts = ${common.extra_scripts} +extra_scripts = ${common_stm32.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py buildroot/share/PlatformIO/scripts/stm32_bootloader.py buildroot/share/PlatformIO/scripts/mks_encrypt.py @@ -506,6 +252,17 @@ board_build.ldscript = ldscript.ld board_build.offset = 0x10000 build_flags = ${common_stm32.build_flags} -DENABLE_HWSERIAL3 -DTIMER_SERIAL=TIM5 build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC -extra_scripts = ${common.extra_scripts} +extra_scripts = ${common_stm32.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py buildroot/share/PlatformIO/scripts/stm32_bootloader.py + +# +# Malyan M200 (STM32F103CB) +# +[env:STM32F103CB_malyan] +platform = ${common_stm32.platform} +extends = common_stm32 +board = malyanm200_f103cb +build_flags = ${common_stm32.build_flags} + -DHAL_PCD_MODULE_ENABLED -DDISABLE_GENERIC_SERIALUSB -DHAL_UART_MODULE_ENABLED +src_filter = ${common.default_src_filter} + diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index 5d6d291182abe..ee88135ecaa5c 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -68,20 +68,6 @@ build_flags = ${common_stm32.build_flags} extra_scripts = ${common.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py -# -# FLY MINI (STM32F103RCT6) -# -[env:FLY_MINI] -platform = ${common_stm32f1.platform} -extends = common_stm32f1 -board = genericSTM32F103RC -board_build.address = 0x08005000 -board_build.ldscript = fly_mini.ld -extra_scripts = ${common_stm32f1.extra_scripts} - buildroot/share/PlatformIO/scripts/custom_board.py -build_flags = ${common_stm32f1.build_flags} - -DDEBUG_LEVEL=0 -DSS_TIMER=4 - # # FYSETC S6 (STM32F446RET6 ARM Cortex-M4) # @@ -127,9 +113,8 @@ board = marlin_STM32F407VGT6_CCM board_build.core = stm32 board_build.variant = MARLIN_F4x7Vx board_build.ldscript = ldscript.ld -board_build.firmware = firmware.srec +board_build.encrypt = firmware.srec # Just openblt.py (not stm32_bootloader.py) generates the file -board_build.encrypt = Yes board_build.offset = 0x10000 board_upload.offset_address = 0x08010000 build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 @@ -160,7 +145,7 @@ debug_init_break = # USB Flash Drive mix-ins for STM32 # [stm_flash_drive] -platform_packages = framework-arduinoststm32@https://github.com/rhapsodyv/Arduino_Core_STM32/archive/usb-host-msc.zip +platform_packages = framework-arduinoststm32@https://github.com/rhapsodyv/Arduino_Core_STM32/archive/usb-host-msc-cdc-msc-3.zip build_flags = ${common_stm32.build_flags} -DHAL_PCD_MODULE_ENABLED -DHAL_HCD_MODULE_ENABLED -DUSBHOST -DUSBH_IRQ_PRIO=3 -DUSBH_IRQ_SUBPRIO=4 @@ -248,22 +233,22 @@ build_flags = ${stm_flash_drive.build_flags} -DHSE_VALUE=8000000U -DHAL_SD_MODULE_ENABLED # -# BigTreeTech Octopus V1.0 (STM32F446ZET6 ARM Cortex-M4) +# BigTreeTech Octopus V1.0/1.1 (STM32F446ZET6 ARM Cortex-M4) # -[env:BIGTREE_OCTOPUS_V1_0] +[env:BIGTREE_OCTOPUS_V1] platform = ${common_stm32.platform} extends = common_stm32 -board = marlin_BigTree_octopus_v1 +board = marlin_BigTree_Octopus_v1 extra_scripts = ${common.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py build_flags = ${common_stm32.build_flags} -DSTM32F446_5VX -DVECT_TAB_OFFSET=0x8000 -DUSE_USB_HS_IN_FS # -# BigTreeTech Octopus V1.0 (STM32F446ZET6 ARM Cortex-M4) with USB Flash Drive Support +# BigTreeTech Octopus V1.0/1.1 (STM32F446ZET6 ARM Cortex-M4) with USB Flash Drive Support # -[env:BIGTREE_OCTOPUS_V1_0_USB] -extends = env:BIGTREE_OCTOPUS_V1_0 +[env:BIGTREE_OCTOPUS_V1_USB] +extends = env:BIGTREE_OCTOPUS_V1 platform_packages = ${stm_flash_drive.platform_packages} #build_unflags = -DUSBCON -DUSBD_USE_CDC build_flags = ${stm_flash_drive.build_flags} @@ -279,7 +264,7 @@ extends = common_stm32 board = marlin_STM32F407ZGT6 board_build.variant = MARLIN_LERDGE board_build.offset = 0x10000 -board_build.encrypt = Yes +board_build.encrypt = firmware.bin extra_scripts = ${common.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py buildroot/share/PlatformIO/scripts/stm32_bootloader.py @@ -294,9 +279,9 @@ build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC -DUS # Lerdge X # [env:LERDGEX] -platform = ${lerdge_common.platform} -extends = lerdge_common -board_build.firmware = Lerdge_X_firmware_force.bin +platform = ${lerdge_common.platform} +extends = lerdge_common +board_build.encrypt = Lerdge_X_firmware_force.bin # # Lerdge X with USB Flash Drive Support @@ -311,9 +296,9 @@ build_flags = ${stm_flash_drive.build_flags} ${lerdge_common.build_flags} # Lerdge S # [env:LERDGES] -platform = ${lerdge_common.platform} -extends = lerdge_common -board_build.firmware = Lerdge_firmware_force.bin +platform = ${lerdge_common.platform} +extends = lerdge_common +board_build.encrypt = Lerdge_firmware_force.bin # # Lerdge S with USB Flash Drive Support @@ -328,10 +313,10 @@ build_flags = ${stm_flash_drive.build_flags} ${lerdge_common.build_flags} # Lerdge K # [env:LERDGEK] -platform = ${lerdge_common.platform} -extends = lerdge_common -board_build.firmware = Lerdge_K_firmware_force.bin -build_flags = ${lerdge_common.build_flags} -DLERDGEK +platform = ${lerdge_common.platform} +extends = lerdge_common +board_build.encrypt = Lerdge_K_firmware_force.bin +build_flags = ${lerdge_common.build_flags} -DLERDGEK # # Lerdge K with USB Flash Drive Support @@ -361,8 +346,6 @@ board_build.core = stm32 board_build.variant = MARLIN_F446VE board_build.ldscript = ldscript.ld board_build.offset = 0x0000 -board_build.encrypt = No -board_build.firmware = firmware.bin extra_scripts = ${common.extra_scripts} pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py buildroot/share/PlatformIO/scripts/stm32_bootloader.py @@ -379,7 +362,6 @@ board = genericSTM32F407VET6 board_build.core = stm32 board_build.variant = MARLIN_F4x7Vx board_build.ldscript = ldscript.ld -board_build.firmware = firmware.bin board_build.offset = 0x0000 board_upload.offset_address = 0x08000000 build_unflags = ${common_stm32.build_unflags} -DUSBCON -DUSBD_USE_CDC @@ -406,7 +388,7 @@ board = marlin_STM32F407VGT6_CCM board_build.core = stm32 board_build.variant = MARLIN_F4x7Vx board_build.ldscript = ldscript.ld -board_build.firmware = Robin_nano_v3.bin +board_build.rename = Robin_nano_v3.bin board_build.offset = 0xC000 board_upload.offset_address = 0x0800C000 build_unflags = ${common_stm32.build_unflags} @@ -438,7 +420,7 @@ build_flags = ${stm_flash_drive.build_flags} ${stm32f4_I2C1.build_flags} [env:mks_robin_nano_v3_usb_flash_drive_msc] platform = ${common_stm32.platform} extends = env:mks_robin_nano_v3 -platform_packages = framework-arduinoststm32@https://github.com/rhapsodyv/Arduino_Core_STM32/archive/usb-host-msc-cdc-msc.zip +platform_packages = framework-arduinoststm32@https://github.com/rhapsodyv/Arduino_Core_STM32/archive/usb-host-msc-cdc-msc-3.zip build_unflags = ${common_stm32.build_unflags} -DUSBD_USE_CDC build_flags = ${stm_flash_drive.build_flags} ${stm32f4_I2C1.build_flags} -DUSBCON diff --git a/platformio.ini b/platformio.ini index c05e8ecb0d306..9ce965c900f10 100644 --- a/platformio.ini +++ b/platformio.ini @@ -24,6 +24,7 @@ extra_configs = ini/native.ini ini/samd51.ini ini/stm32f0.ini + ini/stm32f1-maple.ini ini/stm32f1.ini ini/stm32f4.ini ini/stm32f7.ini @@ -202,7 +203,10 @@ default_src_filter = + - - + - - - + - - + - + - - - -