From c095ee9ce9e69b01c39529492abcd1941606ebbf Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 4 May 2017 01:36:59 -0500 Subject: [PATCH 001/189] Readme Version 1.1.0 --- README.md | 175 ++++++++++++++++++------------------------------------ 1 file changed, 58 insertions(+), 117 deletions(-) diff --git a/README.md b/README.md index ad259a238..acca5b1db 100644 --- a/README.md +++ b/README.md @@ -1,140 +1,81 @@ # Marlin 3D Printer Firmware + + +## Marlin 1.1.0 + +Marlin 1.1 represents an evolutionary leap over Marlin 1.0.2. It is the result of over two years of effort by several volunteers around the world who have paid meticulous and sometimes obsessive attention to every detail. For this release we focused on code quality, performance, stability, and overall user experience. Several new features have also been added, many of which require no extra hardware. + +For complete Marlin documentation click over to the [Marlin Homepage ](http://marlinfw.org/), where you will find in-depth articles, how-to videos, and tutorials on every aspect of Marlin, as the site develops. For release notes, see the [Releases](https://github.com/MarlinFirmware/Marlin/releases) page. + +## Stable Release Branch + +This Release branch contains the latest tagged version of Marlin (currently 1.1.0 – May 2017). + +Previous releases of Marlin include [1.0.2-2](https://github.com/MarlinFirmware/Marlin/tree/1.0.2-2) (December 2016) and [1.0.1](https://github.com/MarlinFirmware/Marlin/tree/1.0.1) (December 2014). Any version of Marlin prior to 1.0.1 (when we started tagging versions) can be collectively referred to as Marlin 1.0.0. + +## Contributing to Marlin + +Click on the [Issue Queue](https://github.com/MarlinFirmware/Marlin/issues) and [Pull Requests](https://github.com/MarlinFirmware/Marlin/pulls) links above at any time to see what we're currently working on. + +To submit patches and new features for Marlin 1.1 check out the [bugfix-1.1.x](https://github.com/MarlinFirmware/Marlin/tree/bugfix-1.1.x) branch, add your commits, and submit a Pull Request back to the `bugfix-1.1.x` branch. Periodically that branch will form the basis for the next minor release. + +Note that our "bugfix" branch will always contain the latest patches to the current release version. These patches may not be widely tested. As always, when using "nightly" builds of Marlin, proceed with full caution. + +## Current Status: In Development + +Marlin development has reached an important milestone with its first stable release in over 2 years. During this period we focused on cleaning up the code and making it more modern, consistent, readable, and sensible. + +## Future Development + +Arduino IDE now supports folder hierarchies, so Marlin 1.1 is the last "flat" version of Marlin. Version 1.2 will have a hierarchical file structure, and will form the starting-point for our integration of 32-bit CPU support. -[![Build Status](https://travis-ci.org/MarlinFirmware/Marlin.svg?branch=RCBugFix)](https://travis-ci.org/MarlinFirmware/Marlin) [![Coverity Scan Build Status](https://scan.coverity.com/projects/2224/badge.svg)](https://scan.coverity.com/projects/2224) +[![Travis Build Status](https://travis-ci.org/MarlinFirmware/Marlin.svg)](https://travis-ci.org/MarlinFirmware/Marlin) - - -Additional documentation can be found at [The Marlin Documentation Project](https://www.marlinfw.org/). -Please test this firmware and inform us if it misbehaves in any way, volunteers are standing by! - -## Release Candidate -- Marlin 1.1.0-RCBugFix - 6 Dec 2016 - -__Not for production use – use with caution!__ - -You can download earlier versions of Marlin on the [Releases page](https://github.com/MarlinFirmware/Marlin/releases). (The latest "stable" release of Marlin is 1.0.2-1.) - -The latest Release Candidate lives in the ["RC" branch](https://github.com/MarlinFirmware/Marlin/tree/RC). Bugs that we find in the current Release Candidate are patched in the ["RCBugFix" branch](https://github.com/MarlinFirmware/Marlin/tree/RCBugFix), so during beta testing this is where you can always find the latest code on its way towards release. - -## Recent Changes -- RCBugFix - - Fixed broken MBL - - M600 heater timeout option - -- RC8 - 06 Dec 2016 - - Major performance improvement for Graphical LCDs - - Simplified probe configuration - - Enable Auto Bed Leveling by type - - Reduce serial communication errors - - Make Bilinear (Mesh) Grid Leveling available for non-delta - - Support for Trinamic TMC2130 SilentStepStick SPI-based drivers - - Add `M211` to Enable/Disable Software Endstops - - Add `M355` to turn the case light on/off and set brightness - - Improved I2C class with full master/slave support - - Add `G38.2` `G38.3` command option for CNC style probing - - Add `MINIMUM_STEPPER_PULSE` option to adjust step pulse duration - - Add `R` parameter support for `G2`/`G3` - - Add `M43` optional command (`PINS_DEBUGGING`) - - Remove SCARA axis scaling - - Improved sanity checking of configuration - - Improved support for PlatformIO and command-line build - - Usable `DELTA_CALIBRATION_MENU` - - Support for Printrbot Rev.F - - New and updated languages - -- RC7 - 26 Jul 2016 - - Add Print Job Timer and Print Counter (`PRINTCOUNTER`) - - New `M600` Filament Change (`FILAMENT_CHANGE_FEATURE`) - - New `G12` Nozzle Clean (`NOZZLE_CLEAN_FEATURE`) - - New `G27` Nozzle Park (`NOZZLE_PARK_FEATURE`) - - Add support for `COREYZ` - - Add a new Advance Extrusion algorithm (`LIN_ADVANCE`) - - Add support for inches, Fahrenheit, Kelvin units (`INCH_MODE_SUPPORT`, `TEMPERATURE_UNITS_SUPPORT`) - - Better handling of `G92` shifting of the coordinate space - - Add Greek and Croatian languages - - Improve the Manual (Mesh) Bed Leveling user interface - - Add support for more boards, controllers, and probes: - - Vellemann K8400 (`BOARD_K8400`) - - RigidBot V2 (`BOARD_RIGIDBOARD_V2`) - - Cartesio UI (`BOARD_CNCONTROLS_12`) - - BLTouch probe sensor (`BLTOUCH`) - - Viki 2 with RAMPS and MKS boards - - Improve support for `DELTA` and other kinematics - - Improve thermal management, add `WATCH_BED_TEMP_PERIOD` - - Better handling of toolchange, multiple tools - - Add support for two X steppers `X_DUAL_STEPPER_DRIVERS` - - Add support for `SINGLENOZZLE`, `MIXING_EXTRUDER`, and `SWITCHING_EXTRUDER` - - Simplified probe configuration, allow usage without bed leveling - - And much more… See the [1.1.0-RC7 Change Log](https://github.com/MarlinFirmware/Marlin/releases/tag/1.1.0-RC7) for the complete list of changes. - -- RC6 - 24 Apr 2016 - - Marlin now requires Arduino version 1.6.0 or later - - Completed support for CoreXY / CoreXZ - - See the [1.1.0-RC6 Change Log](https://github.com/MarlinFirmware/Marlin/releases/tag/1.1.0-RC6) for all the changes. - -- RC5 - 01 Apr 2016 - - Warn if compiling with older versions (<1.50) of Arduino - - Fix various LCD menu issues - - Add formal support for MKSv1.3 and Sainsmart (RAMPS variants) - - Fix bugs in M104, M109, and M190 - - Fix broken M404 command - - Fix issues with M23 and "Start SD Print" - - More output for M111 - - Rename FILAMENT_SENSOR to FILAMENT_WIDTH_SENSOR - - Fix SD card bugs - - and a lot more - - See the [1.1.0-RC5 Change Log](https://github.com/MarlinFirmware/Marlin/releases/tag/1.1.0-RC5) for more! - -- RC4 - 24 Mar 2016 - - Many lingering bugs and nagging issues addressed - - Improvements to LCD menus, CoreXY/CoreXZ, Delta, Bed Leveling, and more… - -- RC3 - 01 Dec 2015 - - A number of language sensitive strings have been revised - - Formatting of the LCD display has been improved to handle negative coordinates better - - Various compiler-related issues have been corrected - -- RC2 - 29 Sep 2015 - - File styling reverted - - LCD update frequency reduced - -- RC1 - 19 Sep 2015 - - Published for testing - -## Submitting Patches -Proposed patches should be submitted as a Pull Request against the [RCBugFix](https://github.com/MarlinFirmware/Marlin/tree/RCBugFix) branch. - -- Don't submit new feature proposals. The RCBugFix branch is for fixing bugs in existing features. -- Do submit questions and concerns. The "naive" question is often the one we forget to ask. -- Follow the proper coding style. Pull requests with styling errors will be delayed. See our [Coding Standards](https://github.com/MarlinFirmware/Marlin/wiki/DNE-Coding-Standards) page for more information. - -### [RepRap.org Wiki Page](http://reprap.org/wiki/Marlin) +##### [RepRap.org Wiki Page](http://reprap.org/wiki/Marlin) +##### [Marlin Home Page](http://marlinfw.org/) +##### [Marlin Discussion Forum](http://forums.reprap.org/list.php?415) ## Credits The current Marlin dev team consists of: - + - Roxanne Neufeld [@Roxy-3D] - English - Scott Lahteine [@thinkyhead] - English - - [@Wurstnase] - Deutsch, English - - F. Malpartida [@fmalpartida] - English, Spanish + - Bob Kuhn [@Bob-the-Kuhn] - English + - Andreas Hardtung [@AnHardt] - Deutsch, English + - Nico Tonnhofer [@Wurstnase] - Deutsch, English - Jochen Groppe [@CONSULitAS] - Deutsch, English + - João Brazio [@jbrazio] - Portuguese, English + - Bo Hermannsen [@boelle] - Danish, English + - Bob Cousins [@bobc] - English - [@maverikou] - Chris Palmer [@nophead] - [@paclema] - - Edward Patel [@epatel] - Swedish, English - Erik van der Zalm [@ErikZalm] - David Braam [@daid] - Bernhard Kubicek [@bkubicek] - - Roxanne Neufeld [@Roxy-3DPrintBoard] - English More features have been added by: - - Alberto Cotronei [@MagoKimbra] - - Lampmaker, - - Bradley Feldman, - - and others... + - Alberto Cotronei [@MagoKimbra] - English, Italian + - Thomas Moore [@tcm0116] + - Ernesto Martinez [@emartinez167] + - Petr Zahradnik [@clexpert] + - Kai [@Kaibob2] + - Edward Patel [@epatel] + - F. Malpartida [@fmalpartida] - English, Spanish + - [@esenapaj] - English, Japanese + - [@benlye] + - [@Tannoo] + - [@teemuatlut] + - [@bgort] + - [@LVD-AC] + - [@paulusjacobus] + - ...and many others ## License -Marlin is published under the [GPL license](/LICENSE) because we believe in open development. The GPL comes with both rights and obligations. Whether you use Marlin firmware as the driver for your open or closed-source product, you must keep Marlin open, and you must provide your compatible Marlin source code to end users upon request. The most straightforward way to comply with the Marlin license is to make a fork of Marlin on Github, perform your modifications, and direct users to your modified fork. +Marlin is published under the [GPL license](/COPYING.md) because we believe in open development. The GPL comes with both rights and obligations. Whether you use Marlin firmware as the driver for your open or closed-source product, you must keep Marlin open, and you must provide your compatible Marlin source code to end users upon request. The most straightforward way to comply with the Marlin license is to make a fork of Marlin on Github, perform your modifications, and direct users to your modified fork. While we can't prevent the use of this code in products (3D printers, CNC, etc.) that are closed source or crippled by a patent, we would prefer that you choose another firmware or, better yet, make your own. + +[![Flattr this git repo](http://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) From 3cd9af24093eb0c5d181706c9822db7b856efc12 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 4 May 2017 03:22:17 -0500 Subject: [PATCH 002/189] bugfix-1.1.x ReadMe, Version, helper scripts --- Marlin/Version.h | 4 +- README.md | 144 +++++++++++++++++++++++++++---------- buildroot/share/git/mfinfo | 2 +- 3 files changed, 111 insertions(+), 39 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 63f4b81ab..d8d490ebb 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -35,7 +35,7 @@ /** * Marlin release version identifier */ - #define SHORT_BUILD_VERSION "1.1.0-RCBugFix" + #define SHORT_BUILD_VERSION "bugfix-1.1.x" /** * Verbose version identifier which should contain a reference to the location @@ -48,7 +48,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ - #define STRING_DISTRIBUTION_DATE "2016-12-06 12:00" + #define STRING_DISTRIBUTION_DATE "2017-05-04 12:00" /** * Required minimum Configuration.h and Configuration_adv.h file versions. diff --git a/README.md b/README.md index acca5b1db..393cb20bd 100644 --- a/README.md +++ b/README.md @@ -1,40 +1,114 @@ # Marlin 3D Printer Firmware - - -## Marlin 1.1.0 - -Marlin 1.1 represents an evolutionary leap over Marlin 1.0.2. It is the result of over two years of effort by several volunteers around the world who have paid meticulous and sometimes obsessive attention to every detail. For this release we focused on code quality, performance, stability, and overall user experience. Several new features have also been added, many of which require no extra hardware. - -For complete Marlin documentation click over to the [Marlin Homepage ](http://marlinfw.org/), where you will find in-depth articles, how-to videos, and tutorials on every aspect of Marlin, as the site develops. For release notes, see the [Releases](https://github.com/MarlinFirmware/Marlin/releases) page. - -## Stable Release Branch - -This Release branch contains the latest tagged version of Marlin (currently 1.1.0 – May 2017). - -Previous releases of Marlin include [1.0.2-2](https://github.com/MarlinFirmware/Marlin/tree/1.0.2-2) (December 2016) and [1.0.1](https://github.com/MarlinFirmware/Marlin/tree/1.0.1) (December 2014). Any version of Marlin prior to 1.0.1 (when we started tagging versions) can be collectively referred to as Marlin 1.0.0. - -## Contributing to Marlin - -Click on the [Issue Queue](https://github.com/MarlinFirmware/Marlin/issues) and [Pull Requests](https://github.com/MarlinFirmware/Marlin/pulls) links above at any time to see what we're currently working on. - -To submit patches and new features for Marlin 1.1 check out the [bugfix-1.1.x](https://github.com/MarlinFirmware/Marlin/tree/bugfix-1.1.x) branch, add your commits, and submit a Pull Request back to the `bugfix-1.1.x` branch. Periodically that branch will form the basis for the next minor release. - -Note that our "bugfix" branch will always contain the latest patches to the current release version. These patches may not be widely tested. As always, when using "nightly" builds of Marlin, proceed with full caution. - -## Current Status: In Development - -Marlin development has reached an important milestone with its first stable release in over 2 years. During this period we focused on cleaning up the code and making it more modern, consistent, readable, and sensible. - -## Future Development - -Arduino IDE now supports folder hierarchies, so Marlin 1.1 is the last "flat" version of Marlin. Version 1.2 will have a hierarchical file structure, and will form the starting-point for our integration of 32-bit CPU support. +[![Build Status](https://travis-ci.org/MarlinFirmware/Marlin.svg?branch=RCBugFix)](https://travis-ci.org/MarlinFirmware/Marlin) [![Coverity Scan Build Status](https://scan.coverity.com/projects/2224/badge.svg)](https://scan.coverity.com/projects/2224) -[![Travis Build Status](https://travis-ci.org/MarlinFirmware/Marlin.svg)](https://travis-ci.org/MarlinFirmware/Marlin) -##### [RepRap.org Wiki Page](http://reprap.org/wiki/Marlin) -##### [Marlin Home Page](http://marlinfw.org/) -##### [Marlin Discussion Forum](http://forums.reprap.org/list.php?415) + + +Additional documentation can be found at the [Marlin Home Page](http://marlinfw.org/). +Please test this firmware and inform us if it misbehaves in any way, volunteers are standing by! + +## Bugfix Branch + +__Not for production use. Use with caution!__ + +This branch is used to accumulate patches to the latest 1.1.x release version. Periodically this branch will form the basis for the next minor 1.1.x release. + +Download earlier versions of Marlin on the [Releases page](https://github.com/MarlinFirmware/Marlin/releases). (The latest tagged release of Marlin is version 1.1.0.) + +## Recent Changes +- 1.1.0 - 4 May 2017 + - See the [1.1.0 Release Notes](https://github.com/MarlinFirmware/Marlin/releases/tag/1.1.0) for a full list of changes. + +- RC8 - 6 Dec 2016 + - Major performance improvement for Graphical LCDs + - Simplified probe configuration + - Enable Auto Bed Leveling by type + - Reduce serial communication errors + - Make Bilinear (Mesh) Grid Leveling available for non-delta + - Support for Trinamic TMC2130 SilentStepStick SPI-based drivers + - Add `M211` to Enable/Disable Software Endstops + - Add `M355` to turn the case light on/off and set brightness + - Improved I2C class with full master/slave support + - Add `G38.2` `G38.3` command option for CNC style probing + - Add `MINIMUM_STEPPER_PULSE` option to adjust step pulse duration + - Add `R` parameter support for `G2`/`G3` + - Add `M43` optional command (`PINS_DEBUGGING`) + - Remove SCARA axis scaling + - Improved sanity checking of configuration + - Improved support for PlatformIO and command-line build + - Usable `DELTA_CALIBRATION_MENU` + - Support for Printrbot Rev.F + - New and updated languages + +- RC7 - 26 Jul 2016 + - Add Print Job Timer and Print Counter (`PRINTCOUNTER`) + - New `M600` Filament Change (`FILAMENT_CHANGE_FEATURE`) + - New `G12` Nozzle Clean (`NOZZLE_CLEAN_FEATURE`) + - New `G27` Nozzle Park (`NOZZLE_PARK_FEATURE`) + - Add support for `COREYZ` + - Add a new Advance Extrusion algorithm (`LIN_ADVANCE`) + - Add support for inches, Fahrenheit, Kelvin units (`INCH_MODE_SUPPORT`, `TEMPERATURE_UNITS_SUPPORT`) + - Better handling of `G92` shifting of the coordinate space + - Add Greek and Croatian languages + - Improve the Manual (Mesh) Bed Leveling user interface + - Add support for more boards, controllers, and probes: + - Vellemann K8400 (`BOARD_K8400`) + - RigidBot V2 (`BOARD_RIGIDBOARD_V2`) + - Cartesio UI (`BOARD_CNCONTROLS_12`) + - BLTouch probe sensor (`BLTOUCH`) + - Viki 2 with RAMPS and MKS boards + - Improve support for `DELTA` and other kinematics + - Improve thermal management, add `WATCH_BED_TEMP_PERIOD` + - Better handling of toolchange, multiple tools + - Add support for two X steppers `X_DUAL_STEPPER_DRIVERS` + - Add support for `SINGLENOZZLE`, `MIXING_EXTRUDER`, and `SWITCHING_EXTRUDER` + - Simplified probe configuration, allow usage without bed leveling + - And much more… See the [1.1.0-RC7 Change Log](https://github.com/MarlinFirmware/Marlin/releases/tag/1.1.0-RC7) for the complete list of changes. + +- RC6 - 24 Apr 2016 + - Marlin now requires Arduino version 1.6.0 or later + - Completed support for CoreXY / CoreXZ + - See the [1.1.0-RC6 Change Log](https://github.com/MarlinFirmware/Marlin/releases/tag/1.1.0-RC6) for all the changes. + +- RC5 - 01 Apr 2016 + - Warn if compiling with older versions (<1.50) of Arduino + - Fix various LCD menu issues + - Add formal support for MKSv1.3 and Sainsmart (RAMPS variants) + - Fix bugs in M104, M109, and M190 + - Fix broken M404 command + - Fix issues with M23 and "Start SD Print" + - More output for M111 + - Rename FILAMENT_SENSOR to FILAMENT_WIDTH_SENSOR + - Fix SD card bugs + - and a lot more + - See the [1.1.0-RC5 Change Log](https://github.com/MarlinFirmware/Marlin/releases/tag/1.1.0-RC5) for more! + +- RC4 - 24 Mar 2016 + - Many lingering bugs and nagging issues addressed + - Improvements to LCD menus, CoreXY/CoreXZ, Delta, Bed Leveling, and more… + +- RC3 - 01 Dec 2015 + - A number of language sensitive strings have been revised + - Formatting of the LCD display has been improved to handle negative coordinates better + - Various compiler-related issues have been corrected + +- RC2 - 29 Sep 2015 + - File styling reverted + - LCD update frequency reduced + +- RC1 - 19 Sep 2015 + - Published for testing + +## Submitting Patches + +Proposed patches should be submitted as a Pull Request against this branch ([bugfix-1.1.x](https://github.com/MarlinFirmware/Marlin/tree/bugfix-1.1.x)). + +- This branch is for fixing bugs and integrating any new features for the duration of the Marlin 1.1.x life-cycle. We've opted for a simplified branch structure while we work on the maintainability and encapsulation of code modules. Version 1.2 and beyond should improve on separation of bug fixes and cutting-edge development. +- Follow the proper coding style to gain points with the maintainers. See our [Coding Standards](http://marlinfw.org/docs/development/coding_standards.html) page for more information. +- Please submit your questions and concerns to the [Issue Queue](https://github.com/MarlinFirmware/Marlin/issues). The "naive" question is often the one we forget to ask. + +### [RepRap.org Wiki Page](http://reprap.org/wiki/Marlin) ## Credits @@ -74,8 +148,6 @@ More features have been added by: ## License -Marlin is published under the [GPL license](/COPYING.md) because we believe in open development. The GPL comes with both rights and obligations. Whether you use Marlin firmware as the driver for your open or closed-source product, you must keep Marlin open, and you must provide your compatible Marlin source code to end users upon request. The most straightforward way to comply with the Marlin license is to make a fork of Marlin on Github, perform your modifications, and direct users to your modified fork. +Marlin is published under the [GPL license](/LICENSE) because we believe in open development. The GPL comes with both rights and obligations. Whether you use Marlin firmware as the driver for your open or closed-source product, you must keep Marlin open, and you must provide your compatible Marlin source code to end users upon request. The most straightforward way to comply with the Marlin license is to make a fork of Marlin on Github, perform your modifications, and direct users to your modified fork. While we can't prevent the use of this code in products (3D printers, CNC, etc.) that are closed source or crippled by a patent, we would prefer that you choose another firmware or, better yet, make your own. - -[![Flattr this git repo](http://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/share/git/mfinfo b/buildroot/share/git/mfinfo index 571531755..e22744fe9 100755 --- a/buildroot/share/git/mfinfo +++ b/buildroot/share/git/mfinfo @@ -25,7 +25,7 @@ if [[ $ORG != MarlinFirmware ]]; then fi case "$REPO" in - Marlin ) TARG=RCBugFix ;; + Marlin ) TARG=bugfix-1.1.x ;; MarlinDev ) TARG=dev ;; MarlinDocumentation ) TARG=master ;; esac From ae7c602031fced19173400d56fa2223260d9484b Mon Sep 17 00:00:00 2001 From: bgort Date: Thu, 4 May 2017 17:09:45 -0400 Subject: [PATCH 003/189] fix error in M105 output -- use SERIAL_PROTOCOL for ints instead of SERIAL_PROTOCOL_F (#6584) also removed wayward 'address of' ampersand in setTargetHotend and setTargetBed parameters --- Marlin/Marlin_main.cpp | 12 ++++++------ Marlin/temperature.h | 5 +++-- 2 files changed, 9 insertions(+), 8 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index a5da26432..784f26784 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -6498,9 +6498,9 @@ inline void gcode_M104() { void print_heaterstates() { #if HAS_TEMP_HOTEND SERIAL_PROTOCOLPGM(" T:"); - SERIAL_PROTOCOL_F(thermalManager.degHotend(target_extruder), 1); + SERIAL_PROTOCOL(thermalManager.degHotend(target_extruder)); SERIAL_PROTOCOLPGM(" /"); - SERIAL_PROTOCOL_F(thermalManager.degTargetHotend(target_extruder), 1); + SERIAL_PROTOCOL(thermalManager.degTargetHotend(target_extruder)); #if ENABLED(SHOW_TEMP_ADC_VALUES) SERIAL_PROTOCOLPAIR(" (", thermalManager.rawHotendTemp(target_extruder) / OVERSAMPLENR); SERIAL_PROTOCOLCHAR(')'); @@ -6508,9 +6508,9 @@ inline void gcode_M104() { #endif #if HAS_TEMP_BED SERIAL_PROTOCOLPGM(" B:"); - SERIAL_PROTOCOL_F(thermalManager.degBed(), 1); + SERIAL_PROTOCOL(thermalManager.degBed()); SERIAL_PROTOCOLPGM(" /"); - SERIAL_PROTOCOL_F(thermalManager.degTargetBed(), 1); + SERIAL_PROTOCOL(thermalManager.degTargetBed()); #if ENABLED(SHOW_TEMP_ADC_VALUES) SERIAL_PROTOCOLPAIR(" (", thermalManager.rawBedTemp() / OVERSAMPLENR); SERIAL_PROTOCOLCHAR(')'); @@ -6520,9 +6520,9 @@ inline void gcode_M104() { HOTEND_LOOP() { SERIAL_PROTOCOLPAIR(" T", e); SERIAL_PROTOCOLCHAR(':'); - SERIAL_PROTOCOL_F(thermalManager.degHotend(e), 1); + SERIAL_PROTOCOL(thermalManager.degHotend(e)); SERIAL_PROTOCOLPGM(" /"); - SERIAL_PROTOCOL_F(thermalManager.degTargetHotend(e), 1); + SERIAL_PROTOCOL(thermalManager.degTargetHotend(e)); #if ENABLED(SHOW_TEMP_ADC_VALUES) SERIAL_PROTOCOLPAIR(" (", thermalManager.rawHotendTemp(e) / OVERSAMPLENR); SERIAL_PROTOCOLCHAR(')'); diff --git a/Marlin/temperature.h b/Marlin/temperature.h index d37cb5593..35d80731e 100644 --- a/Marlin/temperature.h +++ b/Marlin/temperature.h @@ -346,6 +346,7 @@ class Temperature { #endif return target_temperature[HOTEND_INDEX]; } + static int16_t degTargetBed() { return target_temperature_bed; } #if WATCH_HOTENDS @@ -356,7 +357,7 @@ class Temperature { static void start_watching_bed(); #endif - static void setTargetHotend(const int16_t &celsius, uint8_t e) { + static void setTargetHotend(const int16_t celsius, uint8_t e) { #if HOTENDS == 1 UNUSED(e); #endif @@ -372,7 +373,7 @@ class Temperature { #endif } - static void setTargetBed(const int16_t &celsius) { + static void setTargetBed(const int16_t celsius) { target_temperature_bed = celsius; #if WATCH_THE_BED start_watching_bed(); From 267f3a03d95dc741f11abf33cde3933edd59ce48 Mon Sep 17 00:00:00 2001 From: Max Matveev Date: Thu, 4 May 2017 23:38:29 +0200 Subject: [PATCH 004/189] Fixed USE_CONTROLLER_FAN #define usage --- Marlin/Marlin_main.cpp | 6 +++--- Marlin/SanityCheck.h | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 784f26784..4a85d4ba9 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -11479,7 +11479,7 @@ void prepare_move_to_destination() { #endif // BEZIER_CURVE_SUPPORT -#if USE_CONTROLLER_FAN +#if ENABLED(USE_CONTROLLER_FAN) void controllerFan() { static millis_t lastMotorOn = 0, // Last time a motor was turned on @@ -11933,7 +11933,7 @@ void manage_inactivity(bool ignore_stepper_queue/*=false*/) { } #endif - #if USE_CONTROLLER_FAN + #if ENABLED(USE_CONTROLLER_FAN) controllerFan(); // Check if fan should be turned on to cool stepper drivers down #endif @@ -12203,7 +12203,7 @@ void setup() { endstops.enable_z_probe(false); #endif - #if USE_CONTROLLER_FAN + #if ENABLED(USE_CONTROLLER_FAN) SET_OUTPUT(CONTROLLER_FAN_PIN); //Set pin used for driver cooling fan #endif diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index 610a86567..a18d8d557 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -771,7 +771,7 @@ static_assert(1 >= 0 #error "You cannot set CONTROLLER_FAN_PIN equal to FAN_PIN." #endif -#if USE_CONTROLLER_FAN +#if ENABLED(USE_CONTROLLER_FAN) #if !HAS_CONTROLLER_FAN #error "USE_CONTROLLER_FAN requires a CONTROLLER_FAN_PIN. Define in Configuration_adv.h." #elif E0_AUTO_FAN_PIN == CONTROLLER_FAN_PIN From 7fcb5c14241bbb5c01fdf83bb3f2acd8c4c9ccae Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 5 May 2017 00:45:54 -0500 Subject: [PATCH 005/189] Minor fix in K8200 readme --- Marlin/example_configurations/K8200/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/example_configurations/K8200/README.md b/Marlin/example_configurations/K8200/README.md index 1ed6e0097..42cc1846e 100644 --- a/Marlin/example_configurations/K8200/README.md +++ b/Marlin/example_configurations/K8200/README.md @@ -4,7 +4,7 @@ * updated manually with parameters from genuine Vellemann Firmware "firmware_k8200_marlinv2" based on the recent development branch -* VM8201 uses "DISPLAY_CHARSET_HD44870_JAPAN" and "ULTIMAKERCONTROLLER" +* VM8201 uses "DISPLAY_CHARSET_HD44870 JAPANESE" and "ULTIMAKERCONTROLLER" * german (de) translation with umlaut is supported now - thanks to @AnHardt for the great hardware based umlaut support I [@CONSULitAS](https://github.com/CONSULitAS) tested the changes on my K8200 with 20x4-LCD and Arduino 1.6.12 for Mac (SD library added to IDE manually), 2016-11-18 - everything works well. From 6876e79d42b634c7864713307437c4f392632089 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 5 May 2017 02:57:22 -0500 Subject: [PATCH 006/189] Tweak command index increment --- Marlin/Marlin_main.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 4a85d4ba9..9a2ab20cd 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -832,7 +832,7 @@ void clear_command_queue() { */ inline void _commit_command(bool say_ok) { send_ok[cmd_queue_index_w] = say_ok; - cmd_queue_index_w = (cmd_queue_index_w + 1) % BUFSIZE; + if (++cmd_queue_index_w >= BUFSIZE) cmd_queue_index_w = 0; commands_in_queue++; } @@ -12330,7 +12330,7 @@ void loop() { // The queue may be reset by a command handler or by code invoked by idle() within a handler if (commands_in_queue) { --commands_in_queue; - cmd_queue_index_r = (cmd_queue_index_r + 1) % BUFSIZE; + if (++cmd_queue_index_r >= BUFSIZE) cmd_queue_index_r = 0; } } endstops.report_state(); From d14b068147f8d08401e52c16de5a7e5c78df9253 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 5 May 2017 00:46:39 -0500 Subject: [PATCH 007/189] Tweak git helper scripts --- buildroot/share/git/README.md | 60 ++++++++++++++++++++++++ buildroot/share/git/{mfprune => mfclean} | 8 ++-- buildroot/share/git/mfnew | 3 +- buildroot/share/git/mfpub | 48 ++++++++++++------- buildroot/share/git/mfrb | 6 ++- 5 files changed, 104 insertions(+), 21 deletions(-) create mode 100755 buildroot/share/git/README.md rename buildroot/share/git/{mfprune => mfclean} (76%) diff --git a/buildroot/share/git/README.md b/buildroot/share/git/README.md new file mode 100755 index 000000000..8d985242b --- /dev/null +++ b/buildroot/share/git/README.md @@ -0,0 +1,60 @@ +## Marlin Github Helper Scripts + +### Introduction + +A Pull Request is often just the start of a longer process of patching and refining the code until it's ready to merge. In that process it's common to accumulate a lot of commits, some of which are non-functional. Before merging any PR, excess commits need to be "squashed" and sometimes rearranged or reworked to produce a well-packaged set of changes and keep the commit history relatively clean. + +In addition, while a PR is being worked on other commits may be merged, leading to conflicts that need resolution. For this reason, it's a best practice to periodically refresh the PR so the working copy closely reflects the final merge. + +#### Merge vs Rebase + +I recommend not using Github Desktop to sync and merge. Use the command line instead. Github Desktop provides a "merge" option, but for best results "`git rebase`" is recommended. Merge applies new work after your commits. This buries them and makes it hard to bring them together as a final packaged unit. Rebase moves your commits to the end of the branch, ensuring that your commits will be adapted to the current code. This makes it easier to keep revising the commits in-place. + +### The Scripts + +The following scripts can be used on macOS or Linux to speed up the process of working with Marlin and submitting changes to the project. + +#### Remotes + +File|Description +----|----------- +mfadd [user]|Add Remote - Add another Github user's fork of Marlin as a remote, then fetch it. After this you can check out one of their branches and either make a PR targeted at their fork or targeted at `bugfix-1.1.x`. +mfinit|Init Working Copy - Creates a remote named '`upstream`' (for use by the other scripts) pointing to the '`MarlinFirmware`' fork. Use once after checking out your fork. + + +#### Branches + +File|Description +----|----------- +mfnew [branch]|New Branch - Creates a new branch based on `upstream/[PR-target]`. All new work should start here. +firstpush|Push the current branch to 'origin' -your fork on Github- and set it to track '`origin`'. The branch needs to reside on Github before you can use it to make a PR. + + +#### Making / Amending PRs + +File|Description +----|----------- +mfpr|Pull Request - Open the Compare / Pull Request page on Github for the current branch. +mfrb|Do a `git rebase` then `git rebase -i` of the current branch onto `upstream/[PR-target]`. Use this to edit your commits anytime. +mfqp|Quick Patch - Commit all current changes as "patch", `mfrb`, and `git push -f`. + +#### Documentation + +File|Description +----|----------- +mfdoc|Build the documentation and preview it locally. +mfpub|Build the documentation and publish it to marlinfw.org via Github. + +#### Utilities + +File|Description +----|----------- +ghtp -[h/s]|Set the protocol to use for all remotes. -h for HTTPS, -s for SSL. +mfinfo|This utility script is used by the other scripts to get:
- The upstream project ('`MarlinFirmware`')
- the '`origin`' project (i.e., your Github username),
- the repository name ('`Marlin`'),
- the PR target branch ('`bugfix-1.1.x`'), and
- the current branch (or the first command-line argument).

By itself, `mfinfo` simply prints these values to the console. +mfclean     |Prune your merged and remotely-deleted branches. + +--- + +### Examples + +Coming Soon! diff --git a/buildroot/share/git/mfprune b/buildroot/share/git/mfclean similarity index 76% rename from buildroot/share/git/mfprune rename to buildroot/share/git/mfclean index cbf10b0c2..4ce0faa8f 100755 --- a/buildroot/share/git/mfprune +++ b/buildroot/share/git/mfclean @@ -1,22 +1,24 @@ #!/usr/bin/env bash # -# mfprune +# mfclean # # Prune all your merged branches and any branches whose remotes are gone # Great way to clean up your branches after messing around a lot # +KEEP="RC|RCBugFix|dev|master|bugfix-1" + echo "Fetching latest upstream and origin..." git fetch upstream git fetch origin echo echo "Pruning Merged Branches..." -git branch --merged | egrep -v "^\*|RC|RCBugFix|dev" | xargs -n 1 git branch -d +git branch --merged | egrep -v "^\*|$KEEP" | xargs -n 1 git branch -d echo echo "Pruning Remotely-deleted Branches..." -git branch -vv | egrep -v "^\*|RC|RCBugFix|dev" | grep ': gone]' | gawk '{print $1}' | xargs -n 1 git branch -D +git branch -vv | egrep -v "^\*|$KEEP" | grep ': gone]' | gawk '{print $1}' | xargs -n 1 git branch -D echo echo "You may want to remove (or checkout) these refs..." diff --git a/buildroot/share/git/mfnew b/buildroot/share/git/mfnew index 7f3d7876c..42f233bf6 100755 --- a/buildroot/share/git/mfnew +++ b/buildroot/share/git/mfnew @@ -15,4 +15,5 @@ case "$#" in * ) echo "Usage: `basename $0` [branch]" 1>&2 ; exit 1 ;; esac -git checkout $TARG -b $BRANCH +git fetch upstream +git checkout upstream/$TARG -b $BRANCH diff --git a/buildroot/share/git/mfpub b/buildroot/share/git/mfpub index d883561bd..48ddb21dc 100755 --- a/buildroot/share/git/mfpub +++ b/buildroot/share/git/mfpub @@ -2,7 +2,11 @@ # # mfpub # -# Use Jekyll to publish Marlin Documentation to the HTML site +# Use Jekyll to generate Marlin Documentation, which is then +# git-pushed to Github to publish it to the live site. +# This publishes the current branch, and doesn't force +# changes to be pushed to the 'master' branch. Be sure to push +# any permanent changes to 'master'. # MFINFO=$(mfinfo "$@") || exit @@ -19,23 +23,22 @@ if [[ $ORG != "MarlinFirmware" || $REPO != "MarlinDocumentation" ]]; then fi if [[ $BRANCH == "gh-pages" ]]; then - echo "Can't build from 'gh-pages.' Only the Jekyll branches." + echo "Can't build from 'gh-pages.' Only the Jekyll branches (based on 'master')." bundle exec jekyll serve --watch exit fi if [[ $BRANCH != "master" ]]; then echo "Don't forget to update and push 'master'!" + # GOJF Card + git stash fi +# Check out the named branch (or stay in current) git checkout $BRANCH echo "Generating MarlinDocumentation..." -# GOJF Card -git stash - -TMPFOLDER=$( mktemp -d ) COMMIT=$( git log --format="%H" -n 1 ) # Clean out changes and other junk in the branch @@ -45,19 +48,28 @@ git clean -d -f # Push 'master' to the fork and make a proper PR... if [[ $BRANCH == "master" ]]; then - if [ -z "$(git branch -vv | grep ^\* | grep \\[origin)" ]; then firstpush; fi - - git push -f origin + if [[ $$FORK == "MarlinFirmware" ]]; then - TOOL=$(which gnome-open xdg-open open | awk '{ print $1 }') - URL="https://github.com/$ORG/$REPO/compare/$TARG...$FORK:$BRANCH?expand=1" + # Allow working directly with the main fork + git push -f upstream - if [ -z "$TOOL" ]; then - echo "Can't find a tool to open the URL:" - echo $URL else - echo "Opening a New PR Form..." - "$TOOL" "$URL" + + if [ -z "$(git branch -vv | grep ^\* | grep \\[origin)" ]; then firstpush; fi + + git push -f origin + + TOOL=$(which gnome-open xdg-open open | awk '{ print $1 }') + URL="https://github.com/$ORG/$REPO/compare/$TARG...$FORK:$BRANCH?expand=1" + + if [ -z "$TOOL" ]; then + echo "Can't find a tool to open the URL:" + echo $URL + else + echo "Opening a New PR Form..." + "$TOOL" "$URL" + fi + fi fi @@ -66,9 +78,12 @@ fi # mv ./_plugins/jekyll-press.rb-disabled ./_plugins/jekyll-press.rb # bundle install +# build the site statically and proof it bundle exec jekyll build --profile --trace --no-watch bundle exec htmlproofer ./_site --only-4xx --allow-hash-href --check-favicon --check-html --url-swap ".*marlinfw.org/:/" +# Sync the built site into a temporary folder +TMPFOLDER=$( mktemp -d ) rsync -av _site/ ${TMPFOLDER}/ # Clean out changes and other junk in the branch @@ -84,6 +99,7 @@ git add --all git commit --message "Built from ${COMMIT}" git push upstream +# remove the temporary folder rm -rf ${TMPFOLDER} # Go back to the branch we started from diff --git a/buildroot/share/git/mfrb b/buildroot/share/git/mfrb index b0b700868..1e7c26e53 100755 --- a/buildroot/share/git/mfrb +++ b/buildroot/share/git/mfrb @@ -13,4 +13,8 @@ case "$#" in * ) echo "Usage: `basename $0`" 1>&2 ; exit 1 ;; esac -git rebase -i ${INFO[3]} +# If the branch isn't currently the PR target +if [[ ${INFO[4]} != ${INFO[5]} ]]; then + git fetch upstream + git rebase upstream/${INFO[3]} && git rebase -i upstream/${INFO[3]} +fi From 77769e284f0e2a8ca9af93aff880972fd05a7bab Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 5 May 2017 13:30:19 -0500 Subject: [PATCH 008/189] Edit configuration comments --- Marlin/Configuration.h | 277 +++++++++--------- .../Cartesio/Configuration.h | 277 +++++++++--------- .../Felix/Configuration.h | 277 +++++++++--------- .../Felix/DUAL/Configuration.h | 277 +++++++++--------- .../FolgerTech-i3-2020/Configuration.h | 277 +++++++++--------- .../Hephestos/Configuration.h | 277 +++++++++--------- .../Hephestos_2/Configuration.h | 277 +++++++++--------- .../K8200/Configuration.h | 277 +++++++++--------- .../K8400/Configuration.h | 277 +++++++++--------- .../K8400/Dual-head/Configuration.h | 277 +++++++++--------- .../RepRapWorld/Megatronics/Configuration.h | 277 +++++++++--------- .../RigidBot/Configuration.h | 277 +++++++++--------- .../SCARA/Configuration.h | 277 +++++++++--------- .../TAZ4/Configuration.h | 277 +++++++++--------- .../TinyBoy2/Configuration.h | 277 +++++++++--------- .../WITBOX/Configuration.h | 277 +++++++++--------- .../adafruit/ST7565/Configuration.h | 277 +++++++++--------- .../FLSUN/auto_calibrate/Configuration.h | 277 +++++++++--------- .../delta/FLSUN/kossel_mini/Configuration.h | 277 +++++++++--------- .../delta/generic/Configuration.h | 277 +++++++++--------- .../delta/kossel_mini/Configuration.h | 277 +++++++++--------- .../delta/kossel_pro/Configuration.h | 277 +++++++++--------- .../delta/kossel_xl/Configuration.h | 277 +++++++++--------- .../gCreate_gMax1.5+/Configuration.h | 277 +++++++++--------- .../makibox/Configuration.h | 277 +++++++++--------- .../tvrrug/Round2/Configuration.h | 277 +++++++++--------- .../wt150/Configuration.h | 277 +++++++++--------- 27 files changed, 3699 insertions(+), 3780 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 478bb9a1e..4c1a39b8f 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -987,23 +987,17 @@ #define PREHEAT_2_TEMP_BED 110 #define PREHEAT_2_FAN_SPEED 0 // Value from 0 to 255 -// -// Nozzle Park -- EXPERIMENTAL -// -// When enabled allows the user to define a special XYZ position, inside the -// machine's topology, to park the nozzle when idle or when receiving the G27 -// command. -// -// The "P" paramenter controls what is the action applied to the Z axis: -// P0: (Default) If current Z-pos is lower than Z-park then the nozzle will -// be raised to reach Z-park height. -// -// P1: No matter the current Z-pos, the nozzle will be raised/lowered to -// reach Z-park height. -// -// P2: The nozzle height will be raised by Z-park amount but never going over -// the machine's limit of Z_MAX_POS. -// +/** + * Nozzle Park -- EXPERIMENTAL + * + * Park the nozzle at the given XYZ position on idle or G27. + * + * The "P" parameter controls the action applied to the Z axis: + * + * P0 (Default) If Z is below park Z raise the nozzle. + * P1 Raise the nozzle always to Z-park height. + * P2 Raise the nozzle by Z-park amount, limited to Z_MAX_POS. + */ //#define NOZZLE_PARK_FEATURE #if ENABLED(NOZZLE_PARK_FEATURE) @@ -1011,44 +1005,44 @@ #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 } #endif -// -// Clean Nozzle Feature -- EXPERIMENTAL -// -// When enabled allows the user to send G12 to start the nozzle cleaning -// process, the G-Code accepts two parameters: -// "P" for pattern selection -// "S" for defining the number of strokes/repetitions -// -// Available list of patterns: -// P0: This is the default pattern, this process requires a sponge type -// material at a fixed bed location. S defines "strokes" i.e. -// back-and-forth movements between the starting and end points. -// -// P1: This starts a zig-zag pattern between (X0, Y0) and (X1, Y1), "T" -// defines the number of zig-zag triangles to be done. "S" defines the -// number of strokes aka one back-and-forth movement. Zig-zags will -// be performed in whichever dimension is smallest. As an example, -// sending "G12 P1 S1 T3" will execute: -// -// -- -// | (X0, Y1) | /\ /\ /\ | (X1, Y1) -// | | / \ / \ / \ | -// A | | / \ / \ / \ | -// | | / \ / \ / \ | -// | (X0, Y0) | / \/ \/ \ | (X1, Y0) -// -- +--------------------------------+ -// |________|_________|_________| -// T1 T2 T3 -// -// P2: This starts a circular pattern with circle with middle in -// NOZZLE_CLEAN_CIRCLE_MIDDLE radius of R and stroke count of S. -// Before starting the circle nozzle goes to NOZZLE_CLEAN_START_POINT. -// -// Caveats: End point Z should use the same value as Start point Z. -// -// Attention: This is an EXPERIMENTAL feature, in the future the G-code arguments -// may change to add new functionality like different wipe patterns. -// +/** + * Clean Nozzle Feature -- EXPERIMENTAL + * + * Adds the G12 command to perform a nozzle cleaning process. + * + * Parameters: + * P Pattern + * S Strokes / Repetitions + * T Triangles (P1 only) + * + * Patterns: + * P0 Straight line (default). This process requires a sponge type material + * at a fixed bed location. "S" specifies strokes (i.e. back-forth motions) + * between the start / end points. + * + * P1 Zig-zag pattern between (X0, Y0) and (X1, Y1), "T" specifies the + * number of zig-zag triangles to do. "S" defines the number of strokes. + * Zig-zags are done in whichever is the narrower dimension. + * For example, "G12 P1 S1 T3" will execute: + * + * -- + * | (X0, Y1) | /\ /\ /\ | (X1, Y1) + * | | / \ / \ / \ | + * A | | / \ / \ / \ | + * | | / \ / \ / \ | + * | (X0, Y0) | / \/ \/ \ | (X1, Y0) + * -- +--------------------------------+ + * |________|_________|_________| + * T1 T2 T3 + * + * P2 Circular pattern with middle at NOZZLE_CLEAN_CIRCLE_MIDDLE. + * "R" specifies the radius. "S" specifies the stroke count. + * Before starting, the nozzle moves to NOZZLE_CLEAN_START_POINT. + * + * Caveats: The ending Z should be the same as starting Z. + * Attention: EXPERIMENTAL. G-code arguments may change. + * + */ //#define NOZZLE_CLEAN_FEATURE #if ENABLED(NOZZLE_CLEAN_FEATURE) @@ -1073,33 +1067,35 @@ #define NOZZLE_CLEAN_GOBACK #endif -// -// Print job timer -// -// Enable this option to automatically start and stop the -// print job timer when M104/M109/M190 commands are received. -// M104 (extruder without wait) - high temp = none, low temp = stop timer -// M109 (extruder with wait) - high temp = start timer, low temp = stop timer -// M190 (bed with wait) - high temp = start timer, low temp = none -// -// In all cases the timer can be started and stopped using -// the following commands: -// -// - M75 - Start the print job timer -// - M76 - Pause the print job timer -// - M77 - Stop the print job timer +/** + * Print Job Timer + * + * Automatically start and stop the print job timer on M104/M109/M190. + * + * 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 + * + * The timer can also be controlled with the following commands: + * + * M75 - Start the print job timer + * M76 - Pause the print job timer + * M77 - Stop the print job timer + */ #define PRINTJOB_TIMER_AUTOSTART -// -// Print Counter -// -// When enabled Marlin will keep track of some print statistical data such as: -// - Total print jobs -// - Total successful print jobs -// - Total failed print jobs -// - Total time printing -// -// This information can be viewed by the M78 command. +/** + * Print Counter + * + * Track statistical data such as: + * + * - Total print jobs + * - Total successful print jobs + * - Total failed print jobs + * - Total time printing + * + * View the current statistics with M78. + */ //#define PRINTCOUNTER //============================================================================= @@ -1108,78 +1104,79 @@ // @section lcd -// -// LCD LANGUAGE -// -// Here you may choose the language used by Marlin on the LCD menus, the following -// list of languages are available: -// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, -// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test -// -// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } -// +/** + * LCD LANGUAGE + * + * Select the language to display on the LCD. These languages are available: + * + * en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, + * kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test + * + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } + */ #define LCD_LANGUAGE en -// -// LCD Character Set -// -// Note: This option is NOT applicable to Graphical Displays. -// -// All character-based LCD's provide ASCII plus one of these -// language extensions: -// -// - JAPANESE ... the most common -// - WESTERN ... with more accented characters -// - CYRILLIC ... for the Russian language -// -// To determine the language extension installed on your controller: -// -// - Compile and upload with LCD_LANGUAGE set to 'test' -// - Click the controller to view the LCD menu -// - The LCD will display Japanese, Western, or Cyrillic text -// -// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language -// -// :['JAPANESE', 'WESTERN', 'CYRILLIC'] -// +/** + * LCD Character Set + * + * Note: This option is NOT applicable to Graphical Displays. + * + * All character-based LCDs provide ASCII plus one of these + * language extensions: + * + * - JAPANESE ... the most common + * - WESTERN ... with more accented characters + * - CYRILLIC ... for the Russian language + * + * To determine the language extension installed on your controller: + * + * - Compile and upload with LCD_LANGUAGE set to 'test' + * - Click the controller to view the LCD menu + * - The LCD will display Japanese, Western, or Cyrillic text + * + * See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * + * :['JAPANESE', 'WESTERN', 'CYRILLIC'] + */ #define DISPLAY_CHARSET_HD44780 JAPANESE -// -// LCD TYPE -// -// You may choose ULTRA_LCD if you have character based LCD with 16x2, 16x4, 20x2, -// 20x4 char/lines or DOGLCD for the full graphics display with 128x64 pixels -// (ST7565R family). (This option will be set automatically for certain displays.) -// -// IMPORTANT NOTE: The U8glib library is required for Full Graphic Display! -// https://github.com/olikraus/U8glib_Arduino -// +/** + * LCD TYPE + * + * Enable ULTRA_LCD for a 16x2, 16x4, 20x2, or 20x4 character-based LCD. + * Enable DOGLCD for a 128x64 (ST7565R) Full Graphical Display. + * (These options will be enabled automatically for most displays.) + * + * IMPORTANT: The U8glib library is required for Full Graphic Display! + * https://github.com/olikraus/U8glib_Arduino + */ //#define ULTRA_LCD // Character based //#define DOGLCD // Full graphics display -// -// SD CARD -// -// SD Card support is disabled by default. If your controller has an SD slot, -// you must uncomment the following option or it won't work. -// +/** + * SD CARD + * + * SD Card support is disabled by default. If your controller has an SD slot, + * you must uncomment the following option or it won't work. + * + */ //#define SDSUPPORT -// -// SD CARD: SPI SPEED -// -// Uncomment ONE of the following items to use a slower SPI transfer -// speed. This is usually required if you're getting volume init errors. -// +/** + * SD CARD: SPI SPEED + * + * Enable one of the following items for a slower SPI transfer speed. + * This may be required to resolve "volume init" errors. + */ //#define SPI_SPEED SPI_HALF_SPEED //#define SPI_SPEED SPI_QUARTER_SPEED //#define SPI_SPEED SPI_EIGHTH_SPEED -// -// SD CARD: ENABLE CRC -// -// Use CRC checks and retries on the SD communication. -// +/** + * SD CARD: ENABLE CRC + * + * Use CRC checks and retries on the SD communication. + */ //#define SD_CHECK_AND_RETRY // @@ -1207,7 +1204,7 @@ */ // -// This option reverses the encoder direction everywhere +// This option reverses the encoder direction everywhere. // // Set this option if CLOCKWISE causes values to DECREASE // diff --git a/Marlin/example_configurations/Cartesio/Configuration.h b/Marlin/example_configurations/Cartesio/Configuration.h index 1c363e529..f38780bd2 100644 --- a/Marlin/example_configurations/Cartesio/Configuration.h +++ b/Marlin/example_configurations/Cartesio/Configuration.h @@ -985,23 +985,17 @@ #define PREHEAT_2_TEMP_BED 110 #define PREHEAT_2_FAN_SPEED 0 // Value from 0 to 255 -// -// Nozzle Park -- EXPERIMENTAL -// -// When enabled allows the user to define a special XYZ position, inside the -// machine's topology, to park the nozzle when idle or when receiving the G27 -// command. -// -// The "P" paramenter controls what is the action applied to the Z axis: -// P0: (Default) If current Z-pos is lower than Z-park then the nozzle will -// be raised to reach Z-park height. -// -// P1: No matter the current Z-pos, the nozzle will be raised/lowered to -// reach Z-park height. -// -// P2: The nozzle height will be raised by Z-park amount but never going over -// the machine's limit of Z_MAX_POS. -// +/** + * Nozzle Park -- EXPERIMENTAL + * + * Park the nozzle at the given XYZ position on idle or G27. + * + * The "P" parameter controls the action applied to the Z axis: + * + * P0 (Default) If Z is below park Z raise the nozzle. + * P1 Raise the nozzle always to Z-park height. + * P2 Raise the nozzle by Z-park amount, limited to Z_MAX_POS. + */ //#define NOZZLE_PARK_FEATURE #if ENABLED(NOZZLE_PARK_FEATURE) @@ -1009,44 +1003,44 @@ #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 } #endif -// -// Clean Nozzle Feature -- EXPERIMENTAL -// -// When enabled allows the user to send G12 to start the nozzle cleaning -// process, the G-Code accepts two parameters: -// "P" for pattern selection -// "S" for defining the number of strokes/repetitions -// -// Available list of patterns: -// P0: This is the default pattern, this process requires a sponge type -// material at a fixed bed location. S defines "strokes" i.e. -// back-and-forth movements between the starting and end points. -// -// P1: This starts a zig-zag pattern between (X0, Y0) and (X1, Y1), "T" -// defines the number of zig-zag triangles to be done. "S" defines the -// number of strokes aka one back-and-forth movement. Zig-zags will -// be performed in whichever dimension is smallest. As an example, -// sending "G12 P1 S1 T3" will execute: -// -// -- -// | (X0, Y1) | /\ /\ /\ | (X1, Y1) -// | | / \ / \ / \ | -// A | | / \ / \ / \ | -// | | / \ / \ / \ | -// | (X0, Y0) | / \/ \/ \ | (X1, Y0) -// -- +--------------------------------+ -// |________|_________|_________| -// T1 T2 T3 -// -// P2: This starts a circular pattern with circle with middle in -// NOZZLE_CLEAN_CIRCLE_MIDDLE radius of R and stroke count of S. -// Before starting the circle nozzle goes to NOZZLE_CLEAN_START_POINT. -// -// Caveats: End point Z should use the same value as Start point Z. -// -// Attention: This is an EXPERIMENTAL feature, in the future the G-code arguments -// may change to add new functionality like different wipe patterns. -// +/** + * Clean Nozzle Feature -- EXPERIMENTAL + * + * Adds the G12 command to perform a nozzle cleaning process. + * + * Parameters: + * P Pattern + * S Strokes / Repetitions + * T Triangles (P1 only) + * + * Patterns: + * P0 Straight line (default). This process requires a sponge type material + * at a fixed bed location. "S" specifies strokes (i.e. back-forth motions) + * between the start / end points. + * + * P1 Zig-zag pattern between (X0, Y0) and (X1, Y1), "T" specifies the + * number of zig-zag triangles to do. "S" defines the number of strokes. + * Zig-zags are done in whichever is the narrower dimension. + * For example, "G12 P1 S1 T3" will execute: + * + * -- + * | (X0, Y1) | /\ /\ /\ | (X1, Y1) + * | | / \ / \ / \ | + * A | | / \ / \ / \ | + * | | / \ / \ / \ | + * | (X0, Y0) | / \/ \/ \ | (X1, Y0) + * -- +--------------------------------+ + * |________|_________|_________| + * T1 T2 T3 + * + * P2 Circular pattern with middle at NOZZLE_CLEAN_CIRCLE_MIDDLE. + * "R" specifies the radius. "S" specifies the stroke count. + * Before starting, the nozzle moves to NOZZLE_CLEAN_START_POINT. + * + * Caveats: The ending Z should be the same as starting Z. + * Attention: EXPERIMENTAL. G-code arguments may change. + * + */ //#define NOZZLE_CLEAN_FEATURE #if ENABLED(NOZZLE_CLEAN_FEATURE) @@ -1071,33 +1065,35 @@ #define NOZZLE_CLEAN_GOBACK #endif -// -// Print job timer -// -// Enable this option to automatically start and stop the -// print job timer when M104/M109/M190 commands are received. -// M104 (extruder without wait) - high temp = none, low temp = stop timer -// M109 (extruder with wait) - high temp = start timer, low temp = stop timer -// M190 (bed with wait) - high temp = start timer, low temp = none -// -// In all cases the timer can be started and stopped using -// the following commands: -// -// - M75 - Start the print job timer -// - M76 - Pause the print job timer -// - M77 - Stop the print job timer +/** + * Print Job Timer + * + * Automatically start and stop the print job timer on M104/M109/M190. + * + * 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 + * + * The timer can also be controlled with the following commands: + * + * M75 - Start the print job timer + * M76 - Pause the print job timer + * M77 - Stop the print job timer + */ #define PRINTJOB_TIMER_AUTOSTART -// -// Print Counter -// -// When enabled Marlin will keep track of some print statistical data such as: -// - Total print jobs -// - Total successful print jobs -// - Total failed print jobs -// - Total time printing -// -// This information can be viewed by the M78 command. +/** + * Print Counter + * + * Track statistical data such as: + * + * - Total print jobs + * - Total successful print jobs + * - Total failed print jobs + * - Total time printing + * + * View the current statistics with M78. + */ //#define PRINTCOUNTER //============================================================================= @@ -1106,78 +1102,79 @@ // @section lcd -// -// LCD LANGUAGE -// -// Here you may choose the language used by Marlin on the LCD menus, the following -// list of languages are available: -// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, -// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test -// -// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } -// +/** + * LCD LANGUAGE + * + * Select the language to display on the LCD. These languages are available: + * + * en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, + * kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test + * + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } + */ #define LCD_LANGUAGE en -// -// LCD Character Set -// -// Note: This option is NOT applicable to Graphical Displays. -// -// All character-based LCD's provide ASCII plus one of these -// language extensions: -// -// - JAPANESE ... the most common -// - WESTERN ... with more accented characters -// - CYRILLIC ... for the Russian language -// -// To determine the language extension installed on your controller: -// -// - Compile and upload with LCD_LANGUAGE set to 'test' -// - Click the controller to view the LCD menu -// - The LCD will display Japanese, Western, or Cyrillic text -// -// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language -// -// :['JAPANESE', 'WESTERN', 'CYRILLIC'] -// +/** + * LCD Character Set + * + * Note: This option is NOT applicable to Graphical Displays. + * + * All character-based LCDs provide ASCII plus one of these + * language extensions: + * + * - JAPANESE ... the most common + * - WESTERN ... with more accented characters + * - CYRILLIC ... for the Russian language + * + * To determine the language extension installed on your controller: + * + * - Compile and upload with LCD_LANGUAGE set to 'test' + * - Click the controller to view the LCD menu + * - The LCD will display Japanese, Western, or Cyrillic text + * + * See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * + * :['JAPANESE', 'WESTERN', 'CYRILLIC'] + */ #define DISPLAY_CHARSET_HD44780 JAPANESE -// -// LCD TYPE -// -// You may choose ULTRA_LCD if you have character based LCD with 16x2, 16x4, 20x2, -// 20x4 char/lines or DOGLCD for the full graphics display with 128x64 pixels -// (ST7565R family). (This option will be set automatically for certain displays.) -// -// IMPORTANT NOTE: The U8glib library is required for Full Graphic Display! -// https://github.com/olikraus/U8glib_Arduino -// +/** + * LCD TYPE + * + * Enable ULTRA_LCD for a 16x2, 16x4, 20x2, or 20x4 character-based LCD. + * Enable DOGLCD for a 128x64 (ST7565R) Full Graphical Display. + * (These options will be enabled automatically for most displays.) + * + * IMPORTANT: The U8glib library is required for Full Graphic Display! + * https://github.com/olikraus/U8glib_Arduino + */ //#define ULTRA_LCD // Character based //#define DOGLCD // Full graphics display -// -// SD CARD -// -// SD Card support is disabled by default. If your controller has an SD slot, -// you must uncomment the following option or it won't work. -// +/** + * SD CARD + * + * SD Card support is disabled by default. If your controller has an SD slot, + * you must uncomment the following option or it won't work. + * + */ #define SDSUPPORT -// -// SD CARD: SPI SPEED -// -// Uncomment ONE of the following items to use a slower SPI transfer -// speed. This is usually required if you're getting volume init errors. -// +/** + * SD CARD: SPI SPEED + * + * Enable one of the following items for a slower SPI transfer speed. + * This may be required to resolve "volume init" errors. + */ //#define SPI_SPEED SPI_HALF_SPEED //#define SPI_SPEED SPI_QUARTER_SPEED //#define SPI_SPEED SPI_EIGHTH_SPEED -// -// SD CARD: ENABLE CRC -// -// Use CRC checks and retries on the SD communication. -// +/** + * SD CARD: ENABLE CRC + * + * Use CRC checks and retries on the SD communication. + */ //#define SD_CHECK_AND_RETRY // @@ -1205,7 +1202,7 @@ */ // -// This option reverses the encoder direction everywhere +// This option reverses the encoder direction everywhere. // // Set this option if CLOCKWISE causes values to DECREASE // diff --git a/Marlin/example_configurations/Felix/Configuration.h b/Marlin/example_configurations/Felix/Configuration.h index 477063b4f..ec12db1ab 100644 --- a/Marlin/example_configurations/Felix/Configuration.h +++ b/Marlin/example_configurations/Felix/Configuration.h @@ -969,23 +969,17 @@ #define PREHEAT_2_TEMP_BED 100 #define PREHEAT_2_FAN_SPEED 255 // Value from 0 to 255 -// -// Nozzle Park -- EXPERIMENTAL -// -// When enabled allows the user to define a special XYZ position, inside the -// machine's topology, to park the nozzle when idle or when receiving the G27 -// command. -// -// The "P" paramenter controls what is the action applied to the Z axis: -// P0: (Default) If current Z-pos is lower than Z-park then the nozzle will -// be raised to reach Z-park height. -// -// P1: No matter the current Z-pos, the nozzle will be raised/lowered to -// reach Z-park height. -// -// P2: The nozzle height will be raised by Z-park amount but never going over -// the machine's limit of Z_MAX_POS. -// +/** + * Nozzle Park -- EXPERIMENTAL + * + * Park the nozzle at the given XYZ position on idle or G27. + * + * The "P" parameter controls the action applied to the Z axis: + * + * P0 (Default) If Z is below park Z raise the nozzle. + * P1 Raise the nozzle always to Z-park height. + * P2 Raise the nozzle by Z-park amount, limited to Z_MAX_POS. + */ //#define NOZZLE_PARK_FEATURE #if ENABLED(NOZZLE_PARK_FEATURE) @@ -993,44 +987,44 @@ #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 } #endif -// -// Clean Nozzle Feature -- EXPERIMENTAL -// -// When enabled allows the user to send G12 to start the nozzle cleaning -// process, the G-Code accepts two parameters: -// "P" for pattern selection -// "S" for defining the number of strokes/repetitions -// -// Available list of patterns: -// P0: This is the default pattern, this process requires a sponge type -// material at a fixed bed location. S defines "strokes" i.e. -// back-and-forth movements between the starting and end points. -// -// P1: This starts a zig-zag pattern between (X0, Y0) and (X1, Y1), "T" -// defines the number of zig-zag triangles to be done. "S" defines the -// number of strokes aka one back-and-forth movement. Zig-zags will -// be performed in whichever dimension is smallest. As an example, -// sending "G12 P1 S1 T3" will execute: -// -// -- -// | (X0, Y1) | /\ /\ /\ | (X1, Y1) -// | | / \ / \ / \ | -// A | | / \ / \ / \ | -// | | / \ / \ / \ | -// | (X0, Y0) | / \/ \/ \ | (X1, Y0) -// -- +--------------------------------+ -// |________|_________|_________| -// T1 T2 T3 -// -// P2: This starts a circular pattern with circle with middle in -// NOZZLE_CLEAN_CIRCLE_MIDDLE radius of R and stroke count of S. -// Before starting the circle nozzle goes to NOZZLE_CLEAN_START_POINT. -// -// Caveats: End point Z should use the same value as Start point Z. -// -// Attention: This is an EXPERIMENTAL feature, in the future the G-code arguments -// may change to add new functionality like different wipe patterns. -// +/** + * Clean Nozzle Feature -- EXPERIMENTAL + * + * Adds the G12 command to perform a nozzle cleaning process. + * + * Parameters: + * P Pattern + * S Strokes / Repetitions + * T Triangles (P1 only) + * + * Patterns: + * P0 Straight line (default). This process requires a sponge type material + * at a fixed bed location. "S" specifies strokes (i.e. back-forth motions) + * between the start / end points. + * + * P1 Zig-zag pattern between (X0, Y0) and (X1, Y1), "T" specifies the + * number of zig-zag triangles to do. "S" defines the number of strokes. + * Zig-zags are done in whichever is the narrower dimension. + * For example, "G12 P1 S1 T3" will execute: + * + * -- + * | (X0, Y1) | /\ /\ /\ | (X1, Y1) + * | | / \ / \ / \ | + * A | | / \ / \ / \ | + * | | / \ / \ / \ | + * | (X0, Y0) | / \/ \/ \ | (X1, Y0) + * -- +--------------------------------+ + * |________|_________|_________| + * T1 T2 T3 + * + * P2 Circular pattern with middle at NOZZLE_CLEAN_CIRCLE_MIDDLE. + * "R" specifies the radius. "S" specifies the stroke count. + * Before starting, the nozzle moves to NOZZLE_CLEAN_START_POINT. + * + * Caveats: The ending Z should be the same as starting Z. + * Attention: EXPERIMENTAL. G-code arguments may change. + * + */ //#define NOZZLE_CLEAN_FEATURE #if ENABLED(NOZZLE_CLEAN_FEATURE) @@ -1055,33 +1049,35 @@ #define NOZZLE_CLEAN_GOBACK #endif -// -// Print job timer -// -// Enable this option to automatically start and stop the -// print job timer when M104/M109/M190 commands are received. -// M104 (extruder without wait) - high temp = none, low temp = stop timer -// M109 (extruder with wait) - high temp = start timer, low temp = stop timer -// M190 (bed with wait) - high temp = start timer, low temp = none -// -// In all cases the timer can be started and stopped using -// the following commands: -// -// - M75 - Start the print job timer -// - M76 - Pause the print job timer -// - M77 - Stop the print job timer +/** + * Print Job Timer + * + * Automatically start and stop the print job timer on M104/M109/M190. + * + * 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 + * + * The timer can also be controlled with the following commands: + * + * M75 - Start the print job timer + * M76 - Pause the print job timer + * M77 - Stop the print job timer + */ #define PRINTJOB_TIMER_AUTOSTART -// -// Print Counter -// -// When enabled Marlin will keep track of some print statistical data such as: -// - Total print jobs -// - Total successful print jobs -// - Total failed print jobs -// - Total time printing -// -// This information can be viewed by the M78 command. +/** + * Print Counter + * + * Track statistical data such as: + * + * - Total print jobs + * - Total successful print jobs + * - Total failed print jobs + * - Total time printing + * + * View the current statistics with M78. + */ //#define PRINTCOUNTER //============================================================================= @@ -1090,78 +1086,79 @@ // @section lcd -// -// LCD LANGUAGE -// -// Here you may choose the language used by Marlin on the LCD menus, the following -// list of languages are available: -// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, -// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test -// -// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } -// +/** + * LCD LANGUAGE + * + * Select the language to display on the LCD. These languages are available: + * + * en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, + * kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test + * + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } + */ //#define LCD_LANGUAGE en -// -// LCD Character Set -// -// Note: This option is NOT applicable to Graphical Displays. -// -// All character-based LCD's provide ASCII plus one of these -// language extensions: -// -// - JAPANESE ... the most common -// - WESTERN ... with more accented characters -// - CYRILLIC ... for the Russian language -// -// To determine the language extension installed on your controller: -// -// - Compile and upload with LCD_LANGUAGE set to 'test' -// - Click the controller to view the LCD menu -// - The LCD will display Japanese, Western, or Cyrillic text -// -// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language -// -// :['JAPANESE', 'WESTERN', 'CYRILLIC'] -// +/** + * LCD Character Set + * + * Note: This option is NOT applicable to Graphical Displays. + * + * All character-based LCDs provide ASCII plus one of these + * language extensions: + * + * - JAPANESE ... the most common + * - WESTERN ... with more accented characters + * - CYRILLIC ... for the Russian language + * + * To determine the language extension installed on your controller: + * + * - Compile and upload with LCD_LANGUAGE set to 'test' + * - Click the controller to view the LCD menu + * - The LCD will display Japanese, Western, or Cyrillic text + * + * See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * + * :['JAPANESE', 'WESTERN', 'CYRILLIC'] + */ #define DISPLAY_CHARSET_HD44780 JAPANESE -// -// LCD TYPE -// -// You may choose ULTRA_LCD if you have character based LCD with 16x2, 16x4, 20x2, -// 20x4 char/lines or DOGLCD for the full graphics display with 128x64 pixels -// (ST7565R family). (This option will be set automatically for certain displays.) -// -// IMPORTANT NOTE: The U8glib library is required for Full Graphic Display! -// https://github.com/olikraus/U8glib_Arduino -// +/** + * LCD TYPE + * + * Enable ULTRA_LCD for a 16x2, 16x4, 20x2, or 20x4 character-based LCD. + * Enable DOGLCD for a 128x64 (ST7565R) Full Graphical Display. + * (These options will be enabled automatically for most displays.) + * + * IMPORTANT: The U8glib library is required for Full Graphic Display! + * https://github.com/olikraus/U8glib_Arduino + */ //#define ULTRA_LCD // Character based //#define DOGLCD // Full graphics display -// -// SD CARD -// -// SD Card support is disabled by default. If your controller has an SD slot, -// you must uncomment the following option or it won't work. -// +/** + * SD CARD + * + * SD Card support is disabled by default. If your controller has an SD slot, + * you must uncomment the following option or it won't work. + * + */ //#define SDSUPPORT -// -// SD CARD: SPI SPEED -// -// Uncomment ONE of the following items to use a slower SPI transfer -// speed. This is usually required if you're getting volume init errors. -// +/** + * SD CARD: SPI SPEED + * + * Enable one of the following items for a slower SPI transfer speed. + * This may be required to resolve "volume init" errors. + */ //#define SPI_SPEED SPI_HALF_SPEED //#define SPI_SPEED SPI_QUARTER_SPEED //#define SPI_SPEED SPI_EIGHTH_SPEED -// -// SD CARD: ENABLE CRC -// -// Use CRC checks and retries on the SD communication. -// +/** + * SD CARD: ENABLE CRC + * + * Use CRC checks and retries on the SD communication. + */ //#define SD_CHECK_AND_RETRY // @@ -1189,7 +1186,7 @@ */ // -// This option reverses the encoder direction everywhere +// This option reverses the encoder direction everywhere. // // Set this option if CLOCKWISE causes values to DECREASE // diff --git a/Marlin/example_configurations/Felix/DUAL/Configuration.h b/Marlin/example_configurations/Felix/DUAL/Configuration.h index f3d60d472..88c750fb3 100644 --- a/Marlin/example_configurations/Felix/DUAL/Configuration.h +++ b/Marlin/example_configurations/Felix/DUAL/Configuration.h @@ -969,23 +969,17 @@ #define PREHEAT_2_TEMP_BED 100 #define PREHEAT_2_FAN_SPEED 255 // Value from 0 to 255 -// -// Nozzle Park -- EXPERIMENTAL -// -// When enabled allows the user to define a special XYZ position, inside the -// machine's topology, to park the nozzle when idle or when receiving the G27 -// command. -// -// The "P" paramenter controls what is the action applied to the Z axis: -// P0: (Default) If current Z-pos is lower than Z-park then the nozzle will -// be raised to reach Z-park height. -// -// P1: No matter the current Z-pos, the nozzle will be raised/lowered to -// reach Z-park height. -// -// P2: The nozzle height will be raised by Z-park amount but never going over -// the machine's limit of Z_MAX_POS. -// +/** + * Nozzle Park -- EXPERIMENTAL + * + * Park the nozzle at the given XYZ position on idle or G27. + * + * The "P" parameter controls the action applied to the Z axis: + * + * P0 (Default) If Z is below park Z raise the nozzle. + * P1 Raise the nozzle always to Z-park height. + * P2 Raise the nozzle by Z-park amount, limited to Z_MAX_POS. + */ //#define NOZZLE_PARK_FEATURE #if ENABLED(NOZZLE_PARK_FEATURE) @@ -993,44 +987,44 @@ #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 } #endif -// -// Clean Nozzle Feature -- EXPERIMENTAL -// -// When enabled allows the user to send G12 to start the nozzle cleaning -// process, the G-Code accepts two parameters: -// "P" for pattern selection -// "S" for defining the number of strokes/repetitions -// -// Available list of patterns: -// P0: This is the default pattern, this process requires a sponge type -// material at a fixed bed location. S defines "strokes" i.e. -// back-and-forth movements between the starting and end points. -// -// P1: This starts a zig-zag pattern between (X0, Y0) and (X1, Y1), "T" -// defines the number of zig-zag triangles to be done. "S" defines the -// number of strokes aka one back-and-forth movement. Zig-zags will -// be performed in whichever dimension is smallest. As an example, -// sending "G12 P1 S1 T3" will execute: -// -// -- -// | (X0, Y1) | /\ /\ /\ | (X1, Y1) -// | | / \ / \ / \ | -// A | | / \ / \ / \ | -// | | / \ / \ / \ | -// | (X0, Y0) | / \/ \/ \ | (X1, Y0) -// -- +--------------------------------+ -// |________|_________|_________| -// T1 T2 T3 -// -// P2: This starts a circular pattern with circle with middle in -// NOZZLE_CLEAN_CIRCLE_MIDDLE radius of R and stroke count of S. -// Before starting the circle nozzle goes to NOZZLE_CLEAN_START_POINT. -// -// Caveats: End point Z should use the same value as Start point Z. -// -// Attention: This is an EXPERIMENTAL feature, in the future the G-code arguments -// may change to add new functionality like different wipe patterns. -// +/** + * Clean Nozzle Feature -- EXPERIMENTAL + * + * Adds the G12 command to perform a nozzle cleaning process. + * + * Parameters: + * P Pattern + * S Strokes / Repetitions + * T Triangles (P1 only) + * + * Patterns: + * P0 Straight line (default). This process requires a sponge type material + * at a fixed bed location. "S" specifies strokes (i.e. back-forth motions) + * between the start / end points. + * + * P1 Zig-zag pattern between (X0, Y0) and (X1, Y1), "T" specifies the + * number of zig-zag triangles to do. "S" defines the number of strokes. + * Zig-zags are done in whichever is the narrower dimension. + * For example, "G12 P1 S1 T3" will execute: + * + * -- + * | (X0, Y1) | /\ /\ /\ | (X1, Y1) + * | | / \ / \ / \ | + * A | | / \ / \ / \ | + * | | / \ / \ / \ | + * | (X0, Y0) | / \/ \/ \ | (X1, Y0) + * -- +--------------------------------+ + * |________|_________|_________| + * T1 T2 T3 + * + * P2 Circular pattern with middle at NOZZLE_CLEAN_CIRCLE_MIDDLE. + * "R" specifies the radius. "S" specifies the stroke count. + * Before starting, the nozzle moves to NOZZLE_CLEAN_START_POINT. + * + * Caveats: The ending Z should be the same as starting Z. + * Attention: EXPERIMENTAL. G-code arguments may change. + * + */ //#define NOZZLE_CLEAN_FEATURE #if ENABLED(NOZZLE_CLEAN_FEATURE) @@ -1055,33 +1049,35 @@ #define NOZZLE_CLEAN_GOBACK #endif -// -// Print job timer -// -// Enable this option to automatically start and stop the -// print job timer when M104/M109/M190 commands are received. -// M104 (extruder without wait) - high temp = none, low temp = stop timer -// M109 (extruder with wait) - high temp = start timer, low temp = stop timer -// M190 (bed with wait) - high temp = start timer, low temp = none -// -// In all cases the timer can be started and stopped using -// the following commands: -// -// - M75 - Start the print job timer -// - M76 - Pause the print job timer -// - M77 - Stop the print job timer +/** + * Print Job Timer + * + * Automatically start and stop the print job timer on M104/M109/M190. + * + * 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 + * + * The timer can also be controlled with the following commands: + * + * M75 - Start the print job timer + * M76 - Pause the print job timer + * M77 - Stop the print job timer + */ #define PRINTJOB_TIMER_AUTOSTART -// -// Print Counter -// -// When enabled Marlin will keep track of some print statistical data such as: -// - Total print jobs -// - Total successful print jobs -// - Total failed print jobs -// - Total time printing -// -// This information can be viewed by the M78 command. +/** + * Print Counter + * + * Track statistical data such as: + * + * - Total print jobs + * - Total successful print jobs + * - Total failed print jobs + * - Total time printing + * + * View the current statistics with M78. + */ //#define PRINTCOUNTER //============================================================================= @@ -1090,78 +1086,79 @@ // @section lcd -// -// LCD LANGUAGE -// -// Here you may choose the language used by Marlin on the LCD menus, the following -// list of languages are available: -// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, -// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test -// -// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } -// +/** + * LCD LANGUAGE + * + * Select the language to display on the LCD. These languages are available: + * + * en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, + * kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test + * + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } + */ //#define LCD_LANGUAGE en -// -// LCD Character Set -// -// Note: This option is NOT applicable to Graphical Displays. -// -// All character-based LCD's provide ASCII plus one of these -// language extensions: -// -// - JAPANESE ... the most common -// - WESTERN ... with more accented characters -// - CYRILLIC ... for the Russian language -// -// To determine the language extension installed on your controller: -// -// - Compile and upload with LCD_LANGUAGE set to 'test' -// - Click the controller to view the LCD menu -// - The LCD will display Japanese, Western, or Cyrillic text -// -// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language -// -// :['JAPANESE', 'WESTERN', 'CYRILLIC'] -// +/** + * LCD Character Set + * + * Note: This option is NOT applicable to Graphical Displays. + * + * All character-based LCDs provide ASCII plus one of these + * language extensions: + * + * - JAPANESE ... the most common + * - WESTERN ... with more accented characters + * - CYRILLIC ... for the Russian language + * + * To determine the language extension installed on your controller: + * + * - Compile and upload with LCD_LANGUAGE set to 'test' + * - Click the controller to view the LCD menu + * - The LCD will display Japanese, Western, or Cyrillic text + * + * See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * + * :['JAPANESE', 'WESTERN', 'CYRILLIC'] + */ #define DISPLAY_CHARSET_HD44780 JAPANESE -// -// LCD TYPE -// -// You may choose ULTRA_LCD if you have character based LCD with 16x2, 16x4, 20x2, -// 20x4 char/lines or DOGLCD for the full graphics display with 128x64 pixels -// (ST7565R family). (This option will be set automatically for certain displays.) -// -// IMPORTANT NOTE: The U8glib library is required for Full Graphic Display! -// https://github.com/olikraus/U8glib_Arduino -// +/** + * LCD TYPE + * + * Enable ULTRA_LCD for a 16x2, 16x4, 20x2, or 20x4 character-based LCD. + * Enable DOGLCD for a 128x64 (ST7565R) Full Graphical Display. + * (These options will be enabled automatically for most displays.) + * + * IMPORTANT: The U8glib library is required for Full Graphic Display! + * https://github.com/olikraus/U8glib_Arduino + */ //#define ULTRA_LCD // Character based //#define DOGLCD // Full graphics display -// -// SD CARD -// -// SD Card support is disabled by default. If your controller has an SD slot, -// you must uncomment the following option or it won't work. -// +/** + * SD CARD + * + * SD Card support is disabled by default. If your controller has an SD slot, + * you must uncomment the following option or it won't work. + * + */ //#define SDSUPPORT -// -// SD CARD: SPI SPEED -// -// Uncomment ONE of the following items to use a slower SPI transfer -// speed. This is usually required if you're getting volume init errors. -// +/** + * SD CARD: SPI SPEED + * + * Enable one of the following items for a slower SPI transfer speed. + * This may be required to resolve "volume init" errors. + */ //#define SPI_SPEED SPI_HALF_SPEED //#define SPI_SPEED SPI_QUARTER_SPEED //#define SPI_SPEED SPI_EIGHTH_SPEED -// -// SD CARD: ENABLE CRC -// -// Use CRC checks and retries on the SD communication. -// +/** + * SD CARD: ENABLE CRC + * + * Use CRC checks and retries on the SD communication. + */ //#define SD_CHECK_AND_RETRY // @@ -1189,7 +1186,7 @@ */ // -// This option reverses the encoder direction everywhere +// This option reverses the encoder direction everywhere. // // Set this option if CLOCKWISE causes values to DECREASE // diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h index e467d3eed..0e131869f 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h @@ -991,23 +991,17 @@ #define PREHEAT_2_TEMP_BED 110 #define PREHEAT_2_FAN_SPEED 0 // Value from 0 to 255 -// -// Nozzle Park -- EXPERIMENTAL -// -// When enabled allows the user to define a special XYZ position, inside the -// machine's topology, to park the nozzle when idle or when receiving the G27 -// command. -// -// The "P" paramenter controls what is the action applied to the Z axis: -// P0: (Default) If current Z-pos is lower than Z-park then the nozzle will -// be raised to reach Z-park height. -// -// P1: No matter the current Z-pos, the nozzle will be raised/lowered to -// reach Z-park height. -// -// P2: The nozzle height will be raised by Z-park amount but never going over -// the machine's limit of Z_MAX_POS. -// +/** + * Nozzle Park -- EXPERIMENTAL + * + * Park the nozzle at the given XYZ position on idle or G27. + * + * The "P" parameter controls the action applied to the Z axis: + * + * P0 (Default) If Z is below park Z raise the nozzle. + * P1 Raise the nozzle always to Z-park height. + * P2 Raise the nozzle by Z-park amount, limited to Z_MAX_POS. + */ //#define NOZZLE_PARK_FEATURE #if ENABLED(NOZZLE_PARK_FEATURE) @@ -1015,44 +1009,44 @@ #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 } #endif -// -// Clean Nozzle Feature -- EXPERIMENTAL -// -// When enabled allows the user to send G12 to start the nozzle cleaning -// process, the G-Code accepts two parameters: -// "P" for pattern selection -// "S" for defining the number of strokes/repetitions -// -// Available list of patterns: -// P0: This is the default pattern, this process requires a sponge type -// material at a fixed bed location. S defines "strokes" i.e. -// back-and-forth movements between the starting and end points. -// -// P1: This starts a zig-zag pattern between (X0, Y0) and (X1, Y1), "T" -// defines the number of zig-zag triangles to be done. "S" defines the -// number of strokes aka one back-and-forth movement. Zig-zags will -// be performed in whichever dimension is smallest. As an example, -// sending "G12 P1 S1 T3" will execute: -// -// -- -// | (X0, Y1) | /\ /\ /\ | (X1, Y1) -// | | / \ / \ / \ | -// A | | / \ / \ / \ | -// | | / \ / \ / \ | -// | (X0, Y0) | / \/ \/ \ | (X1, Y0) -// -- +--------------------------------+ -// |________|_________|_________| -// T1 T2 T3 -// -// P2: This starts a circular pattern with circle with middle in -// NOZZLE_CLEAN_CIRCLE_MIDDLE radius of R and stroke count of S. -// Before starting the circle nozzle goes to NOZZLE_CLEAN_START_POINT. -// -// Caveats: End point Z should use the same value as Start point Z. -// -// Attention: This is an EXPERIMENTAL feature, in the future the G-code arguments -// may change to add new functionality like different wipe patterns. -// +/** + * Clean Nozzle Feature -- EXPERIMENTAL + * + * Adds the G12 command to perform a nozzle cleaning process. + * + * Parameters: + * P Pattern + * S Strokes / Repetitions + * T Triangles (P1 only) + * + * Patterns: + * P0 Straight line (default). This process requires a sponge type material + * at a fixed bed location. "S" specifies strokes (i.e. back-forth motions) + * between the start / end points. + * + * P1 Zig-zag pattern between (X0, Y0) and (X1, Y1), "T" specifies the + * number of zig-zag triangles to do. "S" defines the number of strokes. + * Zig-zags are done in whichever is the narrower dimension. + * For example, "G12 P1 S1 T3" will execute: + * + * -- + * | (X0, Y1) | /\ /\ /\ | (X1, Y1) + * | | / \ / \ / \ | + * A | | / \ / \ / \ | + * | | / \ / \ / \ | + * | (X0, Y0) | / \/ \/ \ | (X1, Y0) + * -- +--------------------------------+ + * |________|_________|_________| + * T1 T2 T3 + * + * P2 Circular pattern with middle at NOZZLE_CLEAN_CIRCLE_MIDDLE. + * "R" specifies the radius. "S" specifies the stroke count. + * Before starting, the nozzle moves to NOZZLE_CLEAN_START_POINT. + * + * Caveats: The ending Z should be the same as starting Z. + * Attention: EXPERIMENTAL. G-code arguments may change. + * + */ //#define NOZZLE_CLEAN_FEATURE #if ENABLED(NOZZLE_CLEAN_FEATURE) @@ -1077,33 +1071,35 @@ #define NOZZLE_CLEAN_GOBACK #endif -// -// Print job timer -// -// Enable this option to automatically start and stop the -// print job timer when M104/M109/M190 commands are received. -// M104 (extruder without wait) - high temp = none, low temp = stop timer -// M109 (extruder with wait) - high temp = start timer, low temp = stop timer -// M190 (bed with wait) - high temp = start timer, low temp = none -// -// In all cases the timer can be started and stopped using -// the following commands: -// -// - M75 - Start the print job timer -// - M76 - Pause the print job timer -// - M77 - Stop the print job timer +/** + * Print Job Timer + * + * Automatically start and stop the print job timer on M104/M109/M190. + * + * 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 + * + * The timer can also be controlled with the following commands: + * + * M75 - Start the print job timer + * M76 - Pause the print job timer + * M77 - Stop the print job timer + */ #define PRINTJOB_TIMER_AUTOSTART -// -// Print Counter -// -// When enabled Marlin will keep track of some print statistical data such as: -// - Total print jobs -// - Total successful print jobs -// - Total failed print jobs -// - Total time printing -// -// This information can be viewed by the M78 command. +/** + * Print Counter + * + * Track statistical data such as: + * + * - Total print jobs + * - Total successful print jobs + * - Total failed print jobs + * - Total time printing + * + * View the current statistics with M78. + */ //#define PRINTCOUNTER //============================================================================= @@ -1112,78 +1108,79 @@ // @section lcd -// -// LCD LANGUAGE -// -// Here you may choose the language used by Marlin on the LCD menus, the following -// list of languages are available: -// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, -// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test -// -// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } -// +/** + * LCD LANGUAGE + * + * Select the language to display on the LCD. These languages are available: + * + * en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, + * kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test + * + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } + */ #define LCD_LANGUAGE en -// -// LCD Character Set -// -// Note: This option is NOT applicable to Graphical Displays. -// -// All character-based LCD's provide ASCII plus one of these -// language extensions: -// -// - JAPANESE ... the most common -// - WESTERN ... with more accented characters -// - CYRILLIC ... for the Russian language -// -// To determine the language extension installed on your controller: -// -// - Compile and upload with LCD_LANGUAGE set to 'test' -// - Click the controller to view the LCD menu -// - The LCD will display Japanese, Western, or Cyrillic text -// -// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language -// -// :['JAPANESE', 'WESTERN', 'CYRILLIC'] -// +/** + * LCD Character Set + * + * Note: This option is NOT applicable to Graphical Displays. + * + * All character-based LCDs provide ASCII plus one of these + * language extensions: + * + * - JAPANESE ... the most common + * - WESTERN ... with more accented characters + * - CYRILLIC ... for the Russian language + * + * To determine the language extension installed on your controller: + * + * - Compile and upload with LCD_LANGUAGE set to 'test' + * - Click the controller to view the LCD menu + * - The LCD will display Japanese, Western, or Cyrillic text + * + * See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * + * :['JAPANESE', 'WESTERN', 'CYRILLIC'] + */ #define DISPLAY_CHARSET_HD44780 JAPANESE -// -// LCD TYPE -// -// You may choose ULTRA_LCD if you have character based LCD with 16x2, 16x4, 20x2, -// 20x4 char/lines or DOGLCD for the full graphics display with 128x64 pixels -// (ST7565R family). (This option will be set automatically for certain displays.) -// -// IMPORTANT NOTE: The U8glib library is required for Full Graphic Display! -// https://github.com/olikraus/U8glib_Arduino -// +/** + * LCD TYPE + * + * Enable ULTRA_LCD for a 16x2, 16x4, 20x2, or 20x4 character-based LCD. + * Enable DOGLCD for a 128x64 (ST7565R) Full Graphical Display. + * (These options will be enabled automatically for most displays.) + * + * IMPORTANT: The U8glib library is required for Full Graphic Display! + * https://github.com/olikraus/U8glib_Arduino + */ //#define ULTRA_LCD // Character based //#define DOGLCD // Full graphics display -// -// SD CARD -// -// SD Card support is disabled by default. If your controller has an SD slot, -// you must uncomment the following option or it won't work. -// +/** + * SD CARD + * + * SD Card support is disabled by default. If your controller has an SD slot, + * you must uncomment the following option or it won't work. + * + */ #define SDSUPPORT -// -// SD CARD: SPI SPEED -// -// Uncomment ONE of the following items to use a slower SPI transfer -// speed. This is usually required if you're getting volume init errors. -// +/** + * SD CARD: SPI SPEED + * + * Enable one of the following items for a slower SPI transfer speed. + * This may be required to resolve "volume init" errors. + */ //#define SPI_SPEED SPI_HALF_SPEED //#define SPI_SPEED SPI_QUARTER_SPEED //#define SPI_SPEED SPI_EIGHTH_SPEED -// -// SD CARD: ENABLE CRC -// -// Use CRC checks and retries on the SD communication. -// +/** + * SD CARD: ENABLE CRC + * + * Use CRC checks and retries on the SD communication. + */ #define SD_CHECK_AND_RETRY // @@ -1211,7 +1208,7 @@ */ // -// This option reverses the encoder direction everywhere +// This option reverses the encoder direction everywhere. // // Set this option if CLOCKWISE causes values to DECREASE // diff --git a/Marlin/example_configurations/Hephestos/Configuration.h b/Marlin/example_configurations/Hephestos/Configuration.h index ceee2afdf..02dfe9c4f 100644 --- a/Marlin/example_configurations/Hephestos/Configuration.h +++ b/Marlin/example_configurations/Hephestos/Configuration.h @@ -977,23 +977,17 @@ #define PREHEAT_2_TEMP_BED 100 #define PREHEAT_2_FAN_SPEED 255 // Value from 0 to 255 -// -// Nozzle Park -- EXPERIMENTAL -// -// When enabled allows the user to define a special XYZ position, inside the -// machine's topology, to park the nozzle when idle or when receiving the G27 -// command. -// -// The "P" paramenter controls what is the action applied to the Z axis: -// P0: (Default) If current Z-pos is lower than Z-park then the nozzle will -// be raised to reach Z-park height. -// -// P1: No matter the current Z-pos, the nozzle will be raised/lowered to -// reach Z-park height. -// -// P2: The nozzle height will be raised by Z-park amount but never going over -// the machine's limit of Z_MAX_POS. -// +/** + * Nozzle Park -- EXPERIMENTAL + * + * Park the nozzle at the given XYZ position on idle or G27. + * + * The "P" parameter controls the action applied to the Z axis: + * + * P0 (Default) If Z is below park Z raise the nozzle. + * P1 Raise the nozzle always to Z-park height. + * P2 Raise the nozzle by Z-park amount, limited to Z_MAX_POS. + */ //#define NOZZLE_PARK_FEATURE #if ENABLED(NOZZLE_PARK_FEATURE) @@ -1001,44 +995,44 @@ #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 } #endif -// -// Clean Nozzle Feature -- EXPERIMENTAL -// -// When enabled allows the user to send G12 to start the nozzle cleaning -// process, the G-Code accepts two parameters: -// "P" for pattern selection -// "S" for defining the number of strokes/repetitions -// -// Available list of patterns: -// P0: This is the default pattern, this process requires a sponge type -// material at a fixed bed location. S defines "strokes" i.e. -// back-and-forth movements between the starting and end points. -// -// P1: This starts a zig-zag pattern between (X0, Y0) and (X1, Y1), "T" -// defines the number of zig-zag triangles to be done. "S" defines the -// number of strokes aka one back-and-forth movement. Zig-zags will -// be performed in whichever dimension is smallest. As an example, -// sending "G12 P1 S1 T3" will execute: -// -// -- -// | (X0, Y1) | /\ /\ /\ | (X1, Y1) -// | | / \ / \ / \ | -// A | | / \ / \ / \ | -// | | / \ / \ / \ | -// | (X0, Y0) | / \/ \/ \ | (X1, Y0) -// -- +--------------------------------+ -// |________|_________|_________| -// T1 T2 T3 -// -// P2: This starts a circular pattern with circle with middle in -// NOZZLE_CLEAN_CIRCLE_MIDDLE radius of R and stroke count of S. -// Before starting the circle nozzle goes to NOZZLE_CLEAN_START_POINT. -// -// Caveats: End point Z should use the same value as Start point Z. -// -// Attention: This is an EXPERIMENTAL feature, in the future the G-code arguments -// may change to add new functionality like different wipe patterns. -// +/** + * Clean Nozzle Feature -- EXPERIMENTAL + * + * Adds the G12 command to perform a nozzle cleaning process. + * + * Parameters: + * P Pattern + * S Strokes / Repetitions + * T Triangles (P1 only) + * + * Patterns: + * P0 Straight line (default). This process requires a sponge type material + * at a fixed bed location. "S" specifies strokes (i.e. back-forth motions) + * between the start / end points. + * + * P1 Zig-zag pattern between (X0, Y0) and (X1, Y1), "T" specifies the + * number of zig-zag triangles to do. "S" defines the number of strokes. + * Zig-zags are done in whichever is the narrower dimension. + * For example, "G12 P1 S1 T3" will execute: + * + * -- + * | (X0, Y1) | /\ /\ /\ | (X1, Y1) + * | | / \ / \ / \ | + * A | | / \ / \ / \ | + * | | / \ / \ / \ | + * | (X0, Y0) | / \/ \/ \ | (X1, Y0) + * -- +--------------------------------+ + * |________|_________|_________| + * T1 T2 T3 + * + * P2 Circular pattern with middle at NOZZLE_CLEAN_CIRCLE_MIDDLE. + * "R" specifies the radius. "S" specifies the stroke count. + * Before starting, the nozzle moves to NOZZLE_CLEAN_START_POINT. + * + * Caveats: The ending Z should be the same as starting Z. + * Attention: EXPERIMENTAL. G-code arguments may change. + * + */ //#define NOZZLE_CLEAN_FEATURE #if ENABLED(NOZZLE_CLEAN_FEATURE) @@ -1063,33 +1057,35 @@ #define NOZZLE_CLEAN_GOBACK #endif -// -// Print job timer -// -// Enable this option to automatically start and stop the -// print job timer when M104/M109/M190 commands are received. -// M104 (extruder without wait) - high temp = none, low temp = stop timer -// M109 (extruder with wait) - high temp = start timer, low temp = stop timer -// M190 (bed with wait) - high temp = start timer, low temp = none -// -// In all cases the timer can be started and stopped using -// the following commands: -// -// - M75 - Start the print job timer -// - M76 - Pause the print job timer -// - M77 - Stop the print job timer +/** + * Print Job Timer + * + * Automatically start and stop the print job timer on M104/M109/M190. + * + * 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 + * + * The timer can also be controlled with the following commands: + * + * M75 - Start the print job timer + * M76 - Pause the print job timer + * M77 - Stop the print job timer + */ #define PRINTJOB_TIMER_AUTOSTART -// -// Print Counter -// -// When enabled Marlin will keep track of some print statistical data such as: -// - Total print jobs -// - Total successful print jobs -// - Total failed print jobs -// - Total time printing -// -// This information can be viewed by the M78 command. +/** + * Print Counter + * + * Track statistical data such as: + * + * - Total print jobs + * - Total successful print jobs + * - Total failed print jobs + * - Total time printing + * + * View the current statistics with M78. + */ //#define PRINTCOUNTER //============================================================================= @@ -1098,78 +1094,79 @@ // @section lcd -// -// LCD LANGUAGE -// -// Here you may choose the language used by Marlin on the LCD menus, the following -// list of languages are available: -// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, -// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test -// -// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } -// +/** + * LCD LANGUAGE + * + * Select the language to display on the LCD. These languages are available: + * + * en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, + * kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test + * + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } + */ //#define LCD_LANGUAGE en -// -// LCD Character Set -// -// Note: This option is NOT applicable to Graphical Displays. -// -// All character-based LCD's provide ASCII plus one of these -// language extensions: -// -// - JAPANESE ... the most common -// - WESTERN ... with more accented characters -// - CYRILLIC ... for the Russian language -// -// To determine the language extension installed on your controller: -// -// - Compile and upload with LCD_LANGUAGE set to 'test' -// - Click the controller to view the LCD menu -// - The LCD will display Japanese, Western, or Cyrillic text -// -// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language -// -// :['JAPANESE', 'WESTERN', 'CYRILLIC'] -// +/** + * LCD Character Set + * + * Note: This option is NOT applicable to Graphical Displays. + * + * All character-based LCDs provide ASCII plus one of these + * language extensions: + * + * - JAPANESE ... the most common + * - WESTERN ... with more accented characters + * - CYRILLIC ... for the Russian language + * + * To determine the language extension installed on your controller: + * + * - Compile and upload with LCD_LANGUAGE set to 'test' + * - Click the controller to view the LCD menu + * - The LCD will display Japanese, Western, or Cyrillic text + * + * See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * + * :['JAPANESE', 'WESTERN', 'CYRILLIC'] + */ #define DISPLAY_CHARSET_HD44780 JAPANESE -// -// LCD TYPE -// -// You may choose ULTRA_LCD if you have character based LCD with 16x2, 16x4, 20x2, -// 20x4 char/lines or DOGLCD for the full graphics display with 128x64 pixels -// (ST7565R family). (This option will be set automatically for certain displays.) -// -// IMPORTANT NOTE: The U8glib library is required for Full Graphic Display! -// https://github.com/olikraus/U8glib_Arduino -// +/** + * LCD TYPE + * + * Enable ULTRA_LCD for a 16x2, 16x4, 20x2, or 20x4 character-based LCD. + * Enable DOGLCD for a 128x64 (ST7565R) Full Graphical Display. + * (These options will be enabled automatically for most displays.) + * + * IMPORTANT: The U8glib library is required for Full Graphic Display! + * https://github.com/olikraus/U8glib_Arduino + */ #define ULTRA_LCD // Character based //#define DOGLCD // Full graphics display -// -// SD CARD -// -// SD Card support is disabled by default. If your controller has an SD slot, -// you must uncomment the following option or it won't work. -// +/** + * SD CARD + * + * SD Card support is disabled by default. If your controller has an SD slot, + * you must uncomment the following option or it won't work. + * + */ #define SDSUPPORT -// -// SD CARD: SPI SPEED -// -// Uncomment ONE of the following items to use a slower SPI transfer -// speed. This is usually required if you're getting volume init errors. -// +/** + * SD CARD: SPI SPEED + * + * Enable one of the following items for a slower SPI transfer speed. + * This may be required to resolve "volume init" errors. + */ //#define SPI_SPEED SPI_HALF_SPEED //#define SPI_SPEED SPI_QUARTER_SPEED //#define SPI_SPEED SPI_EIGHTH_SPEED -// -// SD CARD: ENABLE CRC -// -// Use CRC checks and retries on the SD communication. -// +/** + * SD CARD: ENABLE CRC + * + * Use CRC checks and retries on the SD communication. + */ //#define SD_CHECK_AND_RETRY // @@ -1197,7 +1194,7 @@ */ // -// This option reverses the encoder direction everywhere +// This option reverses the encoder direction everywhere. // // Set this option if CLOCKWISE causes values to DECREASE // diff --git a/Marlin/example_configurations/Hephestos_2/Configuration.h b/Marlin/example_configurations/Hephestos_2/Configuration.h index 9ca6416e4..5c81632d8 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration.h @@ -980,23 +980,17 @@ #define PREHEAT_2_TEMP_BED 110 #define PREHEAT_2_FAN_SPEED 0 // Value from 0 to 255 -// -// Nozzle Park -- EXPERIMENTAL -// -// When enabled allows the user to define a special XYZ position, inside the -// machine's topology, to park the nozzle when idle or when receiving the G27 -// command. -// -// The "P" paramenter controls what is the action applied to the Z axis: -// P0: (Default) If current Z-pos is lower than Z-park then the nozzle will -// be raised to reach Z-park height. -// -// P1: No matter the current Z-pos, the nozzle will be raised/lowered to -// reach Z-park height. -// -// P2: The nozzle height will be raised by Z-park amount but never going over -// the machine's limit of Z_MAX_POS. -// +/** + * Nozzle Park -- EXPERIMENTAL + * + * Park the nozzle at the given XYZ position on idle or G27. + * + * The "P" parameter controls the action applied to the Z axis: + * + * P0 (Default) If Z is below park Z raise the nozzle. + * P1 Raise the nozzle always to Z-park height. + * P2 Raise the nozzle by Z-park amount, limited to Z_MAX_POS. + */ #define NOZZLE_PARK_FEATURE #if ENABLED(NOZZLE_PARK_FEATURE) @@ -1004,44 +998,44 @@ #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 10 } #endif -// -// Clean Nozzle Feature -- EXPERIMENTAL -// -// When enabled allows the user to send G12 to start the nozzle cleaning -// process, the G-Code accepts two parameters: -// "P" for pattern selection -// "S" for defining the number of strokes/repetitions -// -// Available list of patterns: -// P0: This is the default pattern, this process requires a sponge type -// material at a fixed bed location. S defines "strokes" i.e. -// back-and-forth movements between the starting and end points. -// -// P1: This starts a zig-zag pattern between (X0, Y0) and (X1, Y1), "T" -// defines the number of zig-zag triangles to be done. "S" defines the -// number of strokes aka one back-and-forth movement. Zig-zags will -// be performed in whichever dimension is smallest. As an example, -// sending "G12 P1 S1 T3" will execute: -// -// -- -// | (X0, Y1) | /\ /\ /\ | (X1, Y1) -// | | / \ / \ / \ | -// A | | / \ / \ / \ | -// | | / \ / \ / \ | -// | (X0, Y0) | / \/ \/ \ | (X1, Y0) -// -- +--------------------------------+ -// |________|_________|_________| -// T1 T2 T3 -// -// P2: This starts a circular pattern with circle with middle in -// NOZZLE_CLEAN_CIRCLE_MIDDLE radius of R and stroke count of S. -// Before starting the circle nozzle goes to NOZZLE_CLEAN_START_POINT. -// -// Caveats: End point Z should use the same value as Start point Z. -// -// Attention: This is an EXPERIMENTAL feature, in the future the G-code arguments -// may change to add new functionality like different wipe patterns. -// +/** + * Clean Nozzle Feature -- EXPERIMENTAL + * + * Adds the G12 command to perform a nozzle cleaning process. + * + * Parameters: + * P Pattern + * S Strokes / Repetitions + * T Triangles (P1 only) + * + * Patterns: + * P0 Straight line (default). This process requires a sponge type material + * at a fixed bed location. "S" specifies strokes (i.e. back-forth motions) + * between the start / end points. + * + * P1 Zig-zag pattern between (X0, Y0) and (X1, Y1), "T" specifies the + * number of zig-zag triangles to do. "S" defines the number of strokes. + * Zig-zags are done in whichever is the narrower dimension. + * For example, "G12 P1 S1 T3" will execute: + * + * -- + * | (X0, Y1) | /\ /\ /\ | (X1, Y1) + * | | / \ / \ / \ | + * A | | / \ / \ / \ | + * | | / \ / \ / \ | + * | (X0, Y0) | / \/ \/ \ | (X1, Y0) + * -- +--------------------------------+ + * |________|_________|_________| + * T1 T2 T3 + * + * P2 Circular pattern with middle at NOZZLE_CLEAN_CIRCLE_MIDDLE. + * "R" specifies the radius. "S" specifies the stroke count. + * Before starting, the nozzle moves to NOZZLE_CLEAN_START_POINT. + * + * Caveats: The ending Z should be the same as starting Z. + * Attention: EXPERIMENTAL. G-code arguments may change. + * + */ #define NOZZLE_CLEAN_FEATURE #if ENABLED(NOZZLE_CLEAN_FEATURE) @@ -1066,33 +1060,35 @@ //#define NOZZLE_CLEAN_GOBACK #endif -// -// Print job timer -// -// Enable this option to automatically start and stop the -// print job timer when M104/M109/M190 commands are received. -// M104 (extruder without wait) - high temp = none, low temp = stop timer -// M109 (extruder with wait) - high temp = start timer, low temp = stop timer -// M190 (bed with wait) - high temp = start timer, low temp = none -// -// In all cases the timer can be started and stopped using -// the following commands: -// -// - M75 - Start the print job timer -// - M76 - Pause the print job timer -// - M77 - Stop the print job timer +/** + * Print Job Timer + * + * Automatically start and stop the print job timer on M104/M109/M190. + * + * 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 + * + * The timer can also be controlled with the following commands: + * + * M75 - Start the print job timer + * M76 - Pause the print job timer + * M77 - Stop the print job timer + */ #define PRINTJOB_TIMER_AUTOSTART -// -// Print Counter -// -// When enabled Marlin will keep track of some print statistical data such as: -// - Total print jobs -// - Total successful print jobs -// - Total failed print jobs -// - Total time printing -// -// This information can be viewed by the M78 command. +/** + * Print Counter + * + * Track statistical data such as: + * + * - Total print jobs + * - Total successful print jobs + * - Total failed print jobs + * - Total time printing + * + * View the current statistics with M78. + */ #define PRINTCOUNTER //============================================================================= @@ -1101,78 +1097,79 @@ // @section lcd -// -// LCD LANGUAGE -// -// Here you may choose the language used by Marlin on the LCD menus, the following -// list of languages are available: -// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, -// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test -// -// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } -// +/** + * LCD LANGUAGE + * + * Select the language to display on the LCD. These languages are available: + * + * en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, + * kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test + * + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } + */ #define LCD_LANGUAGE en -// -// LCD Character Set -// -// Note: This option is NOT applicable to Graphical Displays. -// -// All character-based LCD's provide ASCII plus one of these -// language extensions: -// -// - JAPANESE ... the most common -// - WESTERN ... with more accented characters -// - CYRILLIC ... for the Russian language -// -// To determine the language extension installed on your controller: -// -// - Compile and upload with LCD_LANGUAGE set to 'test' -// - Click the controller to view the LCD menu -// - The LCD will display Japanese, Western, or Cyrillic text -// -// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language -// -// :['JAPANESE', 'WESTERN', 'CYRILLIC'] -// +/** + * LCD Character Set + * + * Note: This option is NOT applicable to Graphical Displays. + * + * All character-based LCDs provide ASCII plus one of these + * language extensions: + * + * - JAPANESE ... the most common + * - WESTERN ... with more accented characters + * - CYRILLIC ... for the Russian language + * + * To determine the language extension installed on your controller: + * + * - Compile and upload with LCD_LANGUAGE set to 'test' + * - Click the controller to view the LCD menu + * - The LCD will display Japanese, Western, or Cyrillic text + * + * See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * + * :['JAPANESE', 'WESTERN', 'CYRILLIC'] + */ #define DISPLAY_CHARSET_HD44780 JAPANESE -// -// LCD TYPE -// -// You may choose ULTRA_LCD if you have character based LCD with 16x2, 16x4, 20x2, -// 20x4 char/lines or DOGLCD for the full graphics display with 128x64 pixels -// (ST7565R family). (This option will be set automatically for certain displays.) -// -// IMPORTANT NOTE: The U8glib library is required for Full Graphic Display! -// https://github.com/olikraus/U8glib_Arduino -// +/** + * LCD TYPE + * + * Enable ULTRA_LCD for a 16x2, 16x4, 20x2, or 20x4 character-based LCD. + * Enable DOGLCD for a 128x64 (ST7565R) Full Graphical Display. + * (These options will be enabled automatically for most displays.) + * + * IMPORTANT: The U8glib library is required for Full Graphic Display! + * https://github.com/olikraus/U8glib_Arduino + */ //#define ULTRA_LCD // Character based //#define DOGLCD // Full graphics display -// -// SD CARD -// -// SD Card support is disabled by default. If your controller has an SD slot, -// you must uncomment the following option or it won't work. -// +/** + * SD CARD + * + * SD Card support is disabled by default. If your controller has an SD slot, + * you must uncomment the following option or it won't work. + * + */ #define SDSUPPORT -// -// SD CARD: SPI SPEED -// -// Uncomment ONE of the following items to use a slower SPI transfer -// speed. This is usually required if you're getting volume init errors. -// +/** + * SD CARD: SPI SPEED + * + * Enable one of the following items for a slower SPI transfer speed. + * This may be required to resolve "volume init" errors. + */ //#define SPI_SPEED SPI_HALF_SPEED //#define SPI_SPEED SPI_QUARTER_SPEED //#define SPI_SPEED SPI_EIGHTH_SPEED -// -// SD CARD: ENABLE CRC -// -// Use CRC checks and retries on the SD communication. -// +/** + * SD CARD: ENABLE CRC + * + * Use CRC checks and retries on the SD communication. + */ #define SD_CHECK_AND_RETRY // @@ -1200,7 +1197,7 @@ */ // -// This option reverses the encoder direction everywhere +// This option reverses the encoder direction everywhere. // // Set this option if CLOCKWISE causes values to DECREASE // diff --git a/Marlin/example_configurations/K8200/Configuration.h b/Marlin/example_configurations/K8200/Configuration.h index 1f4964895..914deba96 100644 --- a/Marlin/example_configurations/K8200/Configuration.h +++ b/Marlin/example_configurations/K8200/Configuration.h @@ -1015,23 +1015,17 @@ #define PREHEAT_2_TEMP_BED 60 // K8200: ABS / set back to 110 if you have an upgraded heatbed power supply #define PREHEAT_2_FAN_SPEED 0 // Value from 0 to 255 -// -// Nozzle Park -- EXPERIMENTAL -// -// When enabled allows the user to define a special XYZ position, inside the -// machine's topology, to park the nozzle when idle or when receiving the G27 -// command. -// -// The "P" paramenter controls what is the action applied to the Z axis: -// P0: (Default) If current Z-pos is lower than Z-park then the nozzle will -// be raised to reach Z-park height. -// -// P1: No matter the current Z-pos, the nozzle will be raised/lowered to -// reach Z-park height. -// -// P2: The nozzle height will be raised by Z-park amount but never going over -// the machine's limit of Z_MAX_POS. -// +/** + * Nozzle Park -- EXPERIMENTAL + * + * Park the nozzle at the given XYZ position on idle or G27. + * + * The "P" parameter controls the action applied to the Z axis: + * + * P0 (Default) If Z is below park Z raise the nozzle. + * P1 Raise the nozzle always to Z-park height. + * P2 Raise the nozzle by Z-park amount, limited to Z_MAX_POS. + */ //#define NOZZLE_PARK_FEATURE #if ENABLED(NOZZLE_PARK_FEATURE) @@ -1039,44 +1033,44 @@ #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 } #endif -// -// Clean Nozzle Feature -- EXPERIMENTAL -// -// When enabled allows the user to send G12 to start the nozzle cleaning -// process, the G-Code accepts two parameters: -// "P" for pattern selection -// "S" for defining the number of strokes/repetitions -// -// Available list of patterns: -// P0: This is the default pattern, this process requires a sponge type -// material at a fixed bed location. S defines "strokes" i.e. -// back-and-forth movements between the starting and end points. -// -// P1: This starts a zig-zag pattern between (X0, Y0) and (X1, Y1), "T" -// defines the number of zig-zag triangles to be done. "S" defines the -// number of strokes aka one back-and-forth movement. Zig-zags will -// be performed in whichever dimension is smallest. As an example, -// sending "G12 P1 S1 T3" will execute: -// -// -- -// | (X0, Y1) | /\ /\ /\ | (X1, Y1) -// | | / \ / \ / \ | -// A | | / \ / \ / \ | -// | | / \ / \ / \ | -// | (X0, Y0) | / \/ \/ \ | (X1, Y0) -// -- +--------------------------------+ -// |________|_________|_________| -// T1 T2 T3 -// -// P2: This starts a circular pattern with circle with middle in -// NOZZLE_CLEAN_CIRCLE_MIDDLE radius of R and stroke count of S. -// Before starting the circle nozzle goes to NOZZLE_CLEAN_START_POINT. -// -// Caveats: End point Z should use the same value as Start point Z. -// -// Attention: This is an EXPERIMENTAL feature, in the future the G-code arguments -// may change to add new functionality like different wipe patterns. -// +/** + * Clean Nozzle Feature -- EXPERIMENTAL + * + * Adds the G12 command to perform a nozzle cleaning process. + * + * Parameters: + * P Pattern + * S Strokes / Repetitions + * T Triangles (P1 only) + * + * Patterns: + * P0 Straight line (default). This process requires a sponge type material + * at a fixed bed location. "S" specifies strokes (i.e. back-forth motions) + * between the start / end points. + * + * P1 Zig-zag pattern between (X0, Y0) and (X1, Y1), "T" specifies the + * number of zig-zag triangles to do. "S" defines the number of strokes. + * Zig-zags are done in whichever is the narrower dimension. + * For example, "G12 P1 S1 T3" will execute: + * + * -- + * | (X0, Y1) | /\ /\ /\ | (X1, Y1) + * | | / \ / \ / \ | + * A | | / \ / \ / \ | + * | | / \ / \ / \ | + * | (X0, Y0) | / \/ \/ \ | (X1, Y0) + * -- +--------------------------------+ + * |________|_________|_________| + * T1 T2 T3 + * + * P2 Circular pattern with middle at NOZZLE_CLEAN_CIRCLE_MIDDLE. + * "R" specifies the radius. "S" specifies the stroke count. + * Before starting, the nozzle moves to NOZZLE_CLEAN_START_POINT. + * + * Caveats: The ending Z should be the same as starting Z. + * Attention: EXPERIMENTAL. G-code arguments may change. + * + */ //#define NOZZLE_CLEAN_FEATURE #if ENABLED(NOZZLE_CLEAN_FEATURE) @@ -1101,33 +1095,35 @@ #define NOZZLE_CLEAN_GOBACK #endif -// -// Print job timer -// -// Enable this option to automatically start and stop the -// print job timer when M104/M109/M190 commands are received. -// M104 (extruder without wait) - high temp = none, low temp = stop timer -// M109 (extruder with wait) - high temp = start timer, low temp = stop timer -// M190 (bed with wait) - high temp = start timer, low temp = none -// -// In all cases the timer can be started and stopped using -// the following commands: -// -// - M75 - Start the print job timer -// - M76 - Pause the print job timer -// - M77 - Stop the print job timer +/** + * Print Job Timer + * + * Automatically start and stop the print job timer on M104/M109/M190. + * + * 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 + * + * The timer can also be controlled with the following commands: + * + * M75 - Start the print job timer + * M76 - Pause the print job timer + * M77 - Stop the print job timer + */ #define PRINTJOB_TIMER_AUTOSTART -// -// Print Counter -// -// When enabled Marlin will keep track of some print statistical data such as: -// - Total print jobs -// - Total successful print jobs -// - Total failed print jobs -// - Total time printing -// -// This information can be viewed by the M78 command. +/** + * Print Counter + * + * Track statistical data such as: + * + * - Total print jobs + * - Total successful print jobs + * - Total failed print jobs + * - Total time printing + * + * View the current statistics with M78. + */ #define PRINTCOUNTER //============================================================================= @@ -1139,78 +1135,79 @@ // K8200: for Display VM8201 with SD slot #if ENABLED(K8200_VM8201) -// -// LCD LANGUAGE -// -// Here you may choose the language used by Marlin on the LCD menus, the following -// list of languages are available: -// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, -// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test -// -// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } -// +/** + * LCD LANGUAGE + * + * Select the language to display on the LCD. These languages are available: + * + * en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, + * kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test + * + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } + */ #define LCD_LANGUAGE en -// -// LCD Character Set -// -// Note: This option is NOT applicable to Graphical Displays. -// -// All character-based LCD's provide ASCII plus one of these -// language extensions: -// -// - JAPANESE ... the most common -// - WESTERN ... with more accented characters -// - CYRILLIC ... for the Russian language -// -// To determine the language extension installed on your controller: -// -// - Compile and upload with LCD_LANGUAGE set to 'test' -// - Click the controller to view the LCD menu -// - The LCD will display Japanese, Western, or Cyrillic text -// -// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language -// -// :['JAPANESE', 'WESTERN', 'CYRILLIC'] -// +/** + * LCD Character Set + * + * Note: This option is NOT applicable to Graphical Displays. + * + * All character-based LCDs provide ASCII plus one of these + * language extensions: + * + * - JAPANESE ... the most common + * - WESTERN ... with more accented characters + * - CYRILLIC ... for the Russian language + * + * To determine the language extension installed on your controller: + * + * - Compile and upload with LCD_LANGUAGE set to 'test' + * - Click the controller to view the LCD menu + * - The LCD will display Japanese, Western, or Cyrillic text + * + * See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * + * :['JAPANESE', 'WESTERN', 'CYRILLIC'] + */ #define DISPLAY_CHARSET_HD44780 JAPANESE // K8200: for Display VM8201 // this is the most common hardware -// -// LCD TYPE -// -// You may choose ULTRA_LCD if you have character based LCD with 16x2, 16x4, 20x2, -// 20x4 char/lines or DOGLCD for the full graphics display with 128x64 pixels -// (ST7565R family). (This option will be set automatically for certain displays.) -// -// IMPORTANT NOTE: The U8glib library is required for Full Graphic Display! -// https://github.com/olikraus/U8glib_Arduino -// +/** + * LCD TYPE + * + * Enable ULTRA_LCD for a 16x2, 16x4, 20x2, or 20x4 character-based LCD. + * Enable DOGLCD for a 128x64 (ST7565R) Full Graphical Display. + * (These options will be enabled automatically for most displays.) + * + * IMPORTANT: The U8glib library is required for Full Graphic Display! + * https://github.com/olikraus/U8glib_Arduino + */ //#define ULTRA_LCD // Character based //#define DOGLCD // Full graphics display -// -// SD CARD -// -// SD Card support is disabled by default. If your controller has an SD slot, -// you must uncomment the following option or it won't work. -// +/** + * SD CARD + * + * SD Card support is disabled by default. If your controller has an SD slot, + * you must uncomment the following option or it won't work. + * + */ #define SDSUPPORT -// -// SD CARD: SPI SPEED -// -// Uncomment ONE of the following items to use a slower SPI transfer -// speed. This is usually required if you're getting volume init errors. -// +/** + * SD CARD: SPI SPEED + * + * Enable one of the following items for a slower SPI transfer speed. + * This may be required to resolve "volume init" errors. + */ //#define SPI_SPEED SPI_HALF_SPEED //#define SPI_SPEED SPI_QUARTER_SPEED //#define SPI_SPEED SPI_EIGHTH_SPEED -// -// SD CARD: ENABLE CRC -// -// Use CRC checks and retries on the SD communication. -// +/** + * SD CARD: ENABLE CRC + * + * Use CRC checks and retries on the SD communication. + */ #define SD_CHECK_AND_RETRY // @@ -1238,7 +1235,7 @@ */ // -// This option reverses the encoder direction everywhere +// This option reverses the encoder direction everywhere. // // Set this option if CLOCKWISE causes values to DECREASE // diff --git a/Marlin/example_configurations/K8400/Configuration.h b/Marlin/example_configurations/K8400/Configuration.h index 6705dc9fd..1a0bd3e03 100644 --- a/Marlin/example_configurations/K8400/Configuration.h +++ b/Marlin/example_configurations/K8400/Configuration.h @@ -986,23 +986,17 @@ #define PREHEAT_2_TEMP_BED 0 #define PREHEAT_2_FAN_SPEED 165 // Value from 0 to 255 -// -// Nozzle Park -- EXPERIMENTAL -// -// When enabled allows the user to define a special XYZ position, inside the -// machine's topology, to park the nozzle when idle or when receiving the G27 -// command. -// -// The "P" paramenter controls what is the action applied to the Z axis: -// P0: (Default) If current Z-pos is lower than Z-park then the nozzle will -// be raised to reach Z-park height. -// -// P1: No matter the current Z-pos, the nozzle will be raised/lowered to -// reach Z-park height. -// -// P2: The nozzle height will be raised by Z-park amount but never going over -// the machine's limit of Z_MAX_POS. -// +/** + * Nozzle Park -- EXPERIMENTAL + * + * Park the nozzle at the given XYZ position on idle or G27. + * + * The "P" parameter controls the action applied to the Z axis: + * + * P0 (Default) If Z is below park Z raise the nozzle. + * P1 Raise the nozzle always to Z-park height. + * P2 Raise the nozzle by Z-park amount, limited to Z_MAX_POS. + */ //#define NOZZLE_PARK_FEATURE #if ENABLED(NOZZLE_PARK_FEATURE) @@ -1010,44 +1004,44 @@ #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 } #endif -// -// Clean Nozzle Feature -- EXPERIMENTAL -// -// When enabled allows the user to send G12 to start the nozzle cleaning -// process, the G-Code accepts two parameters: -// "P" for pattern selection -// "S" for defining the number of strokes/repetitions -// -// Available list of patterns: -// P0: This is the default pattern, this process requires a sponge type -// material at a fixed bed location. S defines "strokes" i.e. -// back-and-forth movements between the starting and end points. -// -// P1: This starts a zig-zag pattern between (X0, Y0) and (X1, Y1), "T" -// defines the number of zig-zag triangles to be done. "S" defines the -// number of strokes aka one back-and-forth movement. Zig-zags will -// be performed in whichever dimension is smallest. As an example, -// sending "G12 P1 S1 T3" will execute: -// -// -- -// | (X0, Y1) | /\ /\ /\ | (X1, Y1) -// | | / \ / \ / \ | -// A | | / \ / \ / \ | -// | | / \ / \ / \ | -// | (X0, Y0) | / \/ \/ \ | (X1, Y0) -// -- +--------------------------------+ -// |________|_________|_________| -// T1 T2 T3 -// -// P2: This starts a circular pattern with circle with middle in -// NOZZLE_CLEAN_CIRCLE_MIDDLE radius of R and stroke count of S. -// Before starting the circle nozzle goes to NOZZLE_CLEAN_START_POINT. -// -// Caveats: End point Z should use the same value as Start point Z. -// -// Attention: This is an EXPERIMENTAL feature, in the future the G-code arguments -// may change to add new functionality like different wipe patterns. -// +/** + * Clean Nozzle Feature -- EXPERIMENTAL + * + * Adds the G12 command to perform a nozzle cleaning process. + * + * Parameters: + * P Pattern + * S Strokes / Repetitions + * T Triangles (P1 only) + * + * Patterns: + * P0 Straight line (default). This process requires a sponge type material + * at a fixed bed location. "S" specifies strokes (i.e. back-forth motions) + * between the start / end points. + * + * P1 Zig-zag pattern between (X0, Y0) and (X1, Y1), "T" specifies the + * number of zig-zag triangles to do. "S" defines the number of strokes. + * Zig-zags are done in whichever is the narrower dimension. + * For example, "G12 P1 S1 T3" will execute: + * + * -- + * | (X0, Y1) | /\ /\ /\ | (X1, Y1) + * | | / \ / \ / \ | + * A | | / \ / \ / \ | + * | | / \ / \ / \ | + * | (X0, Y0) | / \/ \/ \ | (X1, Y0) + * -- +--------------------------------+ + * |________|_________|_________| + * T1 T2 T3 + * + * P2 Circular pattern with middle at NOZZLE_CLEAN_CIRCLE_MIDDLE. + * "R" specifies the radius. "S" specifies the stroke count. + * Before starting, the nozzle moves to NOZZLE_CLEAN_START_POINT. + * + * Caveats: The ending Z should be the same as starting Z. + * Attention: EXPERIMENTAL. G-code arguments may change. + * + */ //#define NOZZLE_CLEAN_FEATURE #if ENABLED(NOZZLE_CLEAN_FEATURE) @@ -1072,33 +1066,35 @@ #define NOZZLE_CLEAN_GOBACK #endif -// -// Print job timer -// -// Enable this option to automatically start and stop the -// print job timer when M104/M109/M190 commands are received. -// M104 (extruder without wait) - high temp = none, low temp = stop timer -// M109 (extruder with wait) - high temp = start timer, low temp = stop timer -// M190 (bed with wait) - high temp = start timer, low temp = none -// -// In all cases the timer can be started and stopped using -// the following commands: -// -// - M75 - Start the print job timer -// - M76 - Pause the print job timer -// - M77 - Stop the print job timer +/** + * Print Job Timer + * + * Automatically start and stop the print job timer on M104/M109/M190. + * + * 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 + * + * The timer can also be controlled with the following commands: + * + * M75 - Start the print job timer + * M76 - Pause the print job timer + * M77 - Stop the print job timer + */ #define PRINTJOB_TIMER_AUTOSTART -// -// Print Counter -// -// When enabled Marlin will keep track of some print statistical data such as: -// - Total print jobs -// - Total successful print jobs -// - Total failed print jobs -// - Total time printing -// -// This information can be viewed by the M78 command. +/** + * Print Counter + * + * Track statistical data such as: + * + * - Total print jobs + * - Total successful print jobs + * - Total failed print jobs + * - Total time printing + * + * View the current statistics with M78. + */ //#define PRINTCOUNTER //============================================================================= @@ -1107,78 +1103,79 @@ // @section lcd -// -// LCD LANGUAGE -// -// Here you may choose the language used by Marlin on the LCD menus, the following -// list of languages are available: -// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, -// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test -// -// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } -// +/** + * LCD LANGUAGE + * + * Select the language to display on the LCD. These languages are available: + * + * en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, + * kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test + * + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } + */ #define LCD_LANGUAGE en -// -// LCD Character Set -// -// Note: This option is NOT applicable to Graphical Displays. -// -// All character-based LCD's provide ASCII plus one of these -// language extensions: -// -// - JAPANESE ... the most common -// - WESTERN ... with more accented characters -// - CYRILLIC ... for the Russian language -// -// To determine the language extension installed on your controller: -// -// - Compile and upload with LCD_LANGUAGE set to 'test' -// - Click the controller to view the LCD menu -// - The LCD will display Japanese, Western, or Cyrillic text -// -// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language -// -// :['JAPANESE', 'WESTERN', 'CYRILLIC'] -// +/** + * LCD Character Set + * + * Note: This option is NOT applicable to Graphical Displays. + * + * All character-based LCDs provide ASCII plus one of these + * language extensions: + * + * - JAPANESE ... the most common + * - WESTERN ... with more accented characters + * - CYRILLIC ... for the Russian language + * + * To determine the language extension installed on your controller: + * + * - Compile and upload with LCD_LANGUAGE set to 'test' + * - Click the controller to view the LCD menu + * - The LCD will display Japanese, Western, or Cyrillic text + * + * See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * + * :['JAPANESE', 'WESTERN', 'CYRILLIC'] + */ #define DISPLAY_CHARSET_HD44780 JAPANESE -// -// LCD TYPE -// -// You may choose ULTRA_LCD if you have character based LCD with 16x2, 16x4, 20x2, -// 20x4 char/lines or DOGLCD for the full graphics display with 128x64 pixels -// (ST7565R family). (This option will be set automatically for certain displays.) -// -// IMPORTANT NOTE: The U8glib library is required for Full Graphic Display! -// https://github.com/olikraus/U8glib_Arduino -// +/** + * LCD TYPE + * + * Enable ULTRA_LCD for a 16x2, 16x4, 20x2, or 20x4 character-based LCD. + * Enable DOGLCD for a 128x64 (ST7565R) Full Graphical Display. + * (These options will be enabled automatically for most displays.) + * + * IMPORTANT: The U8glib library is required for Full Graphic Display! + * https://github.com/olikraus/U8glib_Arduino + */ #define ULTRA_LCD // Character based //#define DOGLCD // Full graphics display -// -// SD CARD -// -// SD Card support is disabled by default. If your controller has an SD slot, -// you must uncomment the following option or it won't work. -// +/** + * SD CARD + * + * SD Card support is disabled by default. If your controller has an SD slot, + * you must uncomment the following option or it won't work. + * + */ #define SDSUPPORT -// -// SD CARD: SPI SPEED -// -// Uncomment ONE of the following items to use a slower SPI transfer -// speed. This is usually required if you're getting volume init errors. -// +/** + * SD CARD: SPI SPEED + * + * Enable one of the following items for a slower SPI transfer speed. + * This may be required to resolve "volume init" errors. + */ //#define SPI_SPEED SPI_HALF_SPEED //#define SPI_SPEED SPI_QUARTER_SPEED //#define SPI_SPEED SPI_EIGHTH_SPEED -// -// SD CARD: ENABLE CRC -// -// Use CRC checks and retries on the SD communication. -// +/** + * SD CARD: ENABLE CRC + * + * Use CRC checks and retries on the SD communication. + */ //#define SD_CHECK_AND_RETRY // @@ -1206,7 +1203,7 @@ */ // -// This option reverses the encoder direction everywhere +// This option reverses the encoder direction everywhere. // // Set this option if CLOCKWISE causes values to DECREASE // diff --git a/Marlin/example_configurations/K8400/Dual-head/Configuration.h b/Marlin/example_configurations/K8400/Dual-head/Configuration.h index dd0ab0e12..4d04d6ea6 100644 --- a/Marlin/example_configurations/K8400/Dual-head/Configuration.h +++ b/Marlin/example_configurations/K8400/Dual-head/Configuration.h @@ -986,23 +986,17 @@ #define PREHEAT_2_TEMP_BED 0 #define PREHEAT_2_FAN_SPEED 165 // Value from 0 to 255 -// -// Nozzle Park -- EXPERIMENTAL -// -// When enabled allows the user to define a special XYZ position, inside the -// machine's topology, to park the nozzle when idle or when receiving the G27 -// command. -// -// The "P" paramenter controls what is the action applied to the Z axis: -// P0: (Default) If current Z-pos is lower than Z-park then the nozzle will -// be raised to reach Z-park height. -// -// P1: No matter the current Z-pos, the nozzle will be raised/lowered to -// reach Z-park height. -// -// P2: The nozzle height will be raised by Z-park amount but never going over -// the machine's limit of Z_MAX_POS. -// +/** + * Nozzle Park -- EXPERIMENTAL + * + * Park the nozzle at the given XYZ position on idle or G27. + * + * The "P" parameter controls the action applied to the Z axis: + * + * P0 (Default) If Z is below park Z raise the nozzle. + * P1 Raise the nozzle always to Z-park height. + * P2 Raise the nozzle by Z-park amount, limited to Z_MAX_POS. + */ //#define NOZZLE_PARK_FEATURE #if ENABLED(NOZZLE_PARK_FEATURE) @@ -1010,44 +1004,44 @@ #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 } #endif -// -// Clean Nozzle Feature -- EXPERIMENTAL -// -// When enabled allows the user to send G12 to start the nozzle cleaning -// process, the G-Code accepts two parameters: -// "P" for pattern selection -// "S" for defining the number of strokes/repetitions -// -// Available list of patterns: -// P0: This is the default pattern, this process requires a sponge type -// material at a fixed bed location. S defines "strokes" i.e. -// back-and-forth movements between the starting and end points. -// -// P1: This starts a zig-zag pattern between (X0, Y0) and (X1, Y1), "T" -// defines the number of zig-zag triangles to be done. "S" defines the -// number of strokes aka one back-and-forth movement. Zig-zags will -// be performed in whichever dimension is smallest. As an example, -// sending "G12 P1 S1 T3" will execute: -// -// -- -// | (X0, Y1) | /\ /\ /\ | (X1, Y1) -// | | / \ / \ / \ | -// A | | / \ / \ / \ | -// | | / \ / \ / \ | -// | (X0, Y0) | / \/ \/ \ | (X1, Y0) -// -- +--------------------------------+ -// |________|_________|_________| -// T1 T2 T3 -// -// P2: This starts a circular pattern with circle with middle in -// NOZZLE_CLEAN_CIRCLE_MIDDLE radius of R and stroke count of S. -// Before starting the circle nozzle goes to NOZZLE_CLEAN_START_POINT. -// -// Caveats: End point Z should use the same value as Start point Z. -// -// Attention: This is an EXPERIMENTAL feature, in the future the G-code arguments -// may change to add new functionality like different wipe patterns. -// +/** + * Clean Nozzle Feature -- EXPERIMENTAL + * + * Adds the G12 command to perform a nozzle cleaning process. + * + * Parameters: + * P Pattern + * S Strokes / Repetitions + * T Triangles (P1 only) + * + * Patterns: + * P0 Straight line (default). This process requires a sponge type material + * at a fixed bed location. "S" specifies strokes (i.e. back-forth motions) + * between the start / end points. + * + * P1 Zig-zag pattern between (X0, Y0) and (X1, Y1), "T" specifies the + * number of zig-zag triangles to do. "S" defines the number of strokes. + * Zig-zags are done in whichever is the narrower dimension. + * For example, "G12 P1 S1 T3" will execute: + * + * -- + * | (X0, Y1) | /\ /\ /\ | (X1, Y1) + * | | / \ / \ / \ | + * A | | / \ / \ / \ | + * | | / \ / \ / \ | + * | (X0, Y0) | / \/ \/ \ | (X1, Y0) + * -- +--------------------------------+ + * |________|_________|_________| + * T1 T2 T3 + * + * P2 Circular pattern with middle at NOZZLE_CLEAN_CIRCLE_MIDDLE. + * "R" specifies the radius. "S" specifies the stroke count. + * Before starting, the nozzle moves to NOZZLE_CLEAN_START_POINT. + * + * Caveats: The ending Z should be the same as starting Z. + * Attention: EXPERIMENTAL. G-code arguments may change. + * + */ //#define NOZZLE_CLEAN_FEATURE #if ENABLED(NOZZLE_CLEAN_FEATURE) @@ -1072,33 +1066,35 @@ #define NOZZLE_CLEAN_GOBACK #endif -// -// Print job timer -// -// Enable this option to automatically start and stop the -// print job timer when M104/M109/M190 commands are received. -// M104 (extruder without wait) - high temp = none, low temp = stop timer -// M109 (extruder with wait) - high temp = start timer, low temp = stop timer -// M190 (bed with wait) - high temp = start timer, low temp = none -// -// In all cases the timer can be started and stopped using -// the following commands: -// -// - M75 - Start the print job timer -// - M76 - Pause the print job timer -// - M77 - Stop the print job timer +/** + * Print Job Timer + * + * Automatically start and stop the print job timer on M104/M109/M190. + * + * 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 + * + * The timer can also be controlled with the following commands: + * + * M75 - Start the print job timer + * M76 - Pause the print job timer + * M77 - Stop the print job timer + */ #define PRINTJOB_TIMER_AUTOSTART -// -// Print Counter -// -// When enabled Marlin will keep track of some print statistical data such as: -// - Total print jobs -// - Total successful print jobs -// - Total failed print jobs -// - Total time printing -// -// This information can be viewed by the M78 command. +/** + * Print Counter + * + * Track statistical data such as: + * + * - Total print jobs + * - Total successful print jobs + * - Total failed print jobs + * - Total time printing + * + * View the current statistics with M78. + */ //#define PRINTCOUNTER //============================================================================= @@ -1107,78 +1103,79 @@ // @section lcd -// -// LCD LANGUAGE -// -// Here you may choose the language used by Marlin on the LCD menus, the following -// list of languages are available: -// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, -// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test -// -// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } -// +/** + * LCD LANGUAGE + * + * Select the language to display on the LCD. These languages are available: + * + * en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, + * kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test + * + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } + */ #define LCD_LANGUAGE en -// -// LCD Character Set -// -// Note: This option is NOT applicable to Graphical Displays. -// -// All character-based LCD's provide ASCII plus one of these -// language extensions: -// -// - JAPANESE ... the most common -// - WESTERN ... with more accented characters -// - CYRILLIC ... for the Russian language -// -// To determine the language extension installed on your controller: -// -// - Compile and upload with LCD_LANGUAGE set to 'test' -// - Click the controller to view the LCD menu -// - The LCD will display Japanese, Western, or Cyrillic text -// -// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language -// -// :['JAPANESE', 'WESTERN', 'CYRILLIC'] -// +/** + * LCD Character Set + * + * Note: This option is NOT applicable to Graphical Displays. + * + * All character-based LCDs provide ASCII plus one of these + * language extensions: + * + * - JAPANESE ... the most common + * - WESTERN ... with more accented characters + * - CYRILLIC ... for the Russian language + * + * To determine the language extension installed on your controller: + * + * - Compile and upload with LCD_LANGUAGE set to 'test' + * - Click the controller to view the LCD menu + * - The LCD will display Japanese, Western, or Cyrillic text + * + * See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * + * :['JAPANESE', 'WESTERN', 'CYRILLIC'] + */ #define DISPLAY_CHARSET_HD44780 JAPANESE -// -// LCD TYPE -// -// You may choose ULTRA_LCD if you have character based LCD with 16x2, 16x4, 20x2, -// 20x4 char/lines or DOGLCD for the full graphics display with 128x64 pixels -// (ST7565R family). (This option will be set automatically for certain displays.) -// -// IMPORTANT NOTE: The U8glib library is required for Full Graphic Display! -// https://github.com/olikraus/U8glib_Arduino -// +/** + * LCD TYPE + * + * Enable ULTRA_LCD for a 16x2, 16x4, 20x2, or 20x4 character-based LCD. + * Enable DOGLCD for a 128x64 (ST7565R) Full Graphical Display. + * (These options will be enabled automatically for most displays.) + * + * IMPORTANT: The U8glib library is required for Full Graphic Display! + * https://github.com/olikraus/U8glib_Arduino + */ #define ULTRA_LCD // Character based //#define DOGLCD // Full graphics display -// -// SD CARD -// -// SD Card support is disabled by default. If your controller has an SD slot, -// you must uncomment the following option or it won't work. -// +/** + * SD CARD + * + * SD Card support is disabled by default. If your controller has an SD slot, + * you must uncomment the following option or it won't work. + * + */ #define SDSUPPORT -// -// SD CARD: SPI SPEED -// -// Uncomment ONE of the following items to use a slower SPI transfer -// speed. This is usually required if you're getting volume init errors. -// +/** + * SD CARD: SPI SPEED + * + * Enable one of the following items for a slower SPI transfer speed. + * This may be required to resolve "volume init" errors. + */ //#define SPI_SPEED SPI_HALF_SPEED //#define SPI_SPEED SPI_QUARTER_SPEED //#define SPI_SPEED SPI_EIGHTH_SPEED -// -// SD CARD: ENABLE CRC -// -// Use CRC checks and retries on the SD communication. -// +/** + * SD CARD: ENABLE CRC + * + * Use CRC checks and retries on the SD communication. + */ //#define SD_CHECK_AND_RETRY // @@ -1206,7 +1203,7 @@ */ // -// This option reverses the encoder direction everywhere +// This option reverses the encoder direction everywhere. // // Set this option if CLOCKWISE causes values to DECREASE // diff --git a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h index aff721065..1b18f8ba9 100644 --- a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h +++ b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h @@ -986,23 +986,17 @@ #define PREHEAT_2_TEMP_BED 110 #define PREHEAT_2_FAN_SPEED 0 // Value from 0 to 255 -// -// Nozzle Park -- EXPERIMENTAL -// -// When enabled allows the user to define a special XYZ position, inside the -// machine's topology, to park the nozzle when idle or when receiving the G27 -// command. -// -// The "P" paramenter controls what is the action applied to the Z axis: -// P0: (Default) If current Z-pos is lower than Z-park then the nozzle will -// be raised to reach Z-park height. -// -// P1: No matter the current Z-pos, the nozzle will be raised/lowered to -// reach Z-park height. -// -// P2: The nozzle height will be raised by Z-park amount but never going over -// the machine's limit of Z_MAX_POS. -// +/** + * Nozzle Park -- EXPERIMENTAL + * + * Park the nozzle at the given XYZ position on idle or G27. + * + * The "P" parameter controls the action applied to the Z axis: + * + * P0 (Default) If Z is below park Z raise the nozzle. + * P1 Raise the nozzle always to Z-park height. + * P2 Raise the nozzle by Z-park amount, limited to Z_MAX_POS. + */ //#define NOZZLE_PARK_FEATURE #if ENABLED(NOZZLE_PARK_FEATURE) @@ -1010,44 +1004,44 @@ #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 } #endif -// -// Clean Nozzle Feature -- EXPERIMENTAL -// -// When enabled allows the user to send G12 to start the nozzle cleaning -// process, the G-Code accepts two parameters: -// "P" for pattern selection -// "S" for defining the number of strokes/repetitions -// -// Available list of patterns: -// P0: This is the default pattern, this process requires a sponge type -// material at a fixed bed location. S defines "strokes" i.e. -// back-and-forth movements between the starting and end points. -// -// P1: This starts a zig-zag pattern between (X0, Y0) and (X1, Y1), "T" -// defines the number of zig-zag triangles to be done. "S" defines the -// number of strokes aka one back-and-forth movement. Zig-zags will -// be performed in whichever dimension is smallest. As an example, -// sending "G12 P1 S1 T3" will execute: -// -// -- -// | (X0, Y1) | /\ /\ /\ | (X1, Y1) -// | | / \ / \ / \ | -// A | | / \ / \ / \ | -// | | / \ / \ / \ | -// | (X0, Y0) | / \/ \/ \ | (X1, Y0) -// -- +--------------------------------+ -// |________|_________|_________| -// T1 T2 T3 -// -// P2: This starts a circular pattern with circle with middle in -// NOZZLE_CLEAN_CIRCLE_MIDDLE radius of R and stroke count of S. -// Before starting the circle nozzle goes to NOZZLE_CLEAN_START_POINT. -// -// Caveats: End point Z should use the same value as Start point Z. -// -// Attention: This is an EXPERIMENTAL feature, in the future the G-code arguments -// may change to add new functionality like different wipe patterns. -// +/** + * Clean Nozzle Feature -- EXPERIMENTAL + * + * Adds the G12 command to perform a nozzle cleaning process. + * + * Parameters: + * P Pattern + * S Strokes / Repetitions + * T Triangles (P1 only) + * + * Patterns: + * P0 Straight line (default). This process requires a sponge type material + * at a fixed bed location. "S" specifies strokes (i.e. back-forth motions) + * between the start / end points. + * + * P1 Zig-zag pattern between (X0, Y0) and (X1, Y1), "T" specifies the + * number of zig-zag triangles to do. "S" defines the number of strokes. + * Zig-zags are done in whichever is the narrower dimension. + * For example, "G12 P1 S1 T3" will execute: + * + * -- + * | (X0, Y1) | /\ /\ /\ | (X1, Y1) + * | | / \ / \ / \ | + * A | | / \ / \ / \ | + * | | / \ / \ / \ | + * | (X0, Y0) | / \/ \/ \ | (X1, Y0) + * -- +--------------------------------+ + * |________|_________|_________| + * T1 T2 T3 + * + * P2 Circular pattern with middle at NOZZLE_CLEAN_CIRCLE_MIDDLE. + * "R" specifies the radius. "S" specifies the stroke count. + * Before starting, the nozzle moves to NOZZLE_CLEAN_START_POINT. + * + * Caveats: The ending Z should be the same as starting Z. + * Attention: EXPERIMENTAL. G-code arguments may change. + * + */ //#define NOZZLE_CLEAN_FEATURE #if ENABLED(NOZZLE_CLEAN_FEATURE) @@ -1072,33 +1066,35 @@ #define NOZZLE_CLEAN_GOBACK #endif -// -// Print job timer -// -// Enable this option to automatically start and stop the -// print job timer when M104/M109/M190 commands are received. -// M104 (extruder without wait) - high temp = none, low temp = stop timer -// M109 (extruder with wait) - high temp = start timer, low temp = stop timer -// M190 (bed with wait) - high temp = start timer, low temp = none -// -// In all cases the timer can be started and stopped using -// the following commands: -// -// - M75 - Start the print job timer -// - M76 - Pause the print job timer -// - M77 - Stop the print job timer +/** + * Print Job Timer + * + * Automatically start and stop the print job timer on M104/M109/M190. + * + * 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 + * + * The timer can also be controlled with the following commands: + * + * M75 - Start the print job timer + * M76 - Pause the print job timer + * M77 - Stop the print job timer + */ #define PRINTJOB_TIMER_AUTOSTART -// -// Print Counter -// -// When enabled Marlin will keep track of some print statistical data such as: -// - Total print jobs -// - Total successful print jobs -// - Total failed print jobs -// - Total time printing -// -// This information can be viewed by the M78 command. +/** + * Print Counter + * + * Track statistical data such as: + * + * - Total print jobs + * - Total successful print jobs + * - Total failed print jobs + * - Total time printing + * + * View the current statistics with M78. + */ //#define PRINTCOUNTER //============================================================================= @@ -1107,78 +1103,79 @@ // @section lcd -// -// LCD LANGUAGE -// -// Here you may choose the language used by Marlin on the LCD menus, the following -// list of languages are available: -// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, -// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test -// -// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } -// +/** + * LCD LANGUAGE + * + * Select the language to display on the LCD. These languages are available: + * + * en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, + * kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test + * + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } + */ #define LCD_LANGUAGE en -// -// LCD Character Set -// -// Note: This option is NOT applicable to Graphical Displays. -// -// All character-based LCD's provide ASCII plus one of these -// language extensions: -// -// - JAPANESE ... the most common -// - WESTERN ... with more accented characters -// - CYRILLIC ... for the Russian language -// -// To determine the language extension installed on your controller: -// -// - Compile and upload with LCD_LANGUAGE set to 'test' -// - Click the controller to view the LCD menu -// - The LCD will display Japanese, Western, or Cyrillic text -// -// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language -// -// :['JAPANESE', 'WESTERN', 'CYRILLIC'] -// +/** + * LCD Character Set + * + * Note: This option is NOT applicable to Graphical Displays. + * + * All character-based LCDs provide ASCII plus one of these + * language extensions: + * + * - JAPANESE ... the most common + * - WESTERN ... with more accented characters + * - CYRILLIC ... for the Russian language + * + * To determine the language extension installed on your controller: + * + * - Compile and upload with LCD_LANGUAGE set to 'test' + * - Click the controller to view the LCD menu + * - The LCD will display Japanese, Western, or Cyrillic text + * + * See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * + * :['JAPANESE', 'WESTERN', 'CYRILLIC'] + */ #define DISPLAY_CHARSET_HD44780 JAPANESE -// -// LCD TYPE -// -// You may choose ULTRA_LCD if you have character based LCD with 16x2, 16x4, 20x2, -// 20x4 char/lines or DOGLCD for the full graphics display with 128x64 pixels -// (ST7565R family). (This option will be set automatically for certain displays.) -// -// IMPORTANT NOTE: The U8glib library is required for Full Graphic Display! -// https://github.com/olikraus/U8glib_Arduino -// +/** + * LCD TYPE + * + * Enable ULTRA_LCD for a 16x2, 16x4, 20x2, or 20x4 character-based LCD. + * Enable DOGLCD for a 128x64 (ST7565R) Full Graphical Display. + * (These options will be enabled automatically for most displays.) + * + * IMPORTANT: The U8glib library is required for Full Graphic Display! + * https://github.com/olikraus/U8glib_Arduino + */ #define ULTRA_LCD // Character based //#define DOGLCD // Full graphics display -// -// SD CARD -// -// SD Card support is disabled by default. If your controller has an SD slot, -// you must uncomment the following option or it won't work. -// +/** + * SD CARD + * + * SD Card support is disabled by default. If your controller has an SD slot, + * you must uncomment the following option or it won't work. + * + */ #define SDSUPPORT -// -// SD CARD: SPI SPEED -// -// Uncomment ONE of the following items to use a slower SPI transfer -// speed. This is usually required if you're getting volume init errors. -// +/** + * SD CARD: SPI SPEED + * + * Enable one of the following items for a slower SPI transfer speed. + * This may be required to resolve "volume init" errors. + */ //#define SPI_SPEED SPI_HALF_SPEED //#define SPI_SPEED SPI_QUARTER_SPEED //#define SPI_SPEED SPI_EIGHTH_SPEED -// -// SD CARD: ENABLE CRC -// -// Use CRC checks and retries on the SD communication. -// +/** + * SD CARD: ENABLE CRC + * + * Use CRC checks and retries on the SD communication. + */ #define SD_CHECK_AND_RETRY // @@ -1206,7 +1203,7 @@ */ // -// This option reverses the encoder direction everywhere +// This option reverses the encoder direction everywhere. // // Set this option if CLOCKWISE causes values to DECREASE // diff --git a/Marlin/example_configurations/RigidBot/Configuration.h b/Marlin/example_configurations/RigidBot/Configuration.h index d90db6f6e..4a109a5c9 100644 --- a/Marlin/example_configurations/RigidBot/Configuration.h +++ b/Marlin/example_configurations/RigidBot/Configuration.h @@ -985,23 +985,17 @@ #define PREHEAT_2_TEMP_BED 110 #define PREHEAT_2_FAN_SPEED 255 // Value from 0 to 255 -// -// Nozzle Park -- EXPERIMENTAL -// -// When enabled allows the user to define a special XYZ position, inside the -// machine's topology, to park the nozzle when idle or when receiving the G27 -// command. -// -// The "P" paramenter controls what is the action applied to the Z axis: -// P0: (Default) If current Z-pos is lower than Z-park then the nozzle will -// be raised to reach Z-park height. -// -// P1: No matter the current Z-pos, the nozzle will be raised/lowered to -// reach Z-park height. -// -// P2: The nozzle height will be raised by Z-park amount but never going over -// the machine's limit of Z_MAX_POS. -// +/** + * Nozzle Park -- EXPERIMENTAL + * + * Park the nozzle at the given XYZ position on idle or G27. + * + * The "P" parameter controls the action applied to the Z axis: + * + * P0 (Default) If Z is below park Z raise the nozzle. + * P1 Raise the nozzle always to Z-park height. + * P2 Raise the nozzle by Z-park amount, limited to Z_MAX_POS. + */ //#define NOZZLE_PARK_FEATURE #if ENABLED(NOZZLE_PARK_FEATURE) @@ -1009,44 +1003,44 @@ #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 } #endif -// -// Clean Nozzle Feature -- EXPERIMENTAL -// -// When enabled allows the user to send G12 to start the nozzle cleaning -// process, the G-Code accepts two parameters: -// "P" for pattern selection -// "S" for defining the number of strokes/repetitions -// -// Available list of patterns: -// P0: This is the default pattern, this process requires a sponge type -// material at a fixed bed location. S defines "strokes" i.e. -// back-and-forth movements between the starting and end points. -// -// P1: This starts a zig-zag pattern between (X0, Y0) and (X1, Y1), "T" -// defines the number of zig-zag triangles to be done. "S" defines the -// number of strokes aka one back-and-forth movement. Zig-zags will -// be performed in whichever dimension is smallest. As an example, -// sending "G12 P1 S1 T3" will execute: -// -// -- -// | (X0, Y1) | /\ /\ /\ | (X1, Y1) -// | | / \ / \ / \ | -// A | | / \ / \ / \ | -// | | / \ / \ / \ | -// | (X0, Y0) | / \/ \/ \ | (X1, Y0) -// -- +--------------------------------+ -// |________|_________|_________| -// T1 T2 T3 -// -// P2: This starts a circular pattern with circle with middle in -// NOZZLE_CLEAN_CIRCLE_MIDDLE radius of R and stroke count of S. -// Before starting the circle nozzle goes to NOZZLE_CLEAN_START_POINT. -// -// Caveats: End point Z should use the same value as Start point Z. -// -// Attention: This is an EXPERIMENTAL feature, in the future the G-code arguments -// may change to add new functionality like different wipe patterns. -// +/** + * Clean Nozzle Feature -- EXPERIMENTAL + * + * Adds the G12 command to perform a nozzle cleaning process. + * + * Parameters: + * P Pattern + * S Strokes / Repetitions + * T Triangles (P1 only) + * + * Patterns: + * P0 Straight line (default). This process requires a sponge type material + * at a fixed bed location. "S" specifies strokes (i.e. back-forth motions) + * between the start / end points. + * + * P1 Zig-zag pattern between (X0, Y0) and (X1, Y1), "T" specifies the + * number of zig-zag triangles to do. "S" defines the number of strokes. + * Zig-zags are done in whichever is the narrower dimension. + * For example, "G12 P1 S1 T3" will execute: + * + * -- + * | (X0, Y1) | /\ /\ /\ | (X1, Y1) + * | | / \ / \ / \ | + * A | | / \ / \ / \ | + * | | / \ / \ / \ | + * | (X0, Y0) | / \/ \/ \ | (X1, Y0) + * -- +--------------------------------+ + * |________|_________|_________| + * T1 T2 T3 + * + * P2 Circular pattern with middle at NOZZLE_CLEAN_CIRCLE_MIDDLE. + * "R" specifies the radius. "S" specifies the stroke count. + * Before starting, the nozzle moves to NOZZLE_CLEAN_START_POINT. + * + * Caveats: The ending Z should be the same as starting Z. + * Attention: EXPERIMENTAL. G-code arguments may change. + * + */ //#define NOZZLE_CLEAN_FEATURE #if ENABLED(NOZZLE_CLEAN_FEATURE) @@ -1071,33 +1065,35 @@ #define NOZZLE_CLEAN_GOBACK #endif -// -// Print job timer -// -// Enable this option to automatically start and stop the -// print job timer when M104/M109/M190 commands are received. -// M104 (extruder without wait) - high temp = none, low temp = stop timer -// M109 (extruder with wait) - high temp = start timer, low temp = stop timer -// M190 (bed with wait) - high temp = start timer, low temp = none -// -// In all cases the timer can be started and stopped using -// the following commands: -// -// - M75 - Start the print job timer -// - M76 - Pause the print job timer -// - M77 - Stop the print job timer +/** + * Print Job Timer + * + * Automatically start and stop the print job timer on M104/M109/M190. + * + * 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 + * + * The timer can also be controlled with the following commands: + * + * M75 - Start the print job timer + * M76 - Pause the print job timer + * M77 - Stop the print job timer + */ #define PRINTJOB_TIMER_AUTOSTART -// -// Print Counter -// -// When enabled Marlin will keep track of some print statistical data such as: -// - Total print jobs -// - Total successful print jobs -// - Total failed print jobs -// - Total time printing -// -// This information can be viewed by the M78 command. +/** + * Print Counter + * + * Track statistical data such as: + * + * - Total print jobs + * - Total successful print jobs + * - Total failed print jobs + * - Total time printing + * + * View the current statistics with M78. + */ //#define PRINTCOUNTER //============================================================================= @@ -1106,78 +1102,79 @@ // @section lcd -// -// LCD LANGUAGE -// -// Here you may choose the language used by Marlin on the LCD menus, the following -// list of languages are available: -// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, -// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test -// -// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } -// +/** + * LCD LANGUAGE + * + * Select the language to display on the LCD. These languages are available: + * + * en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, + * kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test + * + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } + */ #define LCD_LANGUAGE en -// -// LCD Character Set -// -// Note: This option is NOT applicable to Graphical Displays. -// -// All character-based LCD's provide ASCII plus one of these -// language extensions: -// -// - JAPANESE ... the most common -// - WESTERN ... with more accented characters -// - CYRILLIC ... for the Russian language -// -// To determine the language extension installed on your controller: -// -// - Compile and upload with LCD_LANGUAGE set to 'test' -// - Click the controller to view the LCD menu -// - The LCD will display Japanese, Western, or Cyrillic text -// -// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language -// -// :['JAPANESE', 'WESTERN', 'CYRILLIC'] -// +/** + * LCD Character Set + * + * Note: This option is NOT applicable to Graphical Displays. + * + * All character-based LCDs provide ASCII plus one of these + * language extensions: + * + * - JAPANESE ... the most common + * - WESTERN ... with more accented characters + * - CYRILLIC ... for the Russian language + * + * To determine the language extension installed on your controller: + * + * - Compile and upload with LCD_LANGUAGE set to 'test' + * - Click the controller to view the LCD menu + * - The LCD will display Japanese, Western, or Cyrillic text + * + * See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * + * :['JAPANESE', 'WESTERN', 'CYRILLIC'] + */ #define DISPLAY_CHARSET_HD44780 JAPANESE -// -// LCD TYPE -// -// You may choose ULTRA_LCD if you have character based LCD with 16x2, 16x4, 20x2, -// 20x4 char/lines or DOGLCD for the full graphics display with 128x64 pixels -// (ST7565R family). (This option will be set automatically for certain displays.) -// -// IMPORTANT NOTE: The U8glib library is required for Full Graphic Display! -// https://github.com/olikraus/U8glib_Arduino -// +/** + * LCD TYPE + * + * Enable ULTRA_LCD for a 16x2, 16x4, 20x2, or 20x4 character-based LCD. + * Enable DOGLCD for a 128x64 (ST7565R) Full Graphical Display. + * (These options will be enabled automatically for most displays.) + * + * IMPORTANT: The U8glib library is required for Full Graphic Display! + * https://github.com/olikraus/U8glib_Arduino + */ //#define ULTRA_LCD // Character based //#define DOGLCD // Full graphics display -// -// SD CARD -// -// SD Card support is disabled by default. If your controller has an SD slot, -// you must uncomment the following option or it won't work. -// +/** + * SD CARD + * + * SD Card support is disabled by default. If your controller has an SD slot, + * you must uncomment the following option or it won't work. + * + */ #define SDSUPPORT -// -// SD CARD: SPI SPEED -// -// Uncomment ONE of the following items to use a slower SPI transfer -// speed. This is usually required if you're getting volume init errors. -// +/** + * SD CARD: SPI SPEED + * + * Enable one of the following items for a slower SPI transfer speed. + * This may be required to resolve "volume init" errors. + */ //#define SPI_SPEED SPI_HALF_SPEED //#define SPI_SPEED SPI_QUARTER_SPEED #define SPI_SPEED SPI_EIGHTH_SPEED -// -// SD CARD: ENABLE CRC -// -// Use CRC checks and retries on the SD communication. -// +/** + * SD CARD: ENABLE CRC + * + * Use CRC checks and retries on the SD communication. + */ //#define SD_CHECK_AND_RETRY // @@ -1205,7 +1202,7 @@ */ // -// This option reverses the encoder direction everywhere +// This option reverses the encoder direction everywhere. // // Set this option if CLOCKWISE causes values to DECREASE // diff --git a/Marlin/example_configurations/SCARA/Configuration.h b/Marlin/example_configurations/SCARA/Configuration.h index 55d991b20..63bc0f333 100644 --- a/Marlin/example_configurations/SCARA/Configuration.h +++ b/Marlin/example_configurations/SCARA/Configuration.h @@ -1001,23 +1001,17 @@ #define PREHEAT_2_TEMP_BED 100 #define PREHEAT_2_FAN_SPEED 255 // Value from 0 to 255 -// -// Nozzle Park -- EXPERIMENTAL -// -// When enabled allows the user to define a special XYZ position, inside the -// machine's topology, to park the nozzle when idle or when receiving the G27 -// command. -// -// The "P" paramenter controls what is the action applied to the Z axis: -// P0: (Default) If current Z-pos is lower than Z-park then the nozzle will -// be raised to reach Z-park height. -// -// P1: No matter the current Z-pos, the nozzle will be raised/lowered to -// reach Z-park height. -// -// P2: The nozzle height will be raised by Z-park amount but never going over -// the machine's limit of Z_MAX_POS. -// +/** + * Nozzle Park -- EXPERIMENTAL + * + * Park the nozzle at the given XYZ position on idle or G27. + * + * The "P" parameter controls the action applied to the Z axis: + * + * P0 (Default) If Z is below park Z raise the nozzle. + * P1 Raise the nozzle always to Z-park height. + * P2 Raise the nozzle by Z-park amount, limited to Z_MAX_POS. + */ //#define NOZZLE_PARK_FEATURE #if ENABLED(NOZZLE_PARK_FEATURE) @@ -1025,44 +1019,44 @@ #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 } #endif -// -// Clean Nozzle Feature -- EXPERIMENTAL -// -// When enabled allows the user to send G12 to start the nozzle cleaning -// process, the G-Code accepts two parameters: -// "P" for pattern selection -// "S" for defining the number of strokes/repetitions -// -// Available list of patterns: -// P0: This is the default pattern, this process requires a sponge type -// material at a fixed bed location. S defines "strokes" i.e. -// back-and-forth movements between the starting and end points. -// -// P1: This starts a zig-zag pattern between (X0, Y0) and (X1, Y1), "T" -// defines the number of zig-zag triangles to be done. "S" defines the -// number of strokes aka one back-and-forth movement. Zig-zags will -// be performed in whichever dimension is smallest. As an example, -// sending "G12 P1 S1 T3" will execute: -// -// -- -// | (X0, Y1) | /\ /\ /\ | (X1, Y1) -// | | / \ / \ / \ | -// A | | / \ / \ / \ | -// | | / \ / \ / \ | -// | (X0, Y0) | / \/ \/ \ | (X1, Y0) -// -- +--------------------------------+ -// |________|_________|_________| -// T1 T2 T3 -// -// P2: This starts a circular pattern with circle with middle in -// NOZZLE_CLEAN_CIRCLE_MIDDLE radius of R and stroke count of S. -// Before starting the circle nozzle goes to NOZZLE_CLEAN_START_POINT. -// -// Caveats: End point Z should use the same value as Start point Z. -// -// Attention: This is an EXPERIMENTAL feature, in the future the G-code arguments -// may change to add new functionality like different wipe patterns. -// +/** + * Clean Nozzle Feature -- EXPERIMENTAL + * + * Adds the G12 command to perform a nozzle cleaning process. + * + * Parameters: + * P Pattern + * S Strokes / Repetitions + * T Triangles (P1 only) + * + * Patterns: + * P0 Straight line (default). This process requires a sponge type material + * at a fixed bed location. "S" specifies strokes (i.e. back-forth motions) + * between the start / end points. + * + * P1 Zig-zag pattern between (X0, Y0) and (X1, Y1), "T" specifies the + * number of zig-zag triangles to do. "S" defines the number of strokes. + * Zig-zags are done in whichever is the narrower dimension. + * For example, "G12 P1 S1 T3" will execute: + * + * -- + * | (X0, Y1) | /\ /\ /\ | (X1, Y1) + * | | / \ / \ / \ | + * A | | / \ / \ / \ | + * | | / \ / \ / \ | + * | (X0, Y0) | / \/ \/ \ | (X1, Y0) + * -- +--------------------------------+ + * |________|_________|_________| + * T1 T2 T3 + * + * P2 Circular pattern with middle at NOZZLE_CLEAN_CIRCLE_MIDDLE. + * "R" specifies the radius. "S" specifies the stroke count. + * Before starting, the nozzle moves to NOZZLE_CLEAN_START_POINT. + * + * Caveats: The ending Z should be the same as starting Z. + * Attention: EXPERIMENTAL. G-code arguments may change. + * + */ //#define NOZZLE_CLEAN_FEATURE #if ENABLED(NOZZLE_CLEAN_FEATURE) @@ -1087,33 +1081,35 @@ #define NOZZLE_CLEAN_GOBACK #endif -// -// Print job timer -// -// Enable this option to automatically start and stop the -// print job timer when M104/M109/M190 commands are received. -// M104 (extruder without wait) - high temp = none, low temp = stop timer -// M109 (extruder with wait) - high temp = start timer, low temp = stop timer -// M190 (bed with wait) - high temp = start timer, low temp = none -// -// In all cases the timer can be started and stopped using -// the following commands: -// -// - M75 - Start the print job timer -// - M76 - Pause the print job timer -// - M77 - Stop the print job timer +/** + * Print Job Timer + * + * Automatically start and stop the print job timer on M104/M109/M190. + * + * 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 + * + * The timer can also be controlled with the following commands: + * + * M75 - Start the print job timer + * M76 - Pause the print job timer + * M77 - Stop the print job timer + */ #define PRINTJOB_TIMER_AUTOSTART -// -// Print Counter -// -// When enabled Marlin will keep track of some print statistical data such as: -// - Total print jobs -// - Total successful print jobs -// - Total failed print jobs -// - Total time printing -// -// This information can be viewed by the M78 command. +/** + * Print Counter + * + * Track statistical data such as: + * + * - Total print jobs + * - Total successful print jobs + * - Total failed print jobs + * - Total time printing + * + * View the current statistics with M78. + */ //#define PRINTCOUNTER //============================================================================= @@ -1122,78 +1118,79 @@ // @section lcd -// -// LCD LANGUAGE -// -// Here you may choose the language used by Marlin on the LCD menus, the following -// list of languages are available: -// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, -// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test -// -// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } -// +/** + * LCD LANGUAGE + * + * Select the language to display on the LCD. These languages are available: + * + * en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, + * kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test + * + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } + */ //#define LCD_LANGUAGE en -// -// LCD Character Set -// -// Note: This option is NOT applicable to Graphical Displays. -// -// All character-based LCD's provide ASCII plus one of these -// language extensions: -// -// - JAPANESE ... the most common -// - WESTERN ... with more accented characters -// - CYRILLIC ... for the Russian language -// -// To determine the language extension installed on your controller: -// -// - Compile and upload with LCD_LANGUAGE set to 'test' -// - Click the controller to view the LCD menu -// - The LCD will display Japanese, Western, or Cyrillic text -// -// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language -// -// :['JAPANESE', 'WESTERN', 'CYRILLIC'] -// +/** + * LCD Character Set + * + * Note: This option is NOT applicable to Graphical Displays. + * + * All character-based LCDs provide ASCII plus one of these + * language extensions: + * + * - JAPANESE ... the most common + * - WESTERN ... with more accented characters + * - CYRILLIC ... for the Russian language + * + * To determine the language extension installed on your controller: + * + * - Compile and upload with LCD_LANGUAGE set to 'test' + * - Click the controller to view the LCD menu + * - The LCD will display Japanese, Western, or Cyrillic text + * + * See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * + * :['JAPANESE', 'WESTERN', 'CYRILLIC'] + */ #define DISPLAY_CHARSET_HD44780 JAPANESE -// -// LCD TYPE -// -// You may choose ULTRA_LCD if you have character based LCD with 16x2, 16x4, 20x2, -// 20x4 char/lines or DOGLCD for the full graphics display with 128x64 pixels -// (ST7565R family). (This option will be set automatically for certain displays.) -// -// IMPORTANT NOTE: The U8glib library is required for Full Graphic Display! -// https://github.com/olikraus/U8glib_Arduino -// +/** + * LCD TYPE + * + * Enable ULTRA_LCD for a 16x2, 16x4, 20x2, or 20x4 character-based LCD. + * Enable DOGLCD for a 128x64 (ST7565R) Full Graphical Display. + * (These options will be enabled automatically for most displays.) + * + * IMPORTANT: The U8glib library is required for Full Graphic Display! + * https://github.com/olikraus/U8glib_Arduino + */ //#define ULTRA_LCD // Character based //#define DOGLCD // Full graphics display -// -// SD CARD -// -// SD Card support is disabled by default. If your controller has an SD slot, -// you must uncomment the following option or it won't work. -// +/** + * SD CARD + * + * SD Card support is disabled by default. If your controller has an SD slot, + * you must uncomment the following option or it won't work. + * + */ //#define SDSUPPORT -// -// SD CARD: SPI SPEED -// -// Uncomment ONE of the following items to use a slower SPI transfer -// speed. This is usually required if you're getting volume init errors. -// +/** + * SD CARD: SPI SPEED + * + * Enable one of the following items for a slower SPI transfer speed. + * This may be required to resolve "volume init" errors. + */ //#define SPI_SPEED SPI_HALF_SPEED //#define SPI_SPEED SPI_QUARTER_SPEED //#define SPI_SPEED SPI_EIGHTH_SPEED -// -// SD CARD: ENABLE CRC -// -// Use CRC checks and retries on the SD communication. -// +/** + * SD CARD: ENABLE CRC + * + * Use CRC checks and retries on the SD communication. + */ //#define SD_CHECK_AND_RETRY // @@ -1221,7 +1218,7 @@ */ // -// This option reverses the encoder direction everywhere +// This option reverses the encoder direction everywhere. // // Set this option if CLOCKWISE causes values to DECREASE // diff --git a/Marlin/example_configurations/TAZ4/Configuration.h b/Marlin/example_configurations/TAZ4/Configuration.h index 83c7a1873..1b3d640a4 100644 --- a/Marlin/example_configurations/TAZ4/Configuration.h +++ b/Marlin/example_configurations/TAZ4/Configuration.h @@ -1006,23 +1006,17 @@ #define PREHEAT_2_TEMP_BED 110 #define PREHEAT_2_FAN_SPEED 0 // Value from 0 to 255 -// -// Nozzle Park -- EXPERIMENTAL -// -// When enabled allows the user to define a special XYZ position, inside the -// machine's topology, to park the nozzle when idle or when receiving the G27 -// command. -// -// The "P" paramenter controls what is the action applied to the Z axis: -// P0: (Default) If current Z-pos is lower than Z-park then the nozzle will -// be raised to reach Z-park height. -// -// P1: No matter the current Z-pos, the nozzle will be raised/lowered to -// reach Z-park height. -// -// P2: The nozzle height will be raised by Z-park amount but never going over -// the machine's limit of Z_MAX_POS. -// +/** + * Nozzle Park -- EXPERIMENTAL + * + * Park the nozzle at the given XYZ position on idle or G27. + * + * The "P" parameter controls the action applied to the Z axis: + * + * P0 (Default) If Z is below park Z raise the nozzle. + * P1 Raise the nozzle always to Z-park height. + * P2 Raise the nozzle by Z-park amount, limited to Z_MAX_POS. + */ //#define NOZZLE_PARK_FEATURE #if ENABLED(NOZZLE_PARK_FEATURE) @@ -1030,44 +1024,44 @@ #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 } #endif -// -// Clean Nozzle Feature -- EXPERIMENTAL -// -// When enabled allows the user to send G12 to start the nozzle cleaning -// process, the G-Code accepts two parameters: -// "P" for pattern selection -// "S" for defining the number of strokes/repetitions -// -// Available list of patterns: -// P0: This is the default pattern, this process requires a sponge type -// material at a fixed bed location. S defines "strokes" i.e. -// back-and-forth movements between the starting and end points. -// -// P1: This starts a zig-zag pattern between (X0, Y0) and (X1, Y1), "T" -// defines the number of zig-zag triangles to be done. "S" defines the -// number of strokes aka one back-and-forth movement. Zig-zags will -// be performed in whichever dimension is smallest. As an example, -// sending "G12 P1 S1 T3" will execute: -// -// -- -// | (X0, Y1) | /\ /\ /\ | (X1, Y1) -// | | / \ / \ / \ | -// A | | / \ / \ / \ | -// | | / \ / \ / \ | -// | (X0, Y0) | / \/ \/ \ | (X1, Y0) -// -- +--------------------------------+ -// |________|_________|_________| -// T1 T2 T3 -// -// P2: This starts a circular pattern with circle with middle in -// NOZZLE_CLEAN_CIRCLE_MIDDLE radius of R and stroke count of S. -// Before starting the circle nozzle goes to NOZZLE_CLEAN_START_POINT. -// -// Caveats: End point Z should use the same value as Start point Z. -// -// Attention: This is an EXPERIMENTAL feature, in the future the G-code arguments -// may change to add new functionality like different wipe patterns. -// +/** + * Clean Nozzle Feature -- EXPERIMENTAL + * + * Adds the G12 command to perform a nozzle cleaning process. + * + * Parameters: + * P Pattern + * S Strokes / Repetitions + * T Triangles (P1 only) + * + * Patterns: + * P0 Straight line (default). This process requires a sponge type material + * at a fixed bed location. "S" specifies strokes (i.e. back-forth motions) + * between the start / end points. + * + * P1 Zig-zag pattern between (X0, Y0) and (X1, Y1), "T" specifies the + * number of zig-zag triangles to do. "S" defines the number of strokes. + * Zig-zags are done in whichever is the narrower dimension. + * For example, "G12 P1 S1 T3" will execute: + * + * -- + * | (X0, Y1) | /\ /\ /\ | (X1, Y1) + * | | / \ / \ / \ | + * A | | / \ / \ / \ | + * | | / \ / \ / \ | + * | (X0, Y0) | / \/ \/ \ | (X1, Y0) + * -- +--------------------------------+ + * |________|_________|_________| + * T1 T2 T3 + * + * P2 Circular pattern with middle at NOZZLE_CLEAN_CIRCLE_MIDDLE. + * "R" specifies the radius. "S" specifies the stroke count. + * Before starting, the nozzle moves to NOZZLE_CLEAN_START_POINT. + * + * Caveats: The ending Z should be the same as starting Z. + * Attention: EXPERIMENTAL. G-code arguments may change. + * + */ //#define NOZZLE_CLEAN_FEATURE #if ENABLED(NOZZLE_CLEAN_FEATURE) @@ -1092,33 +1086,35 @@ #define NOZZLE_CLEAN_GOBACK #endif -// -// Print job timer -// -// Enable this option to automatically start and stop the -// print job timer when M104/M109/M190 commands are received. -// M104 (extruder without wait) - high temp = none, low temp = stop timer -// M109 (extruder with wait) - high temp = start timer, low temp = stop timer -// M190 (bed with wait) - high temp = start timer, low temp = none -// -// In all cases the timer can be started and stopped using -// the following commands: -// -// - M75 - Start the print job timer -// - M76 - Pause the print job timer -// - M77 - Stop the print job timer +/** + * Print Job Timer + * + * Automatically start and stop the print job timer on M104/M109/M190. + * + * 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 + * + * The timer can also be controlled with the following commands: + * + * M75 - Start the print job timer + * M76 - Pause the print job timer + * M77 - Stop the print job timer + */ #define PRINTJOB_TIMER_AUTOSTART -// -// Print Counter -// -// When enabled Marlin will keep track of some print statistical data such as: -// - Total print jobs -// - Total successful print jobs -// - Total failed print jobs -// - Total time printing -// -// This information can be viewed by the M78 command. +/** + * Print Counter + * + * Track statistical data such as: + * + * - Total print jobs + * - Total successful print jobs + * - Total failed print jobs + * - Total time printing + * + * View the current statistics with M78. + */ //#define PRINTCOUNTER //============================================================================= @@ -1127,78 +1123,79 @@ // @section lcd -// -// LCD LANGUAGE -// -// Here you may choose the language used by Marlin on the LCD menus, the following -// list of languages are available: -// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, -// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test -// -// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } -// +/** + * LCD LANGUAGE + * + * Select the language to display on the LCD. These languages are available: + * + * en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, + * kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test + * + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } + */ #define LCD_LANGUAGE en -// -// LCD Character Set -// -// Note: This option is NOT applicable to Graphical Displays. -// -// All character-based LCD's provide ASCII plus one of these -// language extensions: -// -// - JAPANESE ... the most common -// - WESTERN ... with more accented characters -// - CYRILLIC ... for the Russian language -// -// To determine the language extension installed on your controller: -// -// - Compile and upload with LCD_LANGUAGE set to 'test' -// - Click the controller to view the LCD menu -// - The LCD will display Japanese, Western, or Cyrillic text -// -// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language -// -// :['JAPANESE', 'WESTERN', 'CYRILLIC'] -// +/** + * LCD Character Set + * + * Note: This option is NOT applicable to Graphical Displays. + * + * All character-based LCDs provide ASCII plus one of these + * language extensions: + * + * - JAPANESE ... the most common + * - WESTERN ... with more accented characters + * - CYRILLIC ... for the Russian language + * + * To determine the language extension installed on your controller: + * + * - Compile and upload with LCD_LANGUAGE set to 'test' + * - Click the controller to view the LCD menu + * - The LCD will display Japanese, Western, or Cyrillic text + * + * See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * + * :['JAPANESE', 'WESTERN', 'CYRILLIC'] + */ #define DISPLAY_CHARSET_HD44780 JAPANESE -// -// LCD TYPE -// -// You may choose ULTRA_LCD if you have character based LCD with 16x2, 16x4, 20x2, -// 20x4 char/lines or DOGLCD for the full graphics display with 128x64 pixels -// (ST7565R family). (This option will be set automatically for certain displays.) -// -// IMPORTANT NOTE: The U8glib library is required for Full Graphic Display! -// https://github.com/olikraus/U8glib_Arduino -// +/** + * LCD TYPE + * + * Enable ULTRA_LCD for a 16x2, 16x4, 20x2, or 20x4 character-based LCD. + * Enable DOGLCD for a 128x64 (ST7565R) Full Graphical Display. + * (These options will be enabled automatically for most displays.) + * + * IMPORTANT: The U8glib library is required for Full Graphic Display! + * https://github.com/olikraus/U8glib_Arduino + */ //#define ULTRA_LCD // Character based //#define DOGLCD // Full graphics display -// -// SD CARD -// -// SD Card support is disabled by default. If your controller has an SD slot, -// you must uncomment the following option or it won't work. -// +/** + * SD CARD + * + * SD Card support is disabled by default. If your controller has an SD slot, + * you must uncomment the following option or it won't work. + * + */ //#define SDSUPPORT -// -// SD CARD: SPI SPEED -// -// Uncomment ONE of the following items to use a slower SPI transfer -// speed. This is usually required if you're getting volume init errors. -// +/** + * SD CARD: SPI SPEED + * + * Enable one of the following items for a slower SPI transfer speed. + * This may be required to resolve "volume init" errors. + */ //#define SPI_SPEED SPI_HALF_SPEED //#define SPI_SPEED SPI_QUARTER_SPEED //#define SPI_SPEED SPI_EIGHTH_SPEED -// -// SD CARD: ENABLE CRC -// -// Use CRC checks and retries on the SD communication. -// +/** + * SD CARD: ENABLE CRC + * + * Use CRC checks and retries on the SD communication. + */ //#define SD_CHECK_AND_RETRY // @@ -1226,7 +1223,7 @@ */ // -// This option reverses the encoder direction everywhere +// This option reverses the encoder direction everywhere. // // Set this option if CLOCKWISE causes values to DECREASE // diff --git a/Marlin/example_configurations/TinyBoy2/Configuration.h b/Marlin/example_configurations/TinyBoy2/Configuration.h index 966ec447f..39b4ca6b1 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration.h @@ -1042,23 +1042,17 @@ #define PREHEAT_2_TEMP_BED 90 // TB2: ABS default 110, 90 is the maximum temp at 12V supply #define PREHEAT_2_FAN_SPEED 0 // Value from 0 to 255 -// -// Nozzle Park -- EXPERIMENTAL -// -// When enabled allows the user to define a special XYZ position, inside the -// machine's topology, to park the nozzle when idle or when receiving the G27 -// command. -// -// The "P" paramenter controls what is the action applied to the Z axis: -// P0: (Default) If current Z-pos is lower than Z-park then the nozzle will -// be raised to reach Z-park height. -// -// P1: No matter the current Z-pos, the nozzle will be raised/lowered to -// reach Z-park height. -// -// P2: The nozzle height will be raised by Z-park amount but never going over -// the machine's limit of Z_MAX_POS. -// +/** + * Nozzle Park -- EXPERIMENTAL + * + * Park the nozzle at the given XYZ position on idle or G27. + * + * The "P" parameter controls the action applied to the Z axis: + * + * P0 (Default) If Z is below park Z raise the nozzle. + * P1 Raise the nozzle always to Z-park height. + * P2 Raise the nozzle by Z-park amount, limited to Z_MAX_POS. + */ #define NOZZLE_PARK_FEATURE #if ENABLED(NOZZLE_PARK_FEATURE) @@ -1066,44 +1060,44 @@ #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 } #endif -// -// Clean Nozzle Feature -- EXPERIMENTAL -// -// When enabled allows the user to send G12 to start the nozzle cleaning -// process, the G-Code accepts two parameters: -// "P" for pattern selection -// "S" for defining the number of strokes/repetitions -// -// Available list of patterns: -// P0: This is the default pattern, this process requires a sponge type -// material at a fixed bed location. S defines "strokes" i.e. -// back-and-forth movements between the starting and end points. -// -// P1: This starts a zig-zag pattern between (X0, Y0) and (X1, Y1), "T" -// defines the number of zig-zag triangles to be done. "S" defines the -// number of strokes aka one back-and-forth movement. Zig-zags will -// be performed in whichever dimension is smallest. As an example, -// sending "G12 P1 S1 T3" will execute: -// -// -- -// | (X0, Y1) | /\ /\ /\ | (X1, Y1) -// | | / \ / \ / \ | -// A | | / \ / \ / \ | -// | | / \ / \ / \ | -// | (X0, Y0) | / \/ \/ \ | (X1, Y0) -// -- +--------------------------------+ -// |________|_________|_________| -// T1 T2 T3 -// -// P2: This starts a circular pattern with circle with middle in -// NOZZLE_CLEAN_CIRCLE_MIDDLE radius of R and stroke count of S. -// Before starting the circle nozzle goes to NOZZLE_CLEAN_START_POINT. -// -// Caveats: End point Z should use the same value as Start point Z. -// -// Attention: This is an EXPERIMENTAL feature, in the future the G-code arguments -// may change to add new functionality like different wipe patterns. -// +/** + * Clean Nozzle Feature -- EXPERIMENTAL + * + * Adds the G12 command to perform a nozzle cleaning process. + * + * Parameters: + * P Pattern + * S Strokes / Repetitions + * T Triangles (P1 only) + * + * Patterns: + * P0 Straight line (default). This process requires a sponge type material + * at a fixed bed location. "S" specifies strokes (i.e. back-forth motions) + * between the start / end points. + * + * P1 Zig-zag pattern between (X0, Y0) and (X1, Y1), "T" specifies the + * number of zig-zag triangles to do. "S" defines the number of strokes. + * Zig-zags are done in whichever is the narrower dimension. + * For example, "G12 P1 S1 T3" will execute: + * + * -- + * | (X0, Y1) | /\ /\ /\ | (X1, Y1) + * | | / \ / \ / \ | + * A | | / \ / \ / \ | + * | | / \ / \ / \ | + * | (X0, Y0) | / \/ \/ \ | (X1, Y0) + * -- +--------------------------------+ + * |________|_________|_________| + * T1 T2 T3 + * + * P2 Circular pattern with middle at NOZZLE_CLEAN_CIRCLE_MIDDLE. + * "R" specifies the radius. "S" specifies the stroke count. + * Before starting, the nozzle moves to NOZZLE_CLEAN_START_POINT. + * + * Caveats: The ending Z should be the same as starting Z. + * Attention: EXPERIMENTAL. G-code arguments may change. + * + */ //#define NOZZLE_CLEAN_FEATURE #if ENABLED(NOZZLE_CLEAN_FEATURE) @@ -1128,33 +1122,35 @@ #define NOZZLE_CLEAN_GOBACK #endif -// -// Print job timer -// -// Enable this option to automatically start and stop the -// print job timer when M104/M109/M190 commands are received. -// M104 (extruder without wait) - high temp = none, low temp = stop timer -// M109 (extruder with wait) - high temp = start timer, low temp = stop timer -// M190 (bed with wait) - high temp = start timer, low temp = none -// -// In all cases the timer can be started and stopped using -// the following commands: -// -// - M75 - Start the print job timer -// - M76 - Pause the print job timer -// - M77 - Stop the print job timer +/** + * Print Job Timer + * + * Automatically start and stop the print job timer on M104/M109/M190. + * + * 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 + * + * The timer can also be controlled with the following commands: + * + * M75 - Start the print job timer + * M76 - Pause the print job timer + * M77 - Stop the print job timer + */ #define PRINTJOB_TIMER_AUTOSTART -// -// Print Counter -// -// When enabled Marlin will keep track of some print statistical data such as: -// - Total print jobs -// - Total successful print jobs -// - Total failed print jobs -// - Total time printing -// -// This information can be viewed by the M78 command. +/** + * Print Counter + * + * Track statistical data such as: + * + * - Total print jobs + * - Total successful print jobs + * - Total failed print jobs + * - Total time printing + * + * View the current statistics with M78. + */ #define PRINTCOUNTER //============================================================================= @@ -1163,78 +1159,79 @@ // @section lcd -// -// LCD LANGUAGE -// -// Here you may choose the language used by Marlin on the LCD menus, the following -// list of languages are available: -// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, -// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test -// -// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } -// +/** + * LCD LANGUAGE + * + * Select the language to display on the LCD. These languages are available: + * + * en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, + * kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test + * + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } + */ #define LCD_LANGUAGE en -// -// LCD Character Set -// -// Note: This option is NOT applicable to Graphical Displays. -// -// All character-based LCD's provide ASCII plus one of these -// language extensions: -// -// - JAPANESE ... the most common -// - WESTERN ... with more accented characters -// - CYRILLIC ... for the Russian language -// -// To determine the language extension installed on your controller: -// -// - Compile and upload with LCD_LANGUAGE set to 'test' -// - Click the controller to view the LCD menu -// - The LCD will display Japanese, Western, or Cyrillic text -// -// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language -// -// :['JAPANESE', 'WESTERN', 'CYRILLIC'] -// +/** + * LCD Character Set + * + * Note: This option is NOT applicable to Graphical Displays. + * + * All character-based LCDs provide ASCII plus one of these + * language extensions: + * + * - JAPANESE ... the most common + * - WESTERN ... with more accented characters + * - CYRILLIC ... for the Russian language + * + * To determine the language extension installed on your controller: + * + * - Compile and upload with LCD_LANGUAGE set to 'test' + * - Click the controller to view the LCD menu + * - The LCD will display Japanese, Western, or Cyrillic text + * + * See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * + * :['JAPANESE', 'WESTERN', 'CYRILLIC'] + */ #define DISPLAY_CHARSET_HD44780 JAPANESE -// -// LCD TYPE -// -// You may choose ULTRA_LCD if you have character based LCD with 16x2, 16x4, 20x2, -// 20x4 char/lines or DOGLCD for the full graphics display with 128x64 pixels -// (ST7565R family). (This option will be set automatically for certain displays.) -// -// IMPORTANT NOTE: The U8glib library is required for Full Graphic Display! -// https://github.com/olikraus/U8glib_Arduino -// +/** + * LCD TYPE + * + * Enable ULTRA_LCD for a 16x2, 16x4, 20x2, or 20x4 character-based LCD. + * Enable DOGLCD for a 128x64 (ST7565R) Full Graphical Display. + * (These options will be enabled automatically for most displays.) + * + * IMPORTANT: The U8glib library is required for Full Graphic Display! + * https://github.com/olikraus/U8glib_Arduino + */ //#define ULTRA_LCD // Character based //#define DOGLCD // Full graphics display -// -// SD CARD -// -// SD Card support is disabled by default. If your controller has an SD slot, -// you must uncomment the following option or it won't work. -// +/** + * SD CARD + * + * SD Card support is disabled by default. If your controller has an SD slot, + * you must uncomment the following option or it won't work. + * + */ #define SDSUPPORT -// -// SD CARD: SPI SPEED -// -// Uncomment ONE of the following items to use a slower SPI transfer -// speed. This is usually required if you're getting volume init errors. -// +/** + * SD CARD: SPI SPEED + * + * Enable one of the following items for a slower SPI transfer speed. + * This may be required to resolve "volume init" errors. + */ //#define SPI_SPEED SPI_HALF_SPEED //#define SPI_SPEED SPI_QUARTER_SPEED //#define SPI_SPEED SPI_EIGHTH_SPEED -// -// SD CARD: ENABLE CRC -// -// Use CRC checks and retries on the SD communication. -// +/** + * SD CARD: ENABLE CRC + * + * Use CRC checks and retries on the SD communication. + */ #define SD_CHECK_AND_RETRY // @@ -1262,7 +1259,7 @@ */ // -// This option reverses the encoder direction everywhere +// This option reverses the encoder direction everywhere. // // Set this option if CLOCKWISE causes values to DECREASE // diff --git a/Marlin/example_configurations/WITBOX/Configuration.h b/Marlin/example_configurations/WITBOX/Configuration.h index 5143d7bd7..4c6ac763b 100644 --- a/Marlin/example_configurations/WITBOX/Configuration.h +++ b/Marlin/example_configurations/WITBOX/Configuration.h @@ -977,23 +977,17 @@ #define PREHEAT_2_TEMP_BED 100 #define PREHEAT_2_FAN_SPEED 255 // Value from 0 to 255 -// -// Nozzle Park -- EXPERIMENTAL -// -// When enabled allows the user to define a special XYZ position, inside the -// machine's topology, to park the nozzle when idle or when receiving the G27 -// command. -// -// The "P" paramenter controls what is the action applied to the Z axis: -// P0: (Default) If current Z-pos is lower than Z-park then the nozzle will -// be raised to reach Z-park height. -// -// P1: No matter the current Z-pos, the nozzle will be raised/lowered to -// reach Z-park height. -// -// P2: The nozzle height will be raised by Z-park amount but never going over -// the machine's limit of Z_MAX_POS. -// +/** + * Nozzle Park -- EXPERIMENTAL + * + * Park the nozzle at the given XYZ position on idle or G27. + * + * The "P" parameter controls the action applied to the Z axis: + * + * P0 (Default) If Z is below park Z raise the nozzle. + * P1 Raise the nozzle always to Z-park height. + * P2 Raise the nozzle by Z-park amount, limited to Z_MAX_POS. + */ //#define NOZZLE_PARK_FEATURE #if ENABLED(NOZZLE_PARK_FEATURE) @@ -1001,44 +995,44 @@ #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 } #endif -// -// Clean Nozzle Feature -- EXPERIMENTAL -// -// When enabled allows the user to send G12 to start the nozzle cleaning -// process, the G-Code accepts two parameters: -// "P" for pattern selection -// "S" for defining the number of strokes/repetitions -// -// Available list of patterns: -// P0: This is the default pattern, this process requires a sponge type -// material at a fixed bed location. S defines "strokes" i.e. -// back-and-forth movements between the starting and end points. -// -// P1: This starts a zig-zag pattern between (X0, Y0) and (X1, Y1), "T" -// defines the number of zig-zag triangles to be done. "S" defines the -// number of strokes aka one back-and-forth movement. Zig-zags will -// be performed in whichever dimension is smallest. As an example, -// sending "G12 P1 S1 T3" will execute: -// -// -- -// | (X0, Y1) | /\ /\ /\ | (X1, Y1) -// | | / \ / \ / \ | -// A | | / \ / \ / \ | -// | | / \ / \ / \ | -// | (X0, Y0) | / \/ \/ \ | (X1, Y0) -// -- +--------------------------------+ -// |________|_________|_________| -// T1 T2 T3 -// -// P2: This starts a circular pattern with circle with middle in -// NOZZLE_CLEAN_CIRCLE_MIDDLE radius of R and stroke count of S. -// Before starting the circle nozzle goes to NOZZLE_CLEAN_START_POINT. -// -// Caveats: End point Z should use the same value as Start point Z. -// -// Attention: This is an EXPERIMENTAL feature, in the future the G-code arguments -// may change to add new functionality like different wipe patterns. -// +/** + * Clean Nozzle Feature -- EXPERIMENTAL + * + * Adds the G12 command to perform a nozzle cleaning process. + * + * Parameters: + * P Pattern + * S Strokes / Repetitions + * T Triangles (P1 only) + * + * Patterns: + * P0 Straight line (default). This process requires a sponge type material + * at a fixed bed location. "S" specifies strokes (i.e. back-forth motions) + * between the start / end points. + * + * P1 Zig-zag pattern between (X0, Y0) and (X1, Y1), "T" specifies the + * number of zig-zag triangles to do. "S" defines the number of strokes. + * Zig-zags are done in whichever is the narrower dimension. + * For example, "G12 P1 S1 T3" will execute: + * + * -- + * | (X0, Y1) | /\ /\ /\ | (X1, Y1) + * | | / \ / \ / \ | + * A | | / \ / \ / \ | + * | | / \ / \ / \ | + * | (X0, Y0) | / \/ \/ \ | (X1, Y0) + * -- +--------------------------------+ + * |________|_________|_________| + * T1 T2 T3 + * + * P2 Circular pattern with middle at NOZZLE_CLEAN_CIRCLE_MIDDLE. + * "R" specifies the radius. "S" specifies the stroke count. + * Before starting, the nozzle moves to NOZZLE_CLEAN_START_POINT. + * + * Caveats: The ending Z should be the same as starting Z. + * Attention: EXPERIMENTAL. G-code arguments may change. + * + */ //#define NOZZLE_CLEAN_FEATURE #if ENABLED(NOZZLE_CLEAN_FEATURE) @@ -1063,33 +1057,35 @@ #define NOZZLE_CLEAN_GOBACK #endif -// -// Print job timer -// -// Enable this option to automatically start and stop the -// print job timer when M104/M109/M190 commands are received. -// M104 (extruder without wait) - high temp = none, low temp = stop timer -// M109 (extruder with wait) - high temp = start timer, low temp = stop timer -// M190 (bed with wait) - high temp = start timer, low temp = none -// -// In all cases the timer can be started and stopped using -// the following commands: -// -// - M75 - Start the print job timer -// - M76 - Pause the print job timer -// - M77 - Stop the print job timer +/** + * Print Job Timer + * + * Automatically start and stop the print job timer on M104/M109/M190. + * + * 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 + * + * The timer can also be controlled with the following commands: + * + * M75 - Start the print job timer + * M76 - Pause the print job timer + * M77 - Stop the print job timer + */ #define PRINTJOB_TIMER_AUTOSTART -// -// Print Counter -// -// When enabled Marlin will keep track of some print statistical data such as: -// - Total print jobs -// - Total successful print jobs -// - Total failed print jobs -// - Total time printing -// -// This information can be viewed by the M78 command. +/** + * Print Counter + * + * Track statistical data such as: + * + * - Total print jobs + * - Total successful print jobs + * - Total failed print jobs + * - Total time printing + * + * View the current statistics with M78. + */ //#define PRINTCOUNTER //============================================================================= @@ -1098,78 +1094,79 @@ // @section lcd -// -// LCD LANGUAGE -// -// Here you may choose the language used by Marlin on the LCD menus, the following -// list of languages are available: -// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, -// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test -// -// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } -// +/** + * LCD LANGUAGE + * + * Select the language to display on the LCD. These languages are available: + * + * en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, + * kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test + * + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } + */ //#define LCD_LANGUAGE en -// -// LCD Character Set -// -// Note: This option is NOT applicable to Graphical Displays. -// -// All character-based LCD's provide ASCII plus one of these -// language extensions: -// -// - JAPANESE ... the most common -// - WESTERN ... with more accented characters -// - CYRILLIC ... for the Russian language -// -// To determine the language extension installed on your controller: -// -// - Compile and upload with LCD_LANGUAGE set to 'test' -// - Click the controller to view the LCD menu -// - The LCD will display Japanese, Western, or Cyrillic text -// -// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language -// -// :['JAPANESE', 'WESTERN', 'CYRILLIC'] -// +/** + * LCD Character Set + * + * Note: This option is NOT applicable to Graphical Displays. + * + * All character-based LCDs provide ASCII plus one of these + * language extensions: + * + * - JAPANESE ... the most common + * - WESTERN ... with more accented characters + * - CYRILLIC ... for the Russian language + * + * To determine the language extension installed on your controller: + * + * - Compile and upload with LCD_LANGUAGE set to 'test' + * - Click the controller to view the LCD menu + * - The LCD will display Japanese, Western, or Cyrillic text + * + * See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * + * :['JAPANESE', 'WESTERN', 'CYRILLIC'] + */ #define DISPLAY_CHARSET_HD44780 JAPANESE -// -// LCD TYPE -// -// You may choose ULTRA_LCD if you have character based LCD with 16x2, 16x4, 20x2, -// 20x4 char/lines or DOGLCD for the full graphics display with 128x64 pixels -// (ST7565R family). (This option will be set automatically for certain displays.) -// -// IMPORTANT NOTE: The U8glib library is required for Full Graphic Display! -// https://github.com/olikraus/U8glib_Arduino -// +/** + * LCD TYPE + * + * Enable ULTRA_LCD for a 16x2, 16x4, 20x2, or 20x4 character-based LCD. + * Enable DOGLCD for a 128x64 (ST7565R) Full Graphical Display. + * (These options will be enabled automatically for most displays.) + * + * IMPORTANT: The U8glib library is required for Full Graphic Display! + * https://github.com/olikraus/U8glib_Arduino + */ #define ULTRA_LCD // Character based //#define DOGLCD // Full graphics display -// -// SD CARD -// -// SD Card support is disabled by default. If your controller has an SD slot, -// you must uncomment the following option or it won't work. -// +/** + * SD CARD + * + * SD Card support is disabled by default. If your controller has an SD slot, + * you must uncomment the following option or it won't work. + * + */ #define SDSUPPORT -// -// SD CARD: SPI SPEED -// -// Uncomment ONE of the following items to use a slower SPI transfer -// speed. This is usually required if you're getting volume init errors. -// +/** + * SD CARD: SPI SPEED + * + * Enable one of the following items for a slower SPI transfer speed. + * This may be required to resolve "volume init" errors. + */ //#define SPI_SPEED SPI_HALF_SPEED //#define SPI_SPEED SPI_QUARTER_SPEED //#define SPI_SPEED SPI_EIGHTH_SPEED -// -// SD CARD: ENABLE CRC -// -// Use CRC checks and retries on the SD communication. -// +/** + * SD CARD: ENABLE CRC + * + * Use CRC checks and retries on the SD communication. + */ //#define SD_CHECK_AND_RETRY // @@ -1197,7 +1194,7 @@ */ // -// This option reverses the encoder direction everywhere +// This option reverses the encoder direction everywhere. // // Set this option if CLOCKWISE causes values to DECREASE // diff --git a/Marlin/example_configurations/adafruit/ST7565/Configuration.h b/Marlin/example_configurations/adafruit/ST7565/Configuration.h index 1874b12d3..a620b8029 100644 --- a/Marlin/example_configurations/adafruit/ST7565/Configuration.h +++ b/Marlin/example_configurations/adafruit/ST7565/Configuration.h @@ -986,23 +986,17 @@ #define PREHEAT_2_TEMP_BED 110 #define PREHEAT_2_FAN_SPEED 0 // Value from 0 to 255 -// -// Nozzle Park -- EXPERIMENTAL -// -// When enabled allows the user to define a special XYZ position, inside the -// machine's topology, to park the nozzle when idle or when receiving the G27 -// command. -// -// The "P" paramenter controls what is the action applied to the Z axis: -// P0: (Default) If current Z-pos is lower than Z-park then the nozzle will -// be raised to reach Z-park height. -// -// P1: No matter the current Z-pos, the nozzle will be raised/lowered to -// reach Z-park height. -// -// P2: The nozzle height will be raised by Z-park amount but never going over -// the machine's limit of Z_MAX_POS. -// +/** + * Nozzle Park -- EXPERIMENTAL + * + * Park the nozzle at the given XYZ position on idle or G27. + * + * The "P" parameter controls the action applied to the Z axis: + * + * P0 (Default) If Z is below park Z raise the nozzle. + * P1 Raise the nozzle always to Z-park height. + * P2 Raise the nozzle by Z-park amount, limited to Z_MAX_POS. + */ //#define NOZZLE_PARK_FEATURE #if ENABLED(NOZZLE_PARK_FEATURE) @@ -1010,44 +1004,44 @@ #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 } #endif -// -// Clean Nozzle Feature -- EXPERIMENTAL -// -// When enabled allows the user to send G12 to start the nozzle cleaning -// process, the G-Code accepts two parameters: -// "P" for pattern selection -// "S" for defining the number of strokes/repetitions -// -// Available list of patterns: -// P0: This is the default pattern, this process requires a sponge type -// material at a fixed bed location. S defines "strokes" i.e. -// back-and-forth movements between the starting and end points. -// -// P1: This starts a zig-zag pattern between (X0, Y0) and (X1, Y1), "T" -// defines the number of zig-zag triangles to be done. "S" defines the -// number of strokes aka one back-and-forth movement. Zig-zags will -// be performed in whichever dimension is smallest. As an example, -// sending "G12 P1 S1 T3" will execute: -// -// -- -// | (X0, Y1) | /\ /\ /\ | (X1, Y1) -// | | / \ / \ / \ | -// A | | / \ / \ / \ | -// | | / \ / \ / \ | -// | (X0, Y0) | / \/ \/ \ | (X1, Y0) -// -- +--------------------------------+ -// |________|_________|_________| -// T1 T2 T3 -// -// P2: This starts a circular pattern with circle with middle in -// NOZZLE_CLEAN_CIRCLE_MIDDLE radius of R and stroke count of S. -// Before starting the circle nozzle goes to NOZZLE_CLEAN_START_POINT. -// -// Caveats: End point Z should use the same value as Start point Z. -// -// Attention: This is an EXPERIMENTAL feature, in the future the G-code arguments -// may change to add new functionality like different wipe patterns. -// +/** + * Clean Nozzle Feature -- EXPERIMENTAL + * + * Adds the G12 command to perform a nozzle cleaning process. + * + * Parameters: + * P Pattern + * S Strokes / Repetitions + * T Triangles (P1 only) + * + * Patterns: + * P0 Straight line (default). This process requires a sponge type material + * at a fixed bed location. "S" specifies strokes (i.e. back-forth motions) + * between the start / end points. + * + * P1 Zig-zag pattern between (X0, Y0) and (X1, Y1), "T" specifies the + * number of zig-zag triangles to do. "S" defines the number of strokes. + * Zig-zags are done in whichever is the narrower dimension. + * For example, "G12 P1 S1 T3" will execute: + * + * -- + * | (X0, Y1) | /\ /\ /\ | (X1, Y1) + * | | / \ / \ / \ | + * A | | / \ / \ / \ | + * | | / \ / \ / \ | + * | (X0, Y0) | / \/ \/ \ | (X1, Y0) + * -- +--------------------------------+ + * |________|_________|_________| + * T1 T2 T3 + * + * P2 Circular pattern with middle at NOZZLE_CLEAN_CIRCLE_MIDDLE. + * "R" specifies the radius. "S" specifies the stroke count. + * Before starting, the nozzle moves to NOZZLE_CLEAN_START_POINT. + * + * Caveats: The ending Z should be the same as starting Z. + * Attention: EXPERIMENTAL. G-code arguments may change. + * + */ //#define NOZZLE_CLEAN_FEATURE #if ENABLED(NOZZLE_CLEAN_FEATURE) @@ -1072,33 +1066,35 @@ #define NOZZLE_CLEAN_GOBACK #endif -// -// Print job timer -// -// Enable this option to automatically start and stop the -// print job timer when M104/M109/M190 commands are received. -// M104 (extruder without wait) - high temp = none, low temp = stop timer -// M109 (extruder with wait) - high temp = start timer, low temp = stop timer -// M190 (bed with wait) - high temp = start timer, low temp = none -// -// In all cases the timer can be started and stopped using -// the following commands: -// -// - M75 - Start the print job timer -// - M76 - Pause the print job timer -// - M77 - Stop the print job timer +/** + * Print Job Timer + * + * Automatically start and stop the print job timer on M104/M109/M190. + * + * 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 + * + * The timer can also be controlled with the following commands: + * + * M75 - Start the print job timer + * M76 - Pause the print job timer + * M77 - Stop the print job timer + */ #define PRINTJOB_TIMER_AUTOSTART -// -// Print Counter -// -// When enabled Marlin will keep track of some print statistical data such as: -// - Total print jobs -// - Total successful print jobs -// - Total failed print jobs -// - Total time printing -// -// This information can be viewed by the M78 command. +/** + * Print Counter + * + * Track statistical data such as: + * + * - Total print jobs + * - Total successful print jobs + * - Total failed print jobs + * - Total time printing + * + * View the current statistics with M78. + */ //#define PRINTCOUNTER //============================================================================= @@ -1107,78 +1103,79 @@ // @section lcd -// -// LCD LANGUAGE -// -// Here you may choose the language used by Marlin on the LCD menus, the following -// list of languages are available: -// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, -// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test -// -// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } -// +/** + * LCD LANGUAGE + * + * Select the language to display on the LCD. These languages are available: + * + * en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, + * kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test + * + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } + */ #define LCD_LANGUAGE en -// -// LCD Character Set -// -// Note: This option is NOT applicable to Graphical Displays. -// -// All character-based LCD's provide ASCII plus one of these -// language extensions: -// -// - JAPANESE ... the most common -// - WESTERN ... with more accented characters -// - CYRILLIC ... for the Russian language -// -// To determine the language extension installed on your controller: -// -// - Compile and upload with LCD_LANGUAGE set to 'test' -// - Click the controller to view the LCD menu -// - The LCD will display Japanese, Western, or Cyrillic text -// -// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language -// -// :['JAPANESE', 'WESTERN', 'CYRILLIC'] -// +/** + * LCD Character Set + * + * Note: This option is NOT applicable to Graphical Displays. + * + * All character-based LCDs provide ASCII plus one of these + * language extensions: + * + * - JAPANESE ... the most common + * - WESTERN ... with more accented characters + * - CYRILLIC ... for the Russian language + * + * To determine the language extension installed on your controller: + * + * - Compile and upload with LCD_LANGUAGE set to 'test' + * - Click the controller to view the LCD menu + * - The LCD will display Japanese, Western, or Cyrillic text + * + * See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * + * :['JAPANESE', 'WESTERN', 'CYRILLIC'] + */ #define DISPLAY_CHARSET_HD44780 JAPANESE -// -// LCD TYPE -// -// You may choose ULTRA_LCD if you have character based LCD with 16x2, 16x4, 20x2, -// 20x4 char/lines or DOGLCD for the full graphics display with 128x64 pixels -// (ST7565R family). (This option will be set automatically for certain displays.) -// -// IMPORTANT NOTE: The U8glib library is required for Full Graphic Display! -// https://github.com/olikraus/U8glib_Arduino -// +/** + * LCD TYPE + * + * Enable ULTRA_LCD for a 16x2, 16x4, 20x2, or 20x4 character-based LCD. + * Enable DOGLCD for a 128x64 (ST7565R) Full Graphical Display. + * (These options will be enabled automatically for most displays.) + * + * IMPORTANT: The U8glib library is required for Full Graphic Display! + * https://github.com/olikraus/U8glib_Arduino + */ //#define ULTRA_LCD // Character based //#define DOGLCD // Full graphics display -// -// SD CARD -// -// SD Card support is disabled by default. If your controller has an SD slot, -// you must uncomment the following option or it won't work. -// +/** + * SD CARD + * + * SD Card support is disabled by default. If your controller has an SD slot, + * you must uncomment the following option or it won't work. + * + */ #define SDSUPPORT -// -// SD CARD: SPI SPEED -// -// Uncomment ONE of the following items to use a slower SPI transfer -// speed. This is usually required if you're getting volume init errors. -// +/** + * SD CARD: SPI SPEED + * + * Enable one of the following items for a slower SPI transfer speed. + * This may be required to resolve "volume init" errors. + */ #define SPI_SPEED SPI_HALF_SPEED //#define SPI_SPEED SPI_QUARTER_SPEED //#define SPI_SPEED SPI_EIGHTH_SPEED -// -// SD CARD: ENABLE CRC -// -// Use CRC checks and retries on the SD communication. -// +/** + * SD CARD: ENABLE CRC + * + * Use CRC checks and retries on the SD communication. + */ //#define SD_CHECK_AND_RETRY // @@ -1206,7 +1203,7 @@ */ // -// This option reverses the encoder direction everywhere +// This option reverses the encoder direction everywhere. // // Set this option if CLOCKWISE causes values to DECREASE // diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h index e7a7fd20b..f31c8f9e8 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h @@ -1104,23 +1104,17 @@ #define PREHEAT_2_TEMP_BED 100 #define PREHEAT_2_FAN_SPEED 0 // Value from 0 to 255 -// -// Nozzle Park -- EXPERIMENTAL -// -// When enabled allows the user to define a special XYZ position, inside the -// machine's topology, to park the nozzle when idle or when receiving the G27 -// command. -// -// The "P" paramenter controls what is the action applied to the Z axis: -// P0: (Default) If current Z-pos is lower than Z-park then the nozzle will -// be raised to reach Z-park height. -// -// P1: No matter the current Z-pos, the nozzle will be raised/lowered to -// reach Z-park height. -// -// P2: The nozzle height will be raised by Z-park amount but never going over -// the machine's limit of Z_MAX_POS. -// +/** + * Nozzle Park -- EXPERIMENTAL + * + * Park the nozzle at the given XYZ position on idle or G27. + * + * The "P" parameter controls the action applied to the Z axis: + * + * P0 (Default) If Z is below park Z raise the nozzle. + * P1 Raise the nozzle always to Z-park height. + * P2 Raise the nozzle by Z-park amount, limited to Z_MAX_POS. + */ //#define NOZZLE_PARK_FEATURE #if ENABLED(NOZZLE_PARK_FEATURE) @@ -1128,44 +1122,44 @@ #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 } #endif -// -// Clean Nozzle Feature -- EXPERIMENTAL -// -// When enabled allows the user to send G12 to start the nozzle cleaning -// process, the G-Code accepts two parameters: -// "P" for pattern selection -// "S" for defining the number of strokes/repetitions -// -// Available list of patterns: -// P0: This is the default pattern, this process requires a sponge type -// material at a fixed bed location. S defines "strokes" i.e. -// back-and-forth movements between the starting and end points. -// -// P1: This starts a zig-zag pattern between (X0, Y0) and (X1, Y1), "T" -// defines the number of zig-zag triangles to be done. "S" defines the -// number of strokes aka one back-and-forth movement. Zig-zags will -// be performed in whichever dimension is smallest. As an example, -// sending "G12 P1 S1 T3" will execute: -// -// -- -// | (X0, Y1) | /\ /\ /\ | (X1, Y1) -// | | / \ / \ / \ | -// A | | / \ / \ / \ | -// | | / \ / \ / \ | -// | (X0, Y0) | / \/ \/ \ | (X1, Y0) -// -- +--------------------------------+ -// |________|_________|_________| -// T1 T2 T3 -// -// P2: This starts a circular pattern with circle with middle in -// NOZZLE_CLEAN_CIRCLE_MIDDLE radius of R and stroke count of S. -// Before starting the circle nozzle goes to NOZZLE_CLEAN_START_POINT. -// -// Caveats: End point Z should use the same value as Start point Z. -// -// Attention: This is an EXPERIMENTAL feature, in the future the G-code arguments -// may change to add new functionality like different wipe patterns. -// +/** + * Clean Nozzle Feature -- EXPERIMENTAL + * + * Adds the G12 command to perform a nozzle cleaning process. + * + * Parameters: + * P Pattern + * S Strokes / Repetitions + * T Triangles (P1 only) + * + * Patterns: + * P0 Straight line (default). This process requires a sponge type material + * at a fixed bed location. "S" specifies strokes (i.e. back-forth motions) + * between the start / end points. + * + * P1 Zig-zag pattern between (X0, Y0) and (X1, Y1), "T" specifies the + * number of zig-zag triangles to do. "S" defines the number of strokes. + * Zig-zags are done in whichever is the narrower dimension. + * For example, "G12 P1 S1 T3" will execute: + * + * -- + * | (X0, Y1) | /\ /\ /\ | (X1, Y1) + * | | / \ / \ / \ | + * A | | / \ / \ / \ | + * | | / \ / \ / \ | + * | (X0, Y0) | / \/ \/ \ | (X1, Y0) + * -- +--------------------------------+ + * |________|_________|_________| + * T1 T2 T3 + * + * P2 Circular pattern with middle at NOZZLE_CLEAN_CIRCLE_MIDDLE. + * "R" specifies the radius. "S" specifies the stroke count. + * Before starting, the nozzle moves to NOZZLE_CLEAN_START_POINT. + * + * Caveats: The ending Z should be the same as starting Z. + * Attention: EXPERIMENTAL. G-code arguments may change. + * + */ //#define NOZZLE_CLEAN_FEATURE #if ENABLED(NOZZLE_CLEAN_FEATURE) @@ -1190,33 +1184,35 @@ #define NOZZLE_CLEAN_GOBACK #endif -// -// Print job timer -// -// Enable this option to automatically start and stop the -// print job timer when M104/M109/M190 commands are received. -// M104 (extruder without wait) - high temp = none, low temp = stop timer -// M109 (extruder with wait) - high temp = start timer, low temp = stop timer -// M190 (bed with wait) - high temp = start timer, low temp = none -// -// In all cases the timer can be started and stopped using -// the following commands: -// -// - M75 - Start the print job timer -// - M76 - Pause the print job timer -// - M77 - Stop the print job timer +/** + * Print Job Timer + * + * Automatically start and stop the print job timer on M104/M109/M190. + * + * 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 + * + * The timer can also be controlled with the following commands: + * + * M75 - Start the print job timer + * M76 - Pause the print job timer + * M77 - Stop the print job timer + */ #define PRINTJOB_TIMER_AUTOSTART -// -// Print Counter -// -// When enabled Marlin will keep track of some print statistical data such as: -// - Total print jobs -// - Total successful print jobs -// - Total failed print jobs -// - Total time printing -// -// This information can be viewed by the M78 command. +/** + * Print Counter + * + * Track statistical data such as: + * + * - Total print jobs + * - Total successful print jobs + * - Total failed print jobs + * - Total time printing + * + * View the current statistics with M78. + */ #define PRINTCOUNTER //============================================================================= @@ -1225,78 +1221,79 @@ // @section lcd -// -// LCD LANGUAGE -// -// Here you may choose the language used by Marlin on the LCD menus, the following -// list of languages are available: -// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, -// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test -// -// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } -// +/** + * LCD LANGUAGE + * + * Select the language to display on the LCD. These languages are available: + * + * en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, + * kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test + * + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } + */ #define LCD_LANGUAGE en -// -// LCD Character Set -// -// Note: This option is NOT applicable to Graphical Displays. -// -// All character-based LCD's provide ASCII plus one of these -// language extensions: -// -// - JAPANESE ... the most common -// - WESTERN ... with more accented characters -// - CYRILLIC ... for the Russian language -// -// To determine the language extension installed on your controller: -// -// - Compile and upload with LCD_LANGUAGE set to 'test' -// - Click the controller to view the LCD menu -// - The LCD will display Japanese, Western, or Cyrillic text -// -// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language -// -// :['JAPANESE', 'WESTERN', 'CYRILLIC'] -// +/** + * LCD Character Set + * + * Note: This option is NOT applicable to Graphical Displays. + * + * All character-based LCDs provide ASCII plus one of these + * language extensions: + * + * - JAPANESE ... the most common + * - WESTERN ... with more accented characters + * - CYRILLIC ... for the Russian language + * + * To determine the language extension installed on your controller: + * + * - Compile and upload with LCD_LANGUAGE set to 'test' + * - Click the controller to view the LCD menu + * - The LCD will display Japanese, Western, or Cyrillic text + * + * See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * + * :['JAPANESE', 'WESTERN', 'CYRILLIC'] + */ #define DISPLAY_CHARSET_HD44780 WESTERN -// -// LCD TYPE -// -// You may choose ULTRA_LCD if you have character based LCD with 16x2, 16x4, 20x2, -// 20x4 char/lines or DOGLCD for the full graphics display with 128x64 pixels -// (ST7565R family). (This option will be set automatically for certain displays.) -// -// IMPORTANT NOTE: The U8glib library is required for Full Graphic Display! -// https://github.com/olikraus/U8glib_Arduino -// +/** + * LCD TYPE + * + * Enable ULTRA_LCD for a 16x2, 16x4, 20x2, or 20x4 character-based LCD. + * Enable DOGLCD for a 128x64 (ST7565R) Full Graphical Display. + * (These options will be enabled automatically for most displays.) + * + * IMPORTANT: The U8glib library is required for Full Graphic Display! + * https://github.com/olikraus/U8glib_Arduino + */ //#define ULTRA_LCD // Character based //#define DOGLCD // Full graphics display -// -// SD CARD -// -// SD Card support is disabled by default. If your controller has an SD slot, -// you must uncomment the following option or it won't work. -// +/** + * SD CARD + * + * SD Card support is disabled by default. If your controller has an SD slot, + * you must uncomment the following option or it won't work. + * + */ #define SDSUPPORT -// -// SD CARD: SPI SPEED -// -// Uncomment ONE of the following items to use a slower SPI transfer -// speed. This is usually required if you're getting volume init errors. -// +/** + * SD CARD: SPI SPEED + * + * Enable one of the following items for a slower SPI transfer speed. + * This may be required to resolve "volume init" errors. + */ //#define SPI_SPEED SPI_HALF_SPEED //#define SPI_SPEED SPI_QUARTER_SPEED //#define SPI_SPEED SPI_EIGHTH_SPEED -// -// SD CARD: ENABLE CRC -// -// Use CRC checks and retries on the SD communication. -// +/** + * SD CARD: ENABLE CRC + * + * Use CRC checks and retries on the SD communication. + */ #define SD_CHECK_AND_RETRY // @@ -1324,7 +1321,7 @@ */ // -// This option reverses the encoder direction everywhere +// This option reverses the encoder direction everywhere. // // Set this option if CLOCKWISE causes values to DECREASE // diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h index 9654740b1..7e312bfcb 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h @@ -1106,23 +1106,17 @@ #define PREHEAT_2_TEMP_BED 100 #define PREHEAT_2_FAN_SPEED 0 // Value from 0 to 255 -// -// Nozzle Park -- EXPERIMENTAL -// -// When enabled allows the user to define a special XYZ position, inside the -// machine's topology, to park the nozzle when idle or when receiving the G27 -// command. -// -// The "P" paramenter controls what is the action applied to the Z axis: -// P0: (Default) If current Z-pos is lower than Z-park then the nozzle will -// be raised to reach Z-park height. -// -// P1: No matter the current Z-pos, the nozzle will be raised/lowered to -// reach Z-park height. -// -// P2: The nozzle height will be raised by Z-park amount but never going over -// the machine's limit of Z_MAX_POS. -// +/** + * Nozzle Park -- EXPERIMENTAL + * + * Park the nozzle at the given XYZ position on idle or G27. + * + * The "P" parameter controls the action applied to the Z axis: + * + * P0 (Default) If Z is below park Z raise the nozzle. + * P1 Raise the nozzle always to Z-park height. + * P2 Raise the nozzle by Z-park amount, limited to Z_MAX_POS. + */ //#define NOZZLE_PARK_FEATURE #if ENABLED(NOZZLE_PARK_FEATURE) @@ -1130,44 +1124,44 @@ #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 } #endif -// -// Clean Nozzle Feature -- EXPERIMENTAL -// -// When enabled allows the user to send G12 to start the nozzle cleaning -// process, the G-Code accepts two parameters: -// "P" for pattern selection -// "S" for defining the number of strokes/repetitions -// -// Available list of patterns: -// P0: This is the default pattern, this process requires a sponge type -// material at a fixed bed location. S defines "strokes" i.e. -// back-and-forth movements between the starting and end points. -// -// P1: This starts a zig-zag pattern between (X0, Y0) and (X1, Y1), "T" -// defines the number of zig-zag triangles to be done. "S" defines the -// number of strokes aka one back-and-forth movement. Zig-zags will -// be performed in whichever dimension is smallest. As an example, -// sending "G12 P1 S1 T3" will execute: -// -// -- -// | (X0, Y1) | /\ /\ /\ | (X1, Y1) -// | | / \ / \ / \ | -// A | | / \ / \ / \ | -// | | / \ / \ / \ | -// | (X0, Y0) | / \/ \/ \ | (X1, Y0) -// -- +--------------------------------+ -// |________|_________|_________| -// T1 T2 T3 -// -// P2: This starts a circular pattern with circle with middle in -// NOZZLE_CLEAN_CIRCLE_MIDDLE radius of R and stroke count of S. -// Before starting the circle nozzle goes to NOZZLE_CLEAN_START_POINT. -// -// Caveats: End point Z should use the same value as Start point Z. -// -// Attention: This is an EXPERIMENTAL feature, in the future the G-code arguments -// may change to add new functionality like different wipe patterns. -// +/** + * Clean Nozzle Feature -- EXPERIMENTAL + * + * Adds the G12 command to perform a nozzle cleaning process. + * + * Parameters: + * P Pattern + * S Strokes / Repetitions + * T Triangles (P1 only) + * + * Patterns: + * P0 Straight line (default). This process requires a sponge type material + * at a fixed bed location. "S" specifies strokes (i.e. back-forth motions) + * between the start / end points. + * + * P1 Zig-zag pattern between (X0, Y0) and (X1, Y1), "T" specifies the + * number of zig-zag triangles to do. "S" defines the number of strokes. + * Zig-zags are done in whichever is the narrower dimension. + * For example, "G12 P1 S1 T3" will execute: + * + * -- + * | (X0, Y1) | /\ /\ /\ | (X1, Y1) + * | | / \ / \ / \ | + * A | | / \ / \ / \ | + * | | / \ / \ / \ | + * | (X0, Y0) | / \/ \/ \ | (X1, Y0) + * -- +--------------------------------+ + * |________|_________|_________| + * T1 T2 T3 + * + * P2 Circular pattern with middle at NOZZLE_CLEAN_CIRCLE_MIDDLE. + * "R" specifies the radius. "S" specifies the stroke count. + * Before starting, the nozzle moves to NOZZLE_CLEAN_START_POINT. + * + * Caveats: The ending Z should be the same as starting Z. + * Attention: EXPERIMENTAL. G-code arguments may change. + * + */ //#define NOZZLE_CLEAN_FEATURE #if ENABLED(NOZZLE_CLEAN_FEATURE) @@ -1192,33 +1186,35 @@ #define NOZZLE_CLEAN_GOBACK #endif -// -// Print job timer -// -// Enable this option to automatically start and stop the -// print job timer when M104/M109/M190 commands are received. -// M104 (extruder without wait) - high temp = none, low temp = stop timer -// M109 (extruder with wait) - high temp = start timer, low temp = stop timer -// M190 (bed with wait) - high temp = start timer, low temp = none -// -// In all cases the timer can be started and stopped using -// the following commands: -// -// - M75 - Start the print job timer -// - M76 - Pause the print job timer -// - M77 - Stop the print job timer +/** + * Print Job Timer + * + * Automatically start and stop the print job timer on M104/M109/M190. + * + * 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 + * + * The timer can also be controlled with the following commands: + * + * M75 - Start the print job timer + * M76 - Pause the print job timer + * M77 - Stop the print job timer + */ #define PRINTJOB_TIMER_AUTOSTART -// -// Print Counter -// -// When enabled Marlin will keep track of some print statistical data such as: -// - Total print jobs -// - Total successful print jobs -// - Total failed print jobs -// - Total time printing -// -// This information can be viewed by the M78 command. +/** + * Print Counter + * + * Track statistical data such as: + * + * - Total print jobs + * - Total successful print jobs + * - Total failed print jobs + * - Total time printing + * + * View the current statistics with M78. + */ #define PRINTCOUNTER //============================================================================= @@ -1227,78 +1223,79 @@ // @section lcd -// -// LCD LANGUAGE -// -// Here you may choose the language used by Marlin on the LCD menus, the following -// list of languages are available: -// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, -// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test -// -// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } -// +/** + * LCD LANGUAGE + * + * Select the language to display on the LCD. These languages are available: + * + * en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, + * kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test + * + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } + */ #define LCD_LANGUAGE en -// -// LCD Character Set -// -// Note: This option is NOT applicable to Graphical Displays. -// -// All character-based LCD's provide ASCII plus one of these -// language extensions: -// -// - JAPANESE ... the most common -// - WESTERN ... with more accented characters -// - CYRILLIC ... for the Russian language -// -// To determine the language extension installed on your controller: -// -// - Compile and upload with LCD_LANGUAGE set to 'test' -// - Click the controller to view the LCD menu -// - The LCD will display Japanese, Western, or Cyrillic text -// -// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language -// -// :['JAPANESE', 'WESTERN', 'CYRILLIC'] -// +/** + * LCD Character Set + * + * Note: This option is NOT applicable to Graphical Displays. + * + * All character-based LCDs provide ASCII plus one of these + * language extensions: + * + * - JAPANESE ... the most common + * - WESTERN ... with more accented characters + * - CYRILLIC ... for the Russian language + * + * To determine the language extension installed on your controller: + * + * - Compile and upload with LCD_LANGUAGE set to 'test' + * - Click the controller to view the LCD menu + * - The LCD will display Japanese, Western, or Cyrillic text + * + * See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * + * :['JAPANESE', 'WESTERN', 'CYRILLIC'] + */ #define DISPLAY_CHARSET_HD44780 WESTERN -// -// LCD TYPE -// -// You may choose ULTRA_LCD if you have character based LCD with 16x2, 16x4, 20x2, -// 20x4 char/lines or DOGLCD for the full graphics display with 128x64 pixels -// (ST7565R family). (This option will be set automatically for certain displays.) -// -// IMPORTANT NOTE: The U8glib library is required for Full Graphic Display! -// https://github.com/olikraus/U8glib_Arduino -// +/** + * LCD TYPE + * + * Enable ULTRA_LCD for a 16x2, 16x4, 20x2, or 20x4 character-based LCD. + * Enable DOGLCD for a 128x64 (ST7565R) Full Graphical Display. + * (These options will be enabled automatically for most displays.) + * + * IMPORTANT: The U8glib library is required for Full Graphic Display! + * https://github.com/olikraus/U8glib_Arduino + */ //#define ULTRA_LCD // Character based //#define DOGLCD // Full graphics display -// -// SD CARD -// -// SD Card support is disabled by default. If your controller has an SD slot, -// you must uncomment the following option or it won't work. -// +/** + * SD CARD + * + * SD Card support is disabled by default. If your controller has an SD slot, + * you must uncomment the following option or it won't work. + * + */ #define SDSUPPORT -// -// SD CARD: SPI SPEED -// -// Uncomment ONE of the following items to use a slower SPI transfer -// speed. This is usually required if you're getting volume init errors. -// +/** + * SD CARD: SPI SPEED + * + * Enable one of the following items for a slower SPI transfer speed. + * This may be required to resolve "volume init" errors. + */ //#define SPI_SPEED SPI_HALF_SPEED //#define SPI_SPEED SPI_QUARTER_SPEED //#define SPI_SPEED SPI_EIGHTH_SPEED -// -// SD CARD: ENABLE CRC -// -// Use CRC checks and retries on the SD communication. -// +/** + * SD CARD: ENABLE CRC + * + * Use CRC checks and retries on the SD communication. + */ //#define SD_CHECK_AND_RETRY // @@ -1326,7 +1323,7 @@ */ // -// This option reverses the encoder direction everywhere +// This option reverses the encoder direction everywhere. // // Set this option if CLOCKWISE causes values to DECREASE // diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index d93cd6699..0cceaf4c7 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -1093,23 +1093,17 @@ #define PREHEAT_2_TEMP_BED 100 #define PREHEAT_2_FAN_SPEED 255 // Value from 0 to 255 -// -// Nozzle Park -- EXPERIMENTAL -// -// When enabled allows the user to define a special XYZ position, inside the -// machine's topology, to park the nozzle when idle or when receiving the G27 -// command. -// -// The "P" paramenter controls what is the action applied to the Z axis: -// P0: (Default) If current Z-pos is lower than Z-park then the nozzle will -// be raised to reach Z-park height. -// -// P1: No matter the current Z-pos, the nozzle will be raised/lowered to -// reach Z-park height. -// -// P2: The nozzle height will be raised by Z-park amount but never going over -// the machine's limit of Z_MAX_POS. -// +/** + * Nozzle Park -- EXPERIMENTAL + * + * Park the nozzle at the given XYZ position on idle or G27. + * + * The "P" parameter controls the action applied to the Z axis: + * + * P0 (Default) If Z is below park Z raise the nozzle. + * P1 Raise the nozzle always to Z-park height. + * P2 Raise the nozzle by Z-park amount, limited to Z_MAX_POS. + */ //#define NOZZLE_PARK_FEATURE #if ENABLED(NOZZLE_PARK_FEATURE) @@ -1117,44 +1111,44 @@ #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 } #endif -// -// Clean Nozzle Feature -- EXPERIMENTAL -// -// When enabled allows the user to send G12 to start the nozzle cleaning -// process, the G-Code accepts two parameters: -// "P" for pattern selection -// "S" for defining the number of strokes/repetitions -// -// Available list of patterns: -// P0: This is the default pattern, this process requires a sponge type -// material at a fixed bed location. S defines "strokes" i.e. -// back-and-forth movements between the starting and end points. -// -// P1: This starts a zig-zag pattern between (X0, Y0) and (X1, Y1), "T" -// defines the number of zig-zag triangles to be done. "S" defines the -// number of strokes aka one back-and-forth movement. Zig-zags will -// be performed in whichever dimension is smallest. As an example, -// sending "G12 P1 S1 T3" will execute: -// -// -- -// | (X0, Y1) | /\ /\ /\ | (X1, Y1) -// | | / \ / \ / \ | -// A | | / \ / \ / \ | -// | | / \ / \ / \ | -// | (X0, Y0) | / \/ \/ \ | (X1, Y0) -// -- +--------------------------------+ -// |________|_________|_________| -// T1 T2 T3 -// -// P2: This starts a circular pattern with circle with middle in -// NOZZLE_CLEAN_CIRCLE_MIDDLE radius of R and stroke count of S. -// Before starting the circle nozzle goes to NOZZLE_CLEAN_START_POINT. -// -// Caveats: End point Z should use the same value as Start point Z. -// -// Attention: This is an EXPERIMENTAL feature, in the future the G-code arguments -// may change to add new functionality like different wipe patterns. -// +/** + * Clean Nozzle Feature -- EXPERIMENTAL + * + * Adds the G12 command to perform a nozzle cleaning process. + * + * Parameters: + * P Pattern + * S Strokes / Repetitions + * T Triangles (P1 only) + * + * Patterns: + * P0 Straight line (default). This process requires a sponge type material + * at a fixed bed location. "S" specifies strokes (i.e. back-forth motions) + * between the start / end points. + * + * P1 Zig-zag pattern between (X0, Y0) and (X1, Y1), "T" specifies the + * number of zig-zag triangles to do. "S" defines the number of strokes. + * Zig-zags are done in whichever is the narrower dimension. + * For example, "G12 P1 S1 T3" will execute: + * + * -- + * | (X0, Y1) | /\ /\ /\ | (X1, Y1) + * | | / \ / \ / \ | + * A | | / \ / \ / \ | + * | | / \ / \ / \ | + * | (X0, Y0) | / \/ \/ \ | (X1, Y0) + * -- +--------------------------------+ + * |________|_________|_________| + * T1 T2 T3 + * + * P2 Circular pattern with middle at NOZZLE_CLEAN_CIRCLE_MIDDLE. + * "R" specifies the radius. "S" specifies the stroke count. + * Before starting, the nozzle moves to NOZZLE_CLEAN_START_POINT. + * + * Caveats: The ending Z should be the same as starting Z. + * Attention: EXPERIMENTAL. G-code arguments may change. + * + */ //#define NOZZLE_CLEAN_FEATURE #if ENABLED(NOZZLE_CLEAN_FEATURE) @@ -1179,33 +1173,35 @@ #define NOZZLE_CLEAN_GOBACK #endif -// -// Print job timer -// -// Enable this option to automatically start and stop the -// print job timer when M104/M109/M190 commands are received. -// M104 (extruder without wait) - high temp = none, low temp = stop timer -// M109 (extruder with wait) - high temp = start timer, low temp = stop timer -// M190 (bed with wait) - high temp = start timer, low temp = none -// -// In all cases the timer can be started and stopped using -// the following commands: -// -// - M75 - Start the print job timer -// - M76 - Pause the print job timer -// - M77 - Stop the print job timer +/** + * Print Job Timer + * + * Automatically start and stop the print job timer on M104/M109/M190. + * + * 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 + * + * The timer can also be controlled with the following commands: + * + * M75 - Start the print job timer + * M76 - Pause the print job timer + * M77 - Stop the print job timer + */ #define PRINTJOB_TIMER_AUTOSTART -// -// Print Counter -// -// When enabled Marlin will keep track of some print statistical data such as: -// - Total print jobs -// - Total successful print jobs -// - Total failed print jobs -// - Total time printing -// -// This information can be viewed by the M78 command. +/** + * Print Counter + * + * Track statistical data such as: + * + * - Total print jobs + * - Total successful print jobs + * - Total failed print jobs + * - Total time printing + * + * View the current statistics with M78. + */ //#define PRINTCOUNTER //============================================================================= @@ -1214,78 +1210,79 @@ // @section lcd -// -// LCD LANGUAGE -// -// Here you may choose the language used by Marlin on the LCD menus, the following -// list of languages are available: -// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, -// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test -// -// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } -// +/** + * LCD LANGUAGE + * + * Select the language to display on the LCD. These languages are available: + * + * en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, + * kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test + * + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } + */ #define LCD_LANGUAGE en -// -// LCD Character Set -// -// Note: This option is NOT applicable to Graphical Displays. -// -// All character-based LCD's provide ASCII plus one of these -// language extensions: -// -// - JAPANESE ... the most common -// - WESTERN ... with more accented characters -// - CYRILLIC ... for the Russian language -// -// To determine the language extension installed on your controller: -// -// - Compile and upload with LCD_LANGUAGE set to 'test' -// - Click the controller to view the LCD menu -// - The LCD will display Japanese, Western, or Cyrillic text -// -// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language -// -// :['JAPANESE', 'WESTERN', 'CYRILLIC'] -// +/** + * LCD Character Set + * + * Note: This option is NOT applicable to Graphical Displays. + * + * All character-based LCDs provide ASCII plus one of these + * language extensions: + * + * - JAPANESE ... the most common + * - WESTERN ... with more accented characters + * - CYRILLIC ... for the Russian language + * + * To determine the language extension installed on your controller: + * + * - Compile and upload with LCD_LANGUAGE set to 'test' + * - Click the controller to view the LCD menu + * - The LCD will display Japanese, Western, or Cyrillic text + * + * See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * + * :['JAPANESE', 'WESTERN', 'CYRILLIC'] + */ #define DISPLAY_CHARSET_HD44780 JAPANESE -// -// LCD TYPE -// -// You may choose ULTRA_LCD if you have character based LCD with 16x2, 16x4, 20x2, -// 20x4 char/lines or DOGLCD for the full graphics display with 128x64 pixels -// (ST7565R family). (This option will be set automatically for certain displays.) -// -// IMPORTANT NOTE: The U8glib library is required for Full Graphic Display! -// https://github.com/olikraus/U8glib_Arduino -// +/** + * LCD TYPE + * + * Enable ULTRA_LCD for a 16x2, 16x4, 20x2, or 20x4 character-based LCD. + * Enable DOGLCD for a 128x64 (ST7565R) Full Graphical Display. + * (These options will be enabled automatically for most displays.) + * + * IMPORTANT: The U8glib library is required for Full Graphic Display! + * https://github.com/olikraus/U8glib_Arduino + */ //#define ULTRA_LCD // Character based //#define DOGLCD // Full graphics display -// -// SD CARD -// -// SD Card support is disabled by default. If your controller has an SD slot, -// you must uncomment the following option or it won't work. -// +/** + * SD CARD + * + * SD Card support is disabled by default. If your controller has an SD slot, + * you must uncomment the following option or it won't work. + * + */ //#define SDSUPPORT -// -// SD CARD: SPI SPEED -// -// Uncomment ONE of the following items to use a slower SPI transfer -// speed. This is usually required if you're getting volume init errors. -// +/** + * SD CARD: SPI SPEED + * + * Enable one of the following items for a slower SPI transfer speed. + * This may be required to resolve "volume init" errors. + */ //#define SPI_SPEED SPI_HALF_SPEED //#define SPI_SPEED SPI_QUARTER_SPEED //#define SPI_SPEED SPI_EIGHTH_SPEED -// -// SD CARD: ENABLE CRC -// -// Use CRC checks and retries on the SD communication. -// +/** + * SD CARD: ENABLE CRC + * + * Use CRC checks and retries on the SD communication. + */ //#define SD_CHECK_AND_RETRY // @@ -1313,7 +1310,7 @@ */ // -// This option reverses the encoder direction everywhere +// This option reverses the encoder direction everywhere. // // Set this option if CLOCKWISE causes values to DECREASE // diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index 7d6754fc4..ff3f5b286 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -1096,23 +1096,17 @@ #define PREHEAT_2_TEMP_BED 100 #define PREHEAT_2_FAN_SPEED 255 // Value from 0 to 255 -// -// Nozzle Park -- EXPERIMENTAL -// -// When enabled allows the user to define a special XYZ position, inside the -// machine's topology, to park the nozzle when idle or when receiving the G27 -// command. -// -// The "P" paramenter controls what is the action applied to the Z axis: -// P0: (Default) If current Z-pos is lower than Z-park then the nozzle will -// be raised to reach Z-park height. -// -// P1: No matter the current Z-pos, the nozzle will be raised/lowered to -// reach Z-park height. -// -// P2: The nozzle height will be raised by Z-park amount but never going over -// the machine's limit of Z_MAX_POS. -// +/** + * Nozzle Park -- EXPERIMENTAL + * + * Park the nozzle at the given XYZ position on idle or G27. + * + * The "P" parameter controls the action applied to the Z axis: + * + * P0 (Default) If Z is below park Z raise the nozzle. + * P1 Raise the nozzle always to Z-park height. + * P2 Raise the nozzle by Z-park amount, limited to Z_MAX_POS. + */ //#define NOZZLE_PARK_FEATURE #if ENABLED(NOZZLE_PARK_FEATURE) @@ -1120,44 +1114,44 @@ #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 } #endif -// -// Clean Nozzle Feature -- EXPERIMENTAL -// -// When enabled allows the user to send G12 to start the nozzle cleaning -// process, the G-Code accepts two parameters: -// "P" for pattern selection -// "S" for defining the number of strokes/repetitions -// -// Available list of patterns: -// P0: This is the default pattern, this process requires a sponge type -// material at a fixed bed location. S defines "strokes" i.e. -// back-and-forth movements between the starting and end points. -// -// P1: This starts a zig-zag pattern between (X0, Y0) and (X1, Y1), "T" -// defines the number of zig-zag triangles to be done. "S" defines the -// number of strokes aka one back-and-forth movement. Zig-zags will -// be performed in whichever dimension is smallest. As an example, -// sending "G12 P1 S1 T3" will execute: -// -// -- -// | (X0, Y1) | /\ /\ /\ | (X1, Y1) -// | | / \ / \ / \ | -// A | | / \ / \ / \ | -// | | / \ / \ / \ | -// | (X0, Y0) | / \/ \/ \ | (X1, Y0) -// -- +--------------------------------+ -// |________|_________|_________| -// T1 T2 T3 -// -// P2: This starts a circular pattern with circle with middle in -// NOZZLE_CLEAN_CIRCLE_MIDDLE radius of R and stroke count of S. -// Before starting the circle nozzle goes to NOZZLE_CLEAN_START_POINT. -// -// Caveats: End point Z should use the same value as Start point Z. -// -// Attention: This is an EXPERIMENTAL feature, in the future the G-code arguments -// may change to add new functionality like different wipe patterns. -// +/** + * Clean Nozzle Feature -- EXPERIMENTAL + * + * Adds the G12 command to perform a nozzle cleaning process. + * + * Parameters: + * P Pattern + * S Strokes / Repetitions + * T Triangles (P1 only) + * + * Patterns: + * P0 Straight line (default). This process requires a sponge type material + * at a fixed bed location. "S" specifies strokes (i.e. back-forth motions) + * between the start / end points. + * + * P1 Zig-zag pattern between (X0, Y0) and (X1, Y1), "T" specifies the + * number of zig-zag triangles to do. "S" defines the number of strokes. + * Zig-zags are done in whichever is the narrower dimension. + * For example, "G12 P1 S1 T3" will execute: + * + * -- + * | (X0, Y1) | /\ /\ /\ | (X1, Y1) + * | | / \ / \ / \ | + * A | | / \ / \ / \ | + * | | / \ / \ / \ | + * | (X0, Y0) | / \/ \/ \ | (X1, Y0) + * -- +--------------------------------+ + * |________|_________|_________| + * T1 T2 T3 + * + * P2 Circular pattern with middle at NOZZLE_CLEAN_CIRCLE_MIDDLE. + * "R" specifies the radius. "S" specifies the stroke count. + * Before starting, the nozzle moves to NOZZLE_CLEAN_START_POINT. + * + * Caveats: The ending Z should be the same as starting Z. + * Attention: EXPERIMENTAL. G-code arguments may change. + * + */ //#define NOZZLE_CLEAN_FEATURE #if ENABLED(NOZZLE_CLEAN_FEATURE) @@ -1182,33 +1176,35 @@ #define NOZZLE_CLEAN_GOBACK #endif -// -// Print job timer -// -// Enable this option to automatically start and stop the -// print job timer when M104/M109/M190 commands are received. -// M104 (extruder without wait) - high temp = none, low temp = stop timer -// M109 (extruder with wait) - high temp = start timer, low temp = stop timer -// M190 (bed with wait) - high temp = start timer, low temp = none -// -// In all cases the timer can be started and stopped using -// the following commands: -// -// - M75 - Start the print job timer -// - M76 - Pause the print job timer -// - M77 - Stop the print job timer +/** + * Print Job Timer + * + * Automatically start and stop the print job timer on M104/M109/M190. + * + * 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 + * + * The timer can also be controlled with the following commands: + * + * M75 - Start the print job timer + * M76 - Pause the print job timer + * M77 - Stop the print job timer + */ #define PRINTJOB_TIMER_AUTOSTART -// -// Print Counter -// -// When enabled Marlin will keep track of some print statistical data such as: -// - Total print jobs -// - Total successful print jobs -// - Total failed print jobs -// - Total time printing -// -// This information can be viewed by the M78 command. +/** + * Print Counter + * + * Track statistical data such as: + * + * - Total print jobs + * - Total successful print jobs + * - Total failed print jobs + * - Total time printing + * + * View the current statistics with M78. + */ //#define PRINTCOUNTER //============================================================================= @@ -1217,78 +1213,79 @@ // @section lcd -// -// LCD LANGUAGE -// -// Here you may choose the language used by Marlin on the LCD menus, the following -// list of languages are available: -// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, -// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test -// -// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } -// +/** + * LCD LANGUAGE + * + * Select the language to display on the LCD. These languages are available: + * + * en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, + * kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test + * + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } + */ #define LCD_LANGUAGE en -// -// LCD Character Set -// -// Note: This option is NOT applicable to Graphical Displays. -// -// All character-based LCD's provide ASCII plus one of these -// language extensions: -// -// - JAPANESE ... the most common -// - WESTERN ... with more accented characters -// - CYRILLIC ... for the Russian language -// -// To determine the language extension installed on your controller: -// -// - Compile and upload with LCD_LANGUAGE set to 'test' -// - Click the controller to view the LCD menu -// - The LCD will display Japanese, Western, or Cyrillic text -// -// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language -// -// :['JAPANESE', 'WESTERN', 'CYRILLIC'] -// +/** + * LCD Character Set + * + * Note: This option is NOT applicable to Graphical Displays. + * + * All character-based LCDs provide ASCII plus one of these + * language extensions: + * + * - JAPANESE ... the most common + * - WESTERN ... with more accented characters + * - CYRILLIC ... for the Russian language + * + * To determine the language extension installed on your controller: + * + * - Compile and upload with LCD_LANGUAGE set to 'test' + * - Click the controller to view the LCD menu + * - The LCD will display Japanese, Western, or Cyrillic text + * + * See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * + * :['JAPANESE', 'WESTERN', 'CYRILLIC'] + */ #define DISPLAY_CHARSET_HD44780 JAPANESE -// -// LCD TYPE -// -// You may choose ULTRA_LCD if you have character based LCD with 16x2, 16x4, 20x2, -// 20x4 char/lines or DOGLCD for the full graphics display with 128x64 pixels -// (ST7565R family). (This option will be set automatically for certain displays.) -// -// IMPORTANT NOTE: The U8glib library is required for Full Graphic Display! -// https://github.com/olikraus/U8glib_Arduino -// +/** + * LCD TYPE + * + * Enable ULTRA_LCD for a 16x2, 16x4, 20x2, or 20x4 character-based LCD. + * Enable DOGLCD for a 128x64 (ST7565R) Full Graphical Display. + * (These options will be enabled automatically for most displays.) + * + * IMPORTANT: The U8glib library is required for Full Graphic Display! + * https://github.com/olikraus/U8glib_Arduino + */ //#define ULTRA_LCD // Character based //#define DOGLCD // Full graphics display -// -// SD CARD -// -// SD Card support is disabled by default. If your controller has an SD slot, -// you must uncomment the following option or it won't work. -// +/** + * SD CARD + * + * SD Card support is disabled by default. If your controller has an SD slot, + * you must uncomment the following option or it won't work. + * + */ //#define SDSUPPORT -// -// SD CARD: SPI SPEED -// -// Uncomment ONE of the following items to use a slower SPI transfer -// speed. This is usually required if you're getting volume init errors. -// +/** + * SD CARD: SPI SPEED + * + * Enable one of the following items for a slower SPI transfer speed. + * This may be required to resolve "volume init" errors. + */ //#define SPI_SPEED SPI_HALF_SPEED //#define SPI_SPEED SPI_QUARTER_SPEED //#define SPI_SPEED SPI_EIGHTH_SPEED -// -// SD CARD: ENABLE CRC -// -// Use CRC checks and retries on the SD communication. -// +/** + * SD CARD: ENABLE CRC + * + * Use CRC checks and retries on the SD communication. + */ //#define SD_CHECK_AND_RETRY // @@ -1316,7 +1313,7 @@ */ // -// This option reverses the encoder direction everywhere +// This option reverses the encoder direction everywhere. // // Set this option if CLOCKWISE causes values to DECREASE // diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration.h b/Marlin/example_configurations/delta/kossel_pro/Configuration.h index 244976604..2128469ea 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration.h @@ -1102,23 +1102,17 @@ #define PREHEAT_2_TEMP_BED 100 #define PREHEAT_2_FAN_SPEED 255 // Value from 0 to 255 -// -// Nozzle Park -- EXPERIMENTAL -// -// When enabled allows the user to define a special XYZ position, inside the -// machine's topology, to park the nozzle when idle or when receiving the G27 -// command. -// -// The "P" paramenter controls what is the action applied to the Z axis: -// P0: (Default) If current Z-pos is lower than Z-park then the nozzle will -// be raised to reach Z-park height. -// -// P1: No matter the current Z-pos, the nozzle will be raised/lowered to -// reach Z-park height. -// -// P2: The nozzle height will be raised by Z-park amount but never going over -// the machine's limit of Z_MAX_POS. -// +/** + * Nozzle Park -- EXPERIMENTAL + * + * Park the nozzle at the given XYZ position on idle or G27. + * + * The "P" parameter controls the action applied to the Z axis: + * + * P0 (Default) If Z is below park Z raise the nozzle. + * P1 Raise the nozzle always to Z-park height. + * P2 Raise the nozzle by Z-park amount, limited to Z_MAX_POS. + */ //#define NOZZLE_PARK_FEATURE #if ENABLED(NOZZLE_PARK_FEATURE) @@ -1126,44 +1120,44 @@ #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 } #endif -// -// Clean Nozzle Feature -- EXPERIMENTAL -// -// When enabled allows the user to send G12 to start the nozzle cleaning -// process, the G-Code accepts two parameters: -// "P" for pattern selection -// "S" for defining the number of strokes/repetitions -// -// Available list of patterns: -// P0: This is the default pattern, this process requires a sponge type -// material at a fixed bed location. S defines "strokes" i.e. -// back-and-forth movements between the starting and end points. -// -// P1: This starts a zig-zag pattern between (X0, Y0) and (X1, Y1), "T" -// defines the number of zig-zag triangles to be done. "S" defines the -// number of strokes aka one back-and-forth movement. Zig-zags will -// be performed in whichever dimension is smallest. As an example, -// sending "G12 P1 S1 T3" will execute: -// -// -- -// | (X0, Y1) | /\ /\ /\ | (X1, Y1) -// | | / \ / \ / \ | -// A | | / \ / \ / \ | -// | | / \ / \ / \ | -// | (X0, Y0) | / \/ \/ \ | (X1, Y0) -// -- +--------------------------------+ -// |________|_________|_________| -// T1 T2 T3 -// -// P2: This starts a circular pattern with circle with middle in -// NOZZLE_CLEAN_CIRCLE_MIDDLE radius of R and stroke count of S. -// Before starting the circle nozzle goes to NOZZLE_CLEAN_START_POINT. -// -// Caveats: End point Z should use the same value as Start point Z. -// -// Attention: This is an EXPERIMENTAL feature, in the future the G-code arguments -// may change to add new functionality like different wipe patterns. -// +/** + * Clean Nozzle Feature -- EXPERIMENTAL + * + * Adds the G12 command to perform a nozzle cleaning process. + * + * Parameters: + * P Pattern + * S Strokes / Repetitions + * T Triangles (P1 only) + * + * Patterns: + * P0 Straight line (default). This process requires a sponge type material + * at a fixed bed location. "S" specifies strokes (i.e. back-forth motions) + * between the start / end points. + * + * P1 Zig-zag pattern between (X0, Y0) and (X1, Y1), "T" specifies the + * number of zig-zag triangles to do. "S" defines the number of strokes. + * Zig-zags are done in whichever is the narrower dimension. + * For example, "G12 P1 S1 T3" will execute: + * + * -- + * | (X0, Y1) | /\ /\ /\ | (X1, Y1) + * | | / \ / \ / \ | + * A | | / \ / \ / \ | + * | | / \ / \ / \ | + * | (X0, Y0) | / \/ \/ \ | (X1, Y0) + * -- +--------------------------------+ + * |________|_________|_________| + * T1 T2 T3 + * + * P2 Circular pattern with middle at NOZZLE_CLEAN_CIRCLE_MIDDLE. + * "R" specifies the radius. "S" specifies the stroke count. + * Before starting, the nozzle moves to NOZZLE_CLEAN_START_POINT. + * + * Caveats: The ending Z should be the same as starting Z. + * Attention: EXPERIMENTAL. G-code arguments may change. + * + */ //#define NOZZLE_CLEAN_FEATURE #if ENABLED(NOZZLE_CLEAN_FEATURE) @@ -1188,33 +1182,35 @@ #define NOZZLE_CLEAN_GOBACK #endif -// -// Print job timer -// -// Enable this option to automatically start and stop the -// print job timer when M104/M109/M190 commands are received. -// M104 (extruder without wait) - high temp = none, low temp = stop timer -// M109 (extruder with wait) - high temp = start timer, low temp = stop timer -// M190 (bed with wait) - high temp = start timer, low temp = none -// -// In all cases the timer can be started and stopped using -// the following commands: -// -// - M75 - Start the print job timer -// - M76 - Pause the print job timer -// - M77 - Stop the print job timer +/** + * Print Job Timer + * + * Automatically start and stop the print job timer on M104/M109/M190. + * + * 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 + * + * The timer can also be controlled with the following commands: + * + * M75 - Start the print job timer + * M76 - Pause the print job timer + * M77 - Stop the print job timer + */ #define PRINTJOB_TIMER_AUTOSTART -// -// Print Counter -// -// When enabled Marlin will keep track of some print statistical data such as: -// - Total print jobs -// - Total successful print jobs -// - Total failed print jobs -// - Total time printing -// -// This information can be viewed by the M78 command. +/** + * Print Counter + * + * Track statistical data such as: + * + * - Total print jobs + * - Total successful print jobs + * - Total failed print jobs + * - Total time printing + * + * View the current statistics with M78. + */ //#define PRINTCOUNTER //============================================================================= @@ -1223,78 +1219,79 @@ // @section lcd -// -// LCD LANGUAGE -// -// Here you may choose the language used by Marlin on the LCD menus, the following -// list of languages are available: -// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, -// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test -// -// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } -// +/** + * LCD LANGUAGE + * + * Select the language to display on the LCD. These languages are available: + * + * en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, + * kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test + * + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } + */ #define LCD_LANGUAGE en -// -// LCD Character Set -// -// Note: This option is NOT applicable to Graphical Displays. -// -// All character-based LCD's provide ASCII plus one of these -// language extensions: -// -// - JAPANESE ... the most common -// - WESTERN ... with more accented characters -// - CYRILLIC ... for the Russian language -// -// To determine the language extension installed on your controller: -// -// - Compile and upload with LCD_LANGUAGE set to 'test' -// - Click the controller to view the LCD menu -// - The LCD will display Japanese, Western, or Cyrillic text -// -// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language -// -// :['JAPANESE', 'WESTERN', 'CYRILLIC'] -// +/** + * LCD Character Set + * + * Note: This option is NOT applicable to Graphical Displays. + * + * All character-based LCDs provide ASCII plus one of these + * language extensions: + * + * - JAPANESE ... the most common + * - WESTERN ... with more accented characters + * - CYRILLIC ... for the Russian language + * + * To determine the language extension installed on your controller: + * + * - Compile and upload with LCD_LANGUAGE set to 'test' + * - Click the controller to view the LCD menu + * - The LCD will display Japanese, Western, or Cyrillic text + * + * See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * + * :['JAPANESE', 'WESTERN', 'CYRILLIC'] + */ #define DISPLAY_CHARSET_HD44780 JAPANESE -// -// LCD TYPE -// -// You may choose ULTRA_LCD if you have character based LCD with 16x2, 16x4, 20x2, -// 20x4 char/lines or DOGLCD for the full graphics display with 128x64 pixels -// (ST7565R family). (This option will be set automatically for certain displays.) -// -// IMPORTANT NOTE: The U8glib library is required for Full Graphic Display! -// https://github.com/olikraus/U8glib_Arduino -// +/** + * LCD TYPE + * + * Enable ULTRA_LCD for a 16x2, 16x4, 20x2, or 20x4 character-based LCD. + * Enable DOGLCD for a 128x64 (ST7565R) Full Graphical Display. + * (These options will be enabled automatically for most displays.) + * + * IMPORTANT: The U8glib library is required for Full Graphic Display! + * https://github.com/olikraus/U8glib_Arduino + */ //#define ULTRA_LCD // Character based //#define DOGLCD // Full graphics display -// -// SD CARD -// -// SD Card support is disabled by default. If your controller has an SD slot, -// you must uncomment the following option or it won't work. -// +/** + * SD CARD + * + * SD Card support is disabled by default. If your controller has an SD slot, + * you must uncomment the following option or it won't work. + * + */ #define SDSUPPORT -// -// SD CARD: SPI SPEED -// -// Uncomment ONE of the following items to use a slower SPI transfer -// speed. This is usually required if you're getting volume init errors. -// +/** + * SD CARD: SPI SPEED + * + * Enable one of the following items for a slower SPI transfer speed. + * This may be required to resolve "volume init" errors. + */ //#define SPI_SPEED SPI_HALF_SPEED //#define SPI_SPEED SPI_QUARTER_SPEED //#define SPI_SPEED SPI_EIGHTH_SPEED -// -// SD CARD: ENABLE CRC -// -// Use CRC checks and retries on the SD communication. -// +/** + * SD CARD: ENABLE CRC + * + * Use CRC checks and retries on the SD communication. + */ //#define SD_CHECK_AND_RETRY // @@ -1322,7 +1319,7 @@ */ // -// This option reverses the encoder direction everywhere +// This option reverses the encoder direction everywhere. // // Set this option if CLOCKWISE causes values to DECREASE // diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration.h b/Marlin/example_configurations/delta/kossel_xl/Configuration.h index f3e549470..479b4e466 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration.h @@ -1160,23 +1160,17 @@ #define PREHEAT_2_TEMP_BED 100 #define PREHEAT_2_FAN_SPEED 255 // Value from 0 to 255 -// -// Nozzle Park -- EXPERIMENTAL -// -// When enabled allows the user to define a special XYZ position, inside the -// machine's topology, to park the nozzle when idle or when receiving the G27 -// command. -// -// The "P" paramenter controls what is the action applied to the Z axis: -// P0: (Default) If current Z-pos is lower than Z-park then the nozzle will -// be raised to reach Z-park height. -// -// P1: No matter the current Z-pos, the nozzle will be raised/lowered to -// reach Z-park height. -// -// P2: The nozzle height will be raised by Z-park amount but never going over -// the machine's limit of Z_MAX_POS. -// +/** + * Nozzle Park -- EXPERIMENTAL + * + * Park the nozzle at the given XYZ position on idle or G27. + * + * The "P" parameter controls the action applied to the Z axis: + * + * P0 (Default) If Z is below park Z raise the nozzle. + * P1 Raise the nozzle always to Z-park height. + * P2 Raise the nozzle by Z-park amount, limited to Z_MAX_POS. + */ //#define NOZZLE_PARK_FEATURE #if ENABLED(NOZZLE_PARK_FEATURE) @@ -1184,44 +1178,44 @@ #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 } #endif -// -// Clean Nozzle Feature -- EXPERIMENTAL -// -// When enabled allows the user to send G12 to start the nozzle cleaning -// process, the G-Code accepts two parameters: -// "P" for pattern selection -// "S" for defining the number of strokes/repetitions -// -// Available list of patterns: -// P0: This is the default pattern, this process requires a sponge type -// material at a fixed bed location. S defines "strokes" i.e. -// back-and-forth movements between the starting and end points. -// -// P1: This starts a zig-zag pattern between (X0, Y0) and (X1, Y1), "T" -// defines the number of zig-zag triangles to be done. "S" defines the -// number of strokes aka one back-and-forth movement. Zig-zags will -// be performed in whichever dimension is smallest. As an example, -// sending "G12 P1 S1 T3" will execute: -// -// -- -// | (X0, Y1) | /\ /\ /\ | (X1, Y1) -// | | / \ / \ / \ | -// A | | / \ / \ / \ | -// | | / \ / \ / \ | -// | (X0, Y0) | / \/ \/ \ | (X1, Y0) -// -- +--------------------------------+ -// |________|_________|_________| -// T1 T2 T3 -// -// P2: This starts a circular pattern with circle with middle in -// NOZZLE_CLEAN_CIRCLE_MIDDLE radius of R and stroke count of S. -// Before starting the circle nozzle goes to NOZZLE_CLEAN_START_POINT. -// -// Caveats: End point Z should use the same value as Start point Z. -// -// Attention: This is an EXPERIMENTAL feature, in the future the G-code arguments -// may change to add new functionality like different wipe patterns. -// +/** + * Clean Nozzle Feature -- EXPERIMENTAL + * + * Adds the G12 command to perform a nozzle cleaning process. + * + * Parameters: + * P Pattern + * S Strokes / Repetitions + * T Triangles (P1 only) + * + * Patterns: + * P0 Straight line (default). This process requires a sponge type material + * at a fixed bed location. "S" specifies strokes (i.e. back-forth motions) + * between the start / end points. + * + * P1 Zig-zag pattern between (X0, Y0) and (X1, Y1), "T" specifies the + * number of zig-zag triangles to do. "S" defines the number of strokes. + * Zig-zags are done in whichever is the narrower dimension. + * For example, "G12 P1 S1 T3" will execute: + * + * -- + * | (X0, Y1) | /\ /\ /\ | (X1, Y1) + * | | / \ / \ / \ | + * A | | / \ / \ / \ | + * | | / \ / \ / \ | + * | (X0, Y0) | / \/ \/ \ | (X1, Y0) + * -- +--------------------------------+ + * |________|_________|_________| + * T1 T2 T3 + * + * P2 Circular pattern with middle at NOZZLE_CLEAN_CIRCLE_MIDDLE. + * "R" specifies the radius. "S" specifies the stroke count. + * Before starting, the nozzle moves to NOZZLE_CLEAN_START_POINT. + * + * Caveats: The ending Z should be the same as starting Z. + * Attention: EXPERIMENTAL. G-code arguments may change. + * + */ //#define NOZZLE_CLEAN_FEATURE #if ENABLED(NOZZLE_CLEAN_FEATURE) @@ -1246,33 +1240,35 @@ #define NOZZLE_CLEAN_GOBACK #endif -// -// Print job timer -// -// Enable this option to automatically start and stop the -// print job timer when M104/M109/M190 commands are received. -// M104 (extruder without wait) - high temp = none, low temp = stop timer -// M109 (extruder with wait) - high temp = start timer, low temp = stop timer -// M190 (bed with wait) - high temp = start timer, low temp = none -// -// In all cases the timer can be started and stopped using -// the following commands: -// -// - M75 - Start the print job timer -// - M76 - Pause the print job timer -// - M77 - Stop the print job timer +/** + * Print Job Timer + * + * Automatically start and stop the print job timer on M104/M109/M190. + * + * 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 + * + * The timer can also be controlled with the following commands: + * + * M75 - Start the print job timer + * M76 - Pause the print job timer + * M77 - Stop the print job timer + */ #define PRINTJOB_TIMER_AUTOSTART -// -// Print Counter -// -// When enabled Marlin will keep track of some print statistical data such as: -// - Total print jobs -// - Total successful print jobs -// - Total failed print jobs -// - Total time printing -// -// This information can be viewed by the M78 command. +/** + * Print Counter + * + * Track statistical data such as: + * + * - Total print jobs + * - Total successful print jobs + * - Total failed print jobs + * - Total time printing + * + * View the current statistics with M78. + */ //#define PRINTCOUNTER //============================================================================= @@ -1281,78 +1277,79 @@ // @section lcd -// -// LCD LANGUAGE -// -// Here you may choose the language used by Marlin on the LCD menus, the following -// list of languages are available: -// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, -// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test -// -// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } -// +/** + * LCD LANGUAGE + * + * Select the language to display on the LCD. These languages are available: + * + * en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, + * kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test + * + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } + */ #define LCD_LANGUAGE en -// -// LCD Character Set -// -// Note: This option is NOT applicable to Graphical Displays. -// -// All character-based LCD's provide ASCII plus one of these -// language extensions: -// -// - JAPANESE ... the most common -// - WESTERN ... with more accented characters -// - CYRILLIC ... for the Russian language -// -// To determine the language extension installed on your controller: -// -// - Compile and upload with LCD_LANGUAGE set to 'test' -// - Click the controller to view the LCD menu -// - The LCD will display Japanese, Western, or Cyrillic text -// -// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language -// -// :['JAPANESE', 'WESTERN', 'CYRILLIC'] -// +/** + * LCD Character Set + * + * Note: This option is NOT applicable to Graphical Displays. + * + * All character-based LCDs provide ASCII plus one of these + * language extensions: + * + * - JAPANESE ... the most common + * - WESTERN ... with more accented characters + * - CYRILLIC ... for the Russian language + * + * To determine the language extension installed on your controller: + * + * - Compile and upload with LCD_LANGUAGE set to 'test' + * - Click the controller to view the LCD menu + * - The LCD will display Japanese, Western, or Cyrillic text + * + * See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * + * :['JAPANESE', 'WESTERN', 'CYRILLIC'] + */ #define DISPLAY_CHARSET_HD44780 JAPANESE -// -// LCD TYPE -// -// You may choose ULTRA_LCD if you have character based LCD with 16x2, 16x4, 20x2, -// 20x4 char/lines or DOGLCD for the full graphics display with 128x64 pixels -// (ST7565R family). (This option will be set automatically for certain displays.) -// -// IMPORTANT NOTE: The U8glib library is required for Full Graphic Display! -// https://github.com/olikraus/U8glib_Arduino -// +/** + * LCD TYPE + * + * Enable ULTRA_LCD for a 16x2, 16x4, 20x2, or 20x4 character-based LCD. + * Enable DOGLCD for a 128x64 (ST7565R) Full Graphical Display. + * (These options will be enabled automatically for most displays.) + * + * IMPORTANT: The U8glib library is required for Full Graphic Display! + * https://github.com/olikraus/U8glib_Arduino + */ //#define ULTRA_LCD // Character based //#define DOGLCD // Full graphics display -// -// SD CARD -// -// SD Card support is disabled by default. If your controller has an SD slot, -// you must uncomment the following option or it won't work. -// +/** + * SD CARD + * + * SD Card support is disabled by default. If your controller has an SD slot, + * you must uncomment the following option or it won't work. + * + */ //#define SDSUPPORT -// -// SD CARD: SPI SPEED -// -// Uncomment ONE of the following items to use a slower SPI transfer -// speed. This is usually required if you're getting volume init errors. -// +/** + * SD CARD: SPI SPEED + * + * Enable one of the following items for a slower SPI transfer speed. + * This may be required to resolve "volume init" errors. + */ //#define SPI_SPEED SPI_HALF_SPEED //#define SPI_SPEED SPI_QUARTER_SPEED //#define SPI_SPEED SPI_EIGHTH_SPEED -// -// SD CARD: ENABLE CRC -// -// Use CRC checks and retries on the SD communication. -// +/** + * SD CARD: ENABLE CRC + * + * Use CRC checks and retries on the SD communication. + */ //#define SD_CHECK_AND_RETRY // @@ -1380,7 +1377,7 @@ */ // -// This option reverses the encoder direction everywhere +// This option reverses the encoder direction everywhere. // // Set this option if CLOCKWISE causes values to DECREASE // diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h index a841fb604..62ccbfefa 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h @@ -971,23 +971,17 @@ #define PREHEAT_2_TEMP_BED 110 #define PREHEAT_2_FAN_SPEED 0 // Value from 0 to 255 -// -// Nozzle Park -- EXPERIMENTAL -// -// When enabled allows the user to define a special XYZ position, inside the -// machine's topology, to park the nozzle when idle or when receiving the G27 -// command. -// -// The "P" paramenter controls what is the action applied to the Z axis: -// P0: (Default) If current Z-pos is lower than Z-park then the nozzle will -// be raised to reach Z-park height. -// -// P1: No matter the current Z-pos, the nozzle will be raised/lowered to -// reach Z-park height. -// -// P2: The nozzle height will be raised by Z-park amount but never going over -// the machine's limit of Z_MAX_POS. -// +/** + * Nozzle Park -- EXPERIMENTAL + * + * Park the nozzle at the given XYZ position on idle or G27. + * + * The "P" parameter controls the action applied to the Z axis: + * + * P0 (Default) If Z is below park Z raise the nozzle. + * P1 Raise the nozzle always to Z-park height. + * P2 Raise the nozzle by Z-park amount, limited to Z_MAX_POS. + */ //#define NOZZLE_PARK_FEATURE #if ENABLED(NOZZLE_PARK_FEATURE) @@ -995,44 +989,44 @@ #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 } #endif -// -// Clean Nozzle Feature -- EXPERIMENTAL -// -// When enabled allows the user to send G12 to start the nozzle cleaning -// process, the G-Code accepts two parameters: -// "P" for pattern selection -// "S" for defining the number of strokes/repetitions -// -// Available list of patterns: -// P0: This is the default pattern, this process requires a sponge type -// material at a fixed bed location. S defines "strokes" i.e. -// back-and-forth movements between the starting and end points. -// -// P1: This starts a zig-zag pattern between (X0, Y0) and (X1, Y1), "T" -// defines the number of zig-zag triangles to be done. "S" defines the -// number of strokes aka one back-and-forth movement. Zig-zags will -// be performed in whichever dimension is smallest. As an example, -// sending "G12 P1 S1 T3" will execute: -// -// -- -// | (X0, Y1) | /\ /\ /\ | (X1, Y1) -// | | / \ / \ / \ | -// A | | / \ / \ / \ | -// | | / \ / \ / \ | -// | (X0, Y0) | / \/ \/ \ | (X1, Y0) -// -- +--------------------------------+ -// |________|_________|_________| -// T1 T2 T3 -// -// P2: This starts a circular pattern with circle with middle in -// NOZZLE_CLEAN_CIRCLE_MIDDLE radius of R and stroke count of S. -// Before starting the circle nozzle goes to NOZZLE_CLEAN_START_POINT. -// -// Caveats: End point Z should use the same value as Start point Z. -// -// Attention: This is an EXPERIMENTAL feature, in the future the G-code arguments -// may change to add new functionality like different wipe patterns. -// +/** + * Clean Nozzle Feature -- EXPERIMENTAL + * + * Adds the G12 command to perform a nozzle cleaning process. + * + * Parameters: + * P Pattern + * S Strokes / Repetitions + * T Triangles (P1 only) + * + * Patterns: + * P0 Straight line (default). This process requires a sponge type material + * at a fixed bed location. "S" specifies strokes (i.e. back-forth motions) + * between the start / end points. + * + * P1 Zig-zag pattern between (X0, Y0) and (X1, Y1), "T" specifies the + * number of zig-zag triangles to do. "S" defines the number of strokes. + * Zig-zags are done in whichever is the narrower dimension. + * For example, "G12 P1 S1 T3" will execute: + * + * -- + * | (X0, Y1) | /\ /\ /\ | (X1, Y1) + * | | / \ / \ / \ | + * A | | / \ / \ / \ | + * | | / \ / \ / \ | + * | (X0, Y0) | / \/ \/ \ | (X1, Y0) + * -- +--------------------------------+ + * |________|_________|_________| + * T1 T2 T3 + * + * P2 Circular pattern with middle at NOZZLE_CLEAN_CIRCLE_MIDDLE. + * "R" specifies the radius. "S" specifies the stroke count. + * Before starting, the nozzle moves to NOZZLE_CLEAN_START_POINT. + * + * Caveats: The ending Z should be the same as starting Z. + * Attention: EXPERIMENTAL. G-code arguments may change. + * + */ //#define NOZZLE_CLEAN_FEATURE #if ENABLED(NOZZLE_CLEAN_FEATURE) @@ -1057,33 +1051,35 @@ #define NOZZLE_CLEAN_GOBACK #endif -// -// Print job timer -// -// Enable this option to automatically start and stop the -// print job timer when M104/M109/M190 commands are received. -// M104 (extruder without wait) - high temp = none, low temp = stop timer -// M109 (extruder with wait) - high temp = start timer, low temp = stop timer -// M190 (bed with wait) - high temp = start timer, low temp = none -// -// In all cases the timer can be started and stopped using -// the following commands: -// -// - M75 - Start the print job timer -// - M76 - Pause the print job timer -// - M77 - Stop the print job timer +/** + * Print Job Timer + * + * Automatically start and stop the print job timer on M104/M109/M190. + * + * 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 + * + * The timer can also be controlled with the following commands: + * + * M75 - Start the print job timer + * M76 - Pause the print job timer + * M77 - Stop the print job timer + */ #define PRINTJOB_TIMER_AUTOSTART -// -// Print Counter -// -// When enabled Marlin will keep track of some print statistical data such as: -// - Total print jobs -// - Total successful print jobs -// - Total failed print jobs -// - Total time printing -// -// This information can be viewed by the M78 command. +/** + * Print Counter + * + * Track statistical data such as: + * + * - Total print jobs + * - Total successful print jobs + * - Total failed print jobs + * - Total time printing + * + * View the current statistics with M78. + */ //#define PRINTCOUNTER //============================================================================= @@ -1092,78 +1088,79 @@ // @section lcd -// -// LCD LANGUAGE -// -// Here you may choose the language used by Marlin on the LCD menus, the following -// list of languages are available: -// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, -// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test -// -// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } -// +/** + * LCD LANGUAGE + * + * Select the language to display on the LCD. These languages are available: + * + * en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, + * kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test + * + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } + */ #define LCD_LANGUAGE en -// -// LCD Character Set -// -// Note: This option is NOT applicable to Graphical Displays. -// -// All character-based LCD's provide ASCII plus one of these -// language extensions: -// -// - JAPANESE ... the most common -// - WESTERN ... with more accented characters -// - CYRILLIC ... for the Russian language -// -// To determine the language extension installed on your controller: -// -// - Compile and upload with LCD_LANGUAGE set to 'test' -// - Click the controller to view the LCD menu -// - The LCD will display Japanese, Western, or Cyrillic text -// -// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language -// -// :['JAPANESE', 'WESTERN', 'CYRILLIC'] -// +/** + * LCD Character Set + * + * Note: This option is NOT applicable to Graphical Displays. + * + * All character-based LCDs provide ASCII plus one of these + * language extensions: + * + * - JAPANESE ... the most common + * - WESTERN ... with more accented characters + * - CYRILLIC ... for the Russian language + * + * To determine the language extension installed on your controller: + * + * - Compile and upload with LCD_LANGUAGE set to 'test' + * - Click the controller to view the LCD menu + * - The LCD will display Japanese, Western, or Cyrillic text + * + * See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * + * :['JAPANESE', 'WESTERN', 'CYRILLIC'] + */ #define DISPLAY_CHARSET_HD44780 JAPANESE -// -// LCD TYPE -// -// You may choose ULTRA_LCD if you have character based LCD with 16x2, 16x4, 20x2, -// 20x4 char/lines or DOGLCD for the full graphics display with 128x64 pixels -// (ST7565R family). (This option will be set automatically for certain displays.) -// -// IMPORTANT NOTE: The U8glib library is required for Full Graphic Display! -// https://github.com/olikraus/U8glib_Arduino -// +/** + * LCD TYPE + * + * Enable ULTRA_LCD for a 16x2, 16x4, 20x2, or 20x4 character-based LCD. + * Enable DOGLCD for a 128x64 (ST7565R) Full Graphical Display. + * (These options will be enabled automatically for most displays.) + * + * IMPORTANT: The U8glib library is required for Full Graphic Display! + * https://github.com/olikraus/U8glib_Arduino + */ //#define ULTRA_LCD // Character based //#define DOGLCD // Full graphics display -// -// SD CARD -// -// SD Card support is disabled by default. If your controller has an SD slot, -// you must uncomment the following option or it won't work. -// +/** + * SD CARD + * + * SD Card support is disabled by default. If your controller has an SD slot, + * you must uncomment the following option or it won't work. + * + */ #define SDSUPPORT -// -// SD CARD: SPI SPEED -// -// Uncomment ONE of the following items to use a slower SPI transfer -// speed. This is usually required if you're getting volume init errors. -// +/** + * SD CARD: SPI SPEED + * + * Enable one of the following items for a slower SPI transfer speed. + * This may be required to resolve "volume init" errors. + */ //#define SPI_SPEED SPI_HALF_SPEED //#define SPI_SPEED SPI_QUARTER_SPEED //#define SPI_SPEED SPI_EIGHTH_SPEED -// -// SD CARD: ENABLE CRC -// -// Use CRC checks and retries on the SD communication. -// +/** + * SD CARD: ENABLE CRC + * + * Use CRC checks and retries on the SD communication. + */ #define SD_CHECK_AND_RETRY // @@ -1191,7 +1188,7 @@ */ // -// This option reverses the encoder direction everywhere +// This option reverses the encoder direction everywhere. // // Set this option if CLOCKWISE causes values to DECREASE // diff --git a/Marlin/example_configurations/makibox/Configuration.h b/Marlin/example_configurations/makibox/Configuration.h index 1a4d79019..735278440 100644 --- a/Marlin/example_configurations/makibox/Configuration.h +++ b/Marlin/example_configurations/makibox/Configuration.h @@ -989,23 +989,17 @@ #define PREHEAT_2_TEMP_BED 100 #define PREHEAT_2_FAN_SPEED 255 // Value from 0 to 255 -// -// Nozzle Park -- EXPERIMENTAL -// -// When enabled allows the user to define a special XYZ position, inside the -// machine's topology, to park the nozzle when idle or when receiving the G27 -// command. -// -// The "P" paramenter controls what is the action applied to the Z axis: -// P0: (Default) If current Z-pos is lower than Z-park then the nozzle will -// be raised to reach Z-park height. -// -// P1: No matter the current Z-pos, the nozzle will be raised/lowered to -// reach Z-park height. -// -// P2: The nozzle height will be raised by Z-park amount but never going over -// the machine's limit of Z_MAX_POS. -// +/** + * Nozzle Park -- EXPERIMENTAL + * + * Park the nozzle at the given XYZ position on idle or G27. + * + * The "P" parameter controls the action applied to the Z axis: + * + * P0 (Default) If Z is below park Z raise the nozzle. + * P1 Raise the nozzle always to Z-park height. + * P2 Raise the nozzle by Z-park amount, limited to Z_MAX_POS. + */ //#define NOZZLE_PARK_FEATURE #if ENABLED(NOZZLE_PARK_FEATURE) @@ -1013,44 +1007,44 @@ #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 } #endif -// -// Clean Nozzle Feature -- EXPERIMENTAL -// -// When enabled allows the user to send G12 to start the nozzle cleaning -// process, the G-Code accepts two parameters: -// "P" for pattern selection -// "S" for defining the number of strokes/repetitions -// -// Available list of patterns: -// P0: This is the default pattern, this process requires a sponge type -// material at a fixed bed location. S defines "strokes" i.e. -// back-and-forth movements between the starting and end points. -// -// P1: This starts a zig-zag pattern between (X0, Y0) and (X1, Y1), "T" -// defines the number of zig-zag triangles to be done. "S" defines the -// number of strokes aka one back-and-forth movement. Zig-zags will -// be performed in whichever dimension is smallest. As an example, -// sending "G12 P1 S1 T3" will execute: -// -// -- -// | (X0, Y1) | /\ /\ /\ | (X1, Y1) -// | | / \ / \ / \ | -// A | | / \ / \ / \ | -// | | / \ / \ / \ | -// | (X0, Y0) | / \/ \/ \ | (X1, Y0) -// -- +--------------------------------+ -// |________|_________|_________| -// T1 T2 T3 -// -// P2: This starts a circular pattern with circle with middle in -// NOZZLE_CLEAN_CIRCLE_MIDDLE radius of R and stroke count of S. -// Before starting the circle nozzle goes to NOZZLE_CLEAN_START_POINT. -// -// Caveats: End point Z should use the same value as Start point Z. -// -// Attention: This is an EXPERIMENTAL feature, in the future the G-code arguments -// may change to add new functionality like different wipe patterns. -// +/** + * Clean Nozzle Feature -- EXPERIMENTAL + * + * Adds the G12 command to perform a nozzle cleaning process. + * + * Parameters: + * P Pattern + * S Strokes / Repetitions + * T Triangles (P1 only) + * + * Patterns: + * P0 Straight line (default). This process requires a sponge type material + * at a fixed bed location. "S" specifies strokes (i.e. back-forth motions) + * between the start / end points. + * + * P1 Zig-zag pattern between (X0, Y0) and (X1, Y1), "T" specifies the + * number of zig-zag triangles to do. "S" defines the number of strokes. + * Zig-zags are done in whichever is the narrower dimension. + * For example, "G12 P1 S1 T3" will execute: + * + * -- + * | (X0, Y1) | /\ /\ /\ | (X1, Y1) + * | | / \ / \ / \ | + * A | | / \ / \ / \ | + * | | / \ / \ / \ | + * | (X0, Y0) | / \/ \/ \ | (X1, Y0) + * -- +--------------------------------+ + * |________|_________|_________| + * T1 T2 T3 + * + * P2 Circular pattern with middle at NOZZLE_CLEAN_CIRCLE_MIDDLE. + * "R" specifies the radius. "S" specifies the stroke count. + * Before starting, the nozzle moves to NOZZLE_CLEAN_START_POINT. + * + * Caveats: The ending Z should be the same as starting Z. + * Attention: EXPERIMENTAL. G-code arguments may change. + * + */ //#define NOZZLE_CLEAN_FEATURE #if ENABLED(NOZZLE_CLEAN_FEATURE) @@ -1075,33 +1069,35 @@ #define NOZZLE_CLEAN_GOBACK #endif -// -// Print job timer -// -// Enable this option to automatically start and stop the -// print job timer when M104/M109/M190 commands are received. -// M104 (extruder without wait) - high temp = none, low temp = stop timer -// M109 (extruder with wait) - high temp = start timer, low temp = stop timer -// M190 (bed with wait) - high temp = start timer, low temp = none -// -// In all cases the timer can be started and stopped using -// the following commands: -// -// - M75 - Start the print job timer -// - M76 - Pause the print job timer -// - M77 - Stop the print job timer +/** + * Print Job Timer + * + * Automatically start and stop the print job timer on M104/M109/M190. + * + * 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 + * + * The timer can also be controlled with the following commands: + * + * M75 - Start the print job timer + * M76 - Pause the print job timer + * M77 - Stop the print job timer + */ #define PRINTJOB_TIMER_AUTOSTART -// -// Print Counter -// -// When enabled Marlin will keep track of some print statistical data such as: -// - Total print jobs -// - Total successful print jobs -// - Total failed print jobs -// - Total time printing -// -// This information can be viewed by the M78 command. +/** + * Print Counter + * + * Track statistical data such as: + * + * - Total print jobs + * - Total successful print jobs + * - Total failed print jobs + * - Total time printing + * + * View the current statistics with M78. + */ //#define PRINTCOUNTER //============================================================================= @@ -1110,78 +1106,79 @@ // @section lcd -// -// LCD LANGUAGE -// -// Here you may choose the language used by Marlin on the LCD menus, the following -// list of languages are available: -// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, -// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test -// -// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } -// +/** + * LCD LANGUAGE + * + * Select the language to display on the LCD. These languages are available: + * + * en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, + * kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test + * + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } + */ //#define LCD_LANGUAGE en -// -// LCD Character Set -// -// Note: This option is NOT applicable to Graphical Displays. -// -// All character-based LCD's provide ASCII plus one of these -// language extensions: -// -// - JAPANESE ... the most common -// - WESTERN ... with more accented characters -// - CYRILLIC ... for the Russian language -// -// To determine the language extension installed on your controller: -// -// - Compile and upload with LCD_LANGUAGE set to 'test' -// - Click the controller to view the LCD menu -// - The LCD will display Japanese, Western, or Cyrillic text -// -// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language -// -// :['JAPANESE', 'WESTERN', 'CYRILLIC'] -// +/** + * LCD Character Set + * + * Note: This option is NOT applicable to Graphical Displays. + * + * All character-based LCDs provide ASCII plus one of these + * language extensions: + * + * - JAPANESE ... the most common + * - WESTERN ... with more accented characters + * - CYRILLIC ... for the Russian language + * + * To determine the language extension installed on your controller: + * + * - Compile and upload with LCD_LANGUAGE set to 'test' + * - Click the controller to view the LCD menu + * - The LCD will display Japanese, Western, or Cyrillic text + * + * See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * + * :['JAPANESE', 'WESTERN', 'CYRILLIC'] + */ #define DISPLAY_CHARSET_HD44780 JAPANESE -// -// LCD TYPE -// -// You may choose ULTRA_LCD if you have character based LCD with 16x2, 16x4, 20x2, -// 20x4 char/lines or DOGLCD for the full graphics display with 128x64 pixels -// (ST7565R family). (This option will be set automatically for certain displays.) -// -// IMPORTANT NOTE: The U8glib library is required for Full Graphic Display! -// https://github.com/olikraus/U8glib_Arduino -// +/** + * LCD TYPE + * + * Enable ULTRA_LCD for a 16x2, 16x4, 20x2, or 20x4 character-based LCD. + * Enable DOGLCD for a 128x64 (ST7565R) Full Graphical Display. + * (These options will be enabled automatically for most displays.) + * + * IMPORTANT: The U8glib library is required for Full Graphic Display! + * https://github.com/olikraus/U8glib_Arduino + */ //#define ULTRA_LCD // Character based //#define DOGLCD // Full graphics display -// -// SD CARD -// -// SD Card support is disabled by default. If your controller has an SD slot, -// you must uncomment the following option or it won't work. -// +/** + * SD CARD + * + * SD Card support is disabled by default. If your controller has an SD slot, + * you must uncomment the following option or it won't work. + * + */ #define SDSUPPORT -// -// SD CARD: SPI SPEED -// -// Uncomment ONE of the following items to use a slower SPI transfer -// speed. This is usually required if you're getting volume init errors. -// +/** + * SD CARD: SPI SPEED + * + * Enable one of the following items for a slower SPI transfer speed. + * This may be required to resolve "volume init" errors. + */ #define SPI_SPEED SPI_HALF_SPEED //#define SPI_SPEED SPI_QUARTER_SPEED //#define SPI_SPEED SPI_EIGHTH_SPEED -// -// SD CARD: ENABLE CRC -// -// Use CRC checks and retries on the SD communication. -// +/** + * SD CARD: ENABLE CRC + * + * Use CRC checks and retries on the SD communication. + */ //#define SD_CHECK_AND_RETRY // @@ -1209,7 +1206,7 @@ */ // -// This option reverses the encoder direction everywhere +// This option reverses the encoder direction everywhere. // // Set this option if CLOCKWISE causes values to DECREASE // diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration.h b/Marlin/example_configurations/tvrrug/Round2/Configuration.h index 0caad869f..ec6485eab 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration.h @@ -982,23 +982,17 @@ #define PREHEAT_2_TEMP_BED 100 #define PREHEAT_2_FAN_SPEED 255 // Value from 0 to 255 -// -// Nozzle Park -- EXPERIMENTAL -// -// When enabled allows the user to define a special XYZ position, inside the -// machine's topology, to park the nozzle when idle or when receiving the G27 -// command. -// -// The "P" paramenter controls what is the action applied to the Z axis: -// P0: (Default) If current Z-pos is lower than Z-park then the nozzle will -// be raised to reach Z-park height. -// -// P1: No matter the current Z-pos, the nozzle will be raised/lowered to -// reach Z-park height. -// -// P2: The nozzle height will be raised by Z-park amount but never going over -// the machine's limit of Z_MAX_POS. -// +/** + * Nozzle Park -- EXPERIMENTAL + * + * Park the nozzle at the given XYZ position on idle or G27. + * + * The "P" parameter controls the action applied to the Z axis: + * + * P0 (Default) If Z is below park Z raise the nozzle. + * P1 Raise the nozzle always to Z-park height. + * P2 Raise the nozzle by Z-park amount, limited to Z_MAX_POS. + */ //#define NOZZLE_PARK_FEATURE #if ENABLED(NOZZLE_PARK_FEATURE) @@ -1006,44 +1000,44 @@ #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 } #endif -// -// Clean Nozzle Feature -- EXPERIMENTAL -// -// When enabled allows the user to send G12 to start the nozzle cleaning -// process, the G-Code accepts two parameters: -// "P" for pattern selection -// "S" for defining the number of strokes/repetitions -// -// Available list of patterns: -// P0: This is the default pattern, this process requires a sponge type -// material at a fixed bed location. S defines "strokes" i.e. -// back-and-forth movements between the starting and end points. -// -// P1: This starts a zig-zag pattern between (X0, Y0) and (X1, Y1), "T" -// defines the number of zig-zag triangles to be done. "S" defines the -// number of strokes aka one back-and-forth movement. Zig-zags will -// be performed in whichever dimension is smallest. As an example, -// sending "G12 P1 S1 T3" will execute: -// -// -- -// | (X0, Y1) | /\ /\ /\ | (X1, Y1) -// | | / \ / \ / \ | -// A | | / \ / \ / \ | -// | | / \ / \ / \ | -// | (X0, Y0) | / \/ \/ \ | (X1, Y0) -// -- +--------------------------------+ -// |________|_________|_________| -// T1 T2 T3 -// -// P2: This starts a circular pattern with circle with middle in -// NOZZLE_CLEAN_CIRCLE_MIDDLE radius of R and stroke count of S. -// Before starting the circle nozzle goes to NOZZLE_CLEAN_START_POINT. -// -// Caveats: End point Z should use the same value as Start point Z. -// -// Attention: This is an EXPERIMENTAL feature, in the future the G-code arguments -// may change to add new functionality like different wipe patterns. -// +/** + * Clean Nozzle Feature -- EXPERIMENTAL + * + * Adds the G12 command to perform a nozzle cleaning process. + * + * Parameters: + * P Pattern + * S Strokes / Repetitions + * T Triangles (P1 only) + * + * Patterns: + * P0 Straight line (default). This process requires a sponge type material + * at a fixed bed location. "S" specifies strokes (i.e. back-forth motions) + * between the start / end points. + * + * P1 Zig-zag pattern between (X0, Y0) and (X1, Y1), "T" specifies the + * number of zig-zag triangles to do. "S" defines the number of strokes. + * Zig-zags are done in whichever is the narrower dimension. + * For example, "G12 P1 S1 T3" will execute: + * + * -- + * | (X0, Y1) | /\ /\ /\ | (X1, Y1) + * | | / \ / \ / \ | + * A | | / \ / \ / \ | + * | | / \ / \ / \ | + * | (X0, Y0) | / \/ \/ \ | (X1, Y0) + * -- +--------------------------------+ + * |________|_________|_________| + * T1 T2 T3 + * + * P2 Circular pattern with middle at NOZZLE_CLEAN_CIRCLE_MIDDLE. + * "R" specifies the radius. "S" specifies the stroke count. + * Before starting, the nozzle moves to NOZZLE_CLEAN_START_POINT. + * + * Caveats: The ending Z should be the same as starting Z. + * Attention: EXPERIMENTAL. G-code arguments may change. + * + */ //#define NOZZLE_CLEAN_FEATURE #if ENABLED(NOZZLE_CLEAN_FEATURE) @@ -1068,33 +1062,35 @@ #define NOZZLE_CLEAN_GOBACK #endif -// -// Print job timer -// -// Enable this option to automatically start and stop the -// print job timer when M104/M109/M190 commands are received. -// M104 (extruder without wait) - high temp = none, low temp = stop timer -// M109 (extruder with wait) - high temp = start timer, low temp = stop timer -// M190 (bed with wait) - high temp = start timer, low temp = none -// -// In all cases the timer can be started and stopped using -// the following commands: -// -// - M75 - Start the print job timer -// - M76 - Pause the print job timer -// - M77 - Stop the print job timer +/** + * Print Job Timer + * + * Automatically start and stop the print job timer on M104/M109/M190. + * + * 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 + * + * The timer can also be controlled with the following commands: + * + * M75 - Start the print job timer + * M76 - Pause the print job timer + * M77 - Stop the print job timer + */ #define PRINTJOB_TIMER_AUTOSTART -// -// Print Counter -// -// When enabled Marlin will keep track of some print statistical data such as: -// - Total print jobs -// - Total successful print jobs -// - Total failed print jobs -// - Total time printing -// -// This information can be viewed by the M78 command. +/** + * Print Counter + * + * Track statistical data such as: + * + * - Total print jobs + * - Total successful print jobs + * - Total failed print jobs + * - Total time printing + * + * View the current statistics with M78. + */ //#define PRINTCOUNTER //============================================================================= @@ -1103,78 +1099,79 @@ // @section lcd -// -// LCD LANGUAGE -// -// Here you may choose the language used by Marlin on the LCD menus, the following -// list of languages are available: -// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, -// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test -// -// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } -// +/** + * LCD LANGUAGE + * + * Select the language to display on the LCD. These languages are available: + * + * en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, + * kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test + * + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } + */ //#define LCD_LANGUAGE en -// -// LCD Character Set -// -// Note: This option is NOT applicable to Graphical Displays. -// -// All character-based LCD's provide ASCII plus one of these -// language extensions: -// -// - JAPANESE ... the most common -// - WESTERN ... with more accented characters -// - CYRILLIC ... for the Russian language -// -// To determine the language extension installed on your controller: -// -// - Compile and upload with LCD_LANGUAGE set to 'test' -// - Click the controller to view the LCD menu -// - The LCD will display Japanese, Western, or Cyrillic text -// -// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language -// -// :['JAPANESE', 'WESTERN', 'CYRILLIC'] -// +/** + * LCD Character Set + * + * Note: This option is NOT applicable to Graphical Displays. + * + * All character-based LCDs provide ASCII plus one of these + * language extensions: + * + * - JAPANESE ... the most common + * - WESTERN ... with more accented characters + * - CYRILLIC ... for the Russian language + * + * To determine the language extension installed on your controller: + * + * - Compile and upload with LCD_LANGUAGE set to 'test' + * - Click the controller to view the LCD menu + * - The LCD will display Japanese, Western, or Cyrillic text + * + * See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * + * :['JAPANESE', 'WESTERN', 'CYRILLIC'] + */ #define DISPLAY_CHARSET_HD44780 JAPANESE -// -// LCD TYPE -// -// You may choose ULTRA_LCD if you have character based LCD with 16x2, 16x4, 20x2, -// 20x4 char/lines or DOGLCD for the full graphics display with 128x64 pixels -// (ST7565R family). (This option will be set automatically for certain displays.) -// -// IMPORTANT NOTE: The U8glib library is required for Full Graphic Display! -// https://github.com/olikraus/U8glib_Arduino -// +/** + * LCD TYPE + * + * Enable ULTRA_LCD for a 16x2, 16x4, 20x2, or 20x4 character-based LCD. + * Enable DOGLCD for a 128x64 (ST7565R) Full Graphical Display. + * (These options will be enabled automatically for most displays.) + * + * IMPORTANT: The U8glib library is required for Full Graphic Display! + * https://github.com/olikraus/U8glib_Arduino + */ //#define ULTRA_LCD // Character based //#define DOGLCD // Full graphics display -// -// SD CARD -// -// SD Card support is disabled by default. If your controller has an SD slot, -// you must uncomment the following option or it won't work. -// +/** + * SD CARD + * + * SD Card support is disabled by default. If your controller has an SD slot, + * you must uncomment the following option or it won't work. + * + */ //#define SDSUPPORT -// -// SD CARD: SPI SPEED -// -// Uncomment ONE of the following items to use a slower SPI transfer -// speed. This is usually required if you're getting volume init errors. -// +/** + * SD CARD: SPI SPEED + * + * Enable one of the following items for a slower SPI transfer speed. + * This may be required to resolve "volume init" errors. + */ //#define SPI_SPEED SPI_HALF_SPEED //#define SPI_SPEED SPI_QUARTER_SPEED //#define SPI_SPEED SPI_EIGHTH_SPEED -// -// SD CARD: ENABLE CRC -// -// Use CRC checks and retries on the SD communication. -// +/** + * SD CARD: ENABLE CRC + * + * Use CRC checks and retries on the SD communication. + */ //#define SD_CHECK_AND_RETRY // @@ -1202,7 +1199,7 @@ */ // -// This option reverses the encoder direction everywhere +// This option reverses the encoder direction everywhere. // // Set this option if CLOCKWISE causes values to DECREASE // diff --git a/Marlin/example_configurations/wt150/Configuration.h b/Marlin/example_configurations/wt150/Configuration.h index dde673fc9..5deaccf7d 100644 --- a/Marlin/example_configurations/wt150/Configuration.h +++ b/Marlin/example_configurations/wt150/Configuration.h @@ -991,23 +991,17 @@ #define PREHEAT_2_TEMP_BED 110 #define PREHEAT_2_FAN_SPEED 0 // Value from 0 to 255 -// -// Nozzle Park -- EXPERIMENTAL -// -// When enabled allows the user to define a special XYZ position, inside the -// machine's topology, to park the nozzle when idle or when receiving the G27 -// command. -// -// The "P" paramenter controls what is the action applied to the Z axis: -// P0: (Default) If current Z-pos is lower than Z-park then the nozzle will -// be raised to reach Z-park height. -// -// P1: No matter the current Z-pos, the nozzle will be raised/lowered to -// reach Z-park height. -// -// P2: The nozzle height will be raised by Z-park amount but never going over -// the machine's limit of Z_MAX_POS. -// +/** + * Nozzle Park -- EXPERIMENTAL + * + * Park the nozzle at the given XYZ position on idle or G27. + * + * The "P" parameter controls the action applied to the Z axis: + * + * P0 (Default) If Z is below park Z raise the nozzle. + * P1 Raise the nozzle always to Z-park height. + * P2 Raise the nozzle by Z-park amount, limited to Z_MAX_POS. + */ //#define NOZZLE_PARK_FEATURE #if ENABLED(NOZZLE_PARK_FEATURE) @@ -1015,44 +1009,44 @@ #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 } #endif -// -// Clean Nozzle Feature -- EXPERIMENTAL -// -// When enabled allows the user to send G12 to start the nozzle cleaning -// process, the G-Code accepts two parameters: -// "P" for pattern selection -// "S" for defining the number of strokes/repetitions -// -// Available list of patterns: -// P0: This is the default pattern, this process requires a sponge type -// material at a fixed bed location. S defines "strokes" i.e. -// back-and-forth movements between the starting and end points. -// -// P1: This starts a zig-zag pattern between (X0, Y0) and (X1, Y1), "T" -// defines the number of zig-zag triangles to be done. "S" defines the -// number of strokes aka one back-and-forth movement. Zig-zags will -// be performed in whichever dimension is smallest. As an example, -// sending "G12 P1 S1 T3" will execute: -// -// -- -// | (X0, Y1) | /\ /\ /\ | (X1, Y1) -// | | / \ / \ / \ | -// A | | / \ / \ / \ | -// | | / \ / \ / \ | -// | (X0, Y0) | / \/ \/ \ | (X1, Y0) -// -- +--------------------------------+ -// |________|_________|_________| -// T1 T2 T3 -// -// P2: This starts a circular pattern with circle with middle in -// NOZZLE_CLEAN_CIRCLE_MIDDLE radius of R and stroke count of S. -// Before starting the circle nozzle goes to NOZZLE_CLEAN_START_POINT. -// -// Caveats: End point Z should use the same value as Start point Z. -// -// Attention: This is an EXPERIMENTAL feature, in the future the G-code arguments -// may change to add new functionality like different wipe patterns. -// +/** + * Clean Nozzle Feature -- EXPERIMENTAL + * + * Adds the G12 command to perform a nozzle cleaning process. + * + * Parameters: + * P Pattern + * S Strokes / Repetitions + * T Triangles (P1 only) + * + * Patterns: + * P0 Straight line (default). This process requires a sponge type material + * at a fixed bed location. "S" specifies strokes (i.e. back-forth motions) + * between the start / end points. + * + * P1 Zig-zag pattern between (X0, Y0) and (X1, Y1), "T" specifies the + * number of zig-zag triangles to do. "S" defines the number of strokes. + * Zig-zags are done in whichever is the narrower dimension. + * For example, "G12 P1 S1 T3" will execute: + * + * -- + * | (X0, Y1) | /\ /\ /\ | (X1, Y1) + * | | / \ / \ / \ | + * A | | / \ / \ / \ | + * | | / \ / \ / \ | + * | (X0, Y0) | / \/ \/ \ | (X1, Y0) + * -- +--------------------------------+ + * |________|_________|_________| + * T1 T2 T3 + * + * P2 Circular pattern with middle at NOZZLE_CLEAN_CIRCLE_MIDDLE. + * "R" specifies the radius. "S" specifies the stroke count. + * Before starting, the nozzle moves to NOZZLE_CLEAN_START_POINT. + * + * Caveats: The ending Z should be the same as starting Z. + * Attention: EXPERIMENTAL. G-code arguments may change. + * + */ //#define NOZZLE_CLEAN_FEATURE #if ENABLED(NOZZLE_CLEAN_FEATURE) @@ -1077,33 +1071,35 @@ #define NOZZLE_CLEAN_GOBACK #endif -// -// Print job timer -// -// Enable this option to automatically start and stop the -// print job timer when M104/M109/M190 commands are received. -// M104 (extruder without wait) - high temp = none, low temp = stop timer -// M109 (extruder with wait) - high temp = start timer, low temp = stop timer -// M190 (bed with wait) - high temp = start timer, low temp = none -// -// In all cases the timer can be started and stopped using -// the following commands: -// -// - M75 - Start the print job timer -// - M76 - Pause the print job timer -// - M77 - Stop the print job timer +/** + * Print Job Timer + * + * Automatically start and stop the print job timer on M104/M109/M190. + * + * 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 + * + * The timer can also be controlled with the following commands: + * + * M75 - Start the print job timer + * M76 - Pause the print job timer + * M77 - Stop the print job timer + */ #define PRINTJOB_TIMER_AUTOSTART -// -// Print Counter -// -// When enabled Marlin will keep track of some print statistical data such as: -// - Total print jobs -// - Total successful print jobs -// - Total failed print jobs -// - Total time printing -// -// This information can be viewed by the M78 command. +/** + * Print Counter + * + * Track statistical data such as: + * + * - Total print jobs + * - Total successful print jobs + * - Total failed print jobs + * - Total time printing + * + * View the current statistics with M78. + */ #define PRINTCOUNTER //============================================================================= @@ -1112,78 +1108,79 @@ // @section lcd -// -// LCD LANGUAGE -// -// Here you may choose the language used by Marlin on the LCD menus, the following -// list of languages are available: -// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, -// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test -// -// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } -// +/** + * LCD LANGUAGE + * + * Select the language to display on the LCD. These languages are available: + * + * en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it, + * kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test + * + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } + */ #define LCD_LANGUAGE en -// -// LCD Character Set -// -// Note: This option is NOT applicable to Graphical Displays. -// -// All character-based LCD's provide ASCII plus one of these -// language extensions: -// -// - JAPANESE ... the most common -// - WESTERN ... with more accented characters -// - CYRILLIC ... for the Russian language -// -// To determine the language extension installed on your controller: -// -// - Compile and upload with LCD_LANGUAGE set to 'test' -// - Click the controller to view the LCD menu -// - The LCD will display Japanese, Western, or Cyrillic text -// -// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language -// -// :['JAPANESE', 'WESTERN', 'CYRILLIC'] -// +/** + * LCD Character Set + * + * Note: This option is NOT applicable to Graphical Displays. + * + * All character-based LCDs provide ASCII plus one of these + * language extensions: + * + * - JAPANESE ... the most common + * - WESTERN ... with more accented characters + * - CYRILLIC ... for the Russian language + * + * To determine the language extension installed on your controller: + * + * - Compile and upload with LCD_LANGUAGE set to 'test' + * - Click the controller to view the LCD menu + * - The LCD will display Japanese, Western, or Cyrillic text + * + * See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * + * :['JAPANESE', 'WESTERN', 'CYRILLIC'] + */ #define DISPLAY_CHARSET_HD44780 JAPANESE -// -// LCD TYPE -// -// You may choose ULTRA_LCD if you have character based LCD with 16x2, 16x4, 20x2, -// 20x4 char/lines or DOGLCD for the full graphics display with 128x64 pixels -// (ST7565R family). (This option will be set automatically for certain displays.) -// -// IMPORTANT NOTE: The U8glib library is required for Full Graphic Display! -// https://github.com/olikraus/U8glib_Arduino -// +/** + * LCD TYPE + * + * Enable ULTRA_LCD for a 16x2, 16x4, 20x2, or 20x4 character-based LCD. + * Enable DOGLCD for a 128x64 (ST7565R) Full Graphical Display. + * (These options will be enabled automatically for most displays.) + * + * IMPORTANT: The U8glib library is required for Full Graphic Display! + * https://github.com/olikraus/U8glib_Arduino + */ //#define ULTRA_LCD // Character based //#define DOGLCD // Full graphics display -// -// SD CARD -// -// SD Card support is disabled by default. If your controller has an SD slot, -// you must uncomment the following option or it won't work. -// +/** + * SD CARD + * + * SD Card support is disabled by default. If your controller has an SD slot, + * you must uncomment the following option or it won't work. + * + */ #define SDSUPPORT -// -// SD CARD: SPI SPEED -// -// Uncomment ONE of the following items to use a slower SPI transfer -// speed. This is usually required if you're getting volume init errors. -// +/** + * SD CARD: SPI SPEED + * + * Enable one of the following items for a slower SPI transfer speed. + * This may be required to resolve "volume init" errors. + */ //#define SPI_SPEED SPI_HALF_SPEED //#define SPI_SPEED SPI_QUARTER_SPEED //#define SPI_SPEED SPI_EIGHTH_SPEED -// -// SD CARD: ENABLE CRC -// -// Use CRC checks and retries on the SD communication. -// +/** + * SD CARD: ENABLE CRC + * + * Use CRC checks and retries on the SD communication. + */ //#define SD_CHECK_AND_RETRY // @@ -1211,7 +1208,7 @@ */ // -// This option reverses the encoder direction everywhere +// This option reverses the encoder direction everywhere. // // Set this option if CLOCKWISE causes values to DECREASE // From bef9791ea3da2ef43309b6adbb2575c2b883b2b1 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 5 May 2017 14:14:13 -0500 Subject: [PATCH 009/189] Fix mfrb and mfpub --- buildroot/share/git/mfpub | 2 +- buildroot/share/git/mfrb | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/buildroot/share/git/mfpub b/buildroot/share/git/mfpub index 48ddb21dc..aa76498c0 100755 --- a/buildroot/share/git/mfpub +++ b/buildroot/share/git/mfpub @@ -48,7 +48,7 @@ git clean -d -f # Push 'master' to the fork and make a proper PR... if [[ $BRANCH == "master" ]]; then - if [[ $$FORK == "MarlinFirmware" ]]; then + if [[ $FORK == "MarlinFirmware" ]]; then # Allow working directly with the main fork git push -f upstream diff --git a/buildroot/share/git/mfrb b/buildroot/share/git/mfrb index 1e7c26e53..954556d0e 100755 --- a/buildroot/share/git/mfrb +++ b/buildroot/share/git/mfrb @@ -14,7 +14,7 @@ case "$#" in esac # If the branch isn't currently the PR target -if [[ ${INFO[4]} != ${INFO[5]} ]]; then +if [[ ${INFO[3]} != ${INFO[4]} ]]; then git fetch upstream git rebase upstream/${INFO[3]} && git rebase -i upstream/${INFO[3]} fi From 0446dd3ad8d95eae7e2042dae8ee43f29150869e Mon Sep 17 00:00:00 2001 From: Brian Date: Sat, 6 May 2017 06:17:07 -0400 Subject: [PATCH 010/189] PlatformIO-related changes - move platformio.ini out of source directory to be more consistent with 'normal' PlatformIO usage - facilitates IDE integration - add related .gitignores --- .gitignore | 4 ++++ Marlin/platformio.ini => platformio.ini | 8 ++++---- 2 files changed, 8 insertions(+), 4 deletions(-) rename Marlin/platformio.ini => platformio.ini (93%) diff --git a/.gitignore b/.gitignore index e9301b9bb..bc9226570 100755 --- a/.gitignore +++ b/.gitignore @@ -132,3 +132,7 @@ Marlin/.vs/ #cmake CMakeLists.txt Marlin/CMakeLists.txt +CMakeListsPrivate.txt + +#CLion +cmake-build-* diff --git a/Marlin/platformio.ini b/platformio.ini similarity index 93% rename from Marlin/platformio.ini rename to platformio.ini index 2b8285313..2cc47133b 100644 --- a/Marlin/platformio.ini +++ b/platformio.ini @@ -12,10 +12,10 @@ # targets = upload [platformio] -src_dir = ./ -envs_dir = ../.pioenvs -lib_dir = ../.piolib -libdeps_dir = ../.piolibdeps +src_dir = Marlin +envs_dir = .pioenvs +lib_dir = .piolib +libdeps_dir = .piolibdeps env_default = mega2560 [common] From a59066bca9282f97d8a924b5889b144620931113 Mon Sep 17 00:00:00 2001 From: bgort Date: Sat, 6 May 2017 19:59:16 -0400 Subject: [PATCH 011/189] Various improvements - mostly UBL-related (#6607) UBL Clean up. --- Marlin/Marlin_main.cpp | 6 ++--- Marlin/least_squares_fit.cpp | 3 ++- Marlin/ubl.cpp | 18 +++----------- Marlin/ubl_G29.cpp | 48 +++++++++++++++++++----------------- 4 files changed, 35 insertions(+), 40 deletions(-) mode change 100755 => 100644 Marlin/ubl.cpp diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 9a2ab20cd..e5dcc5fea 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -4360,7 +4360,7 @@ void home_all_axes() { gcode_G28(); } verbose_level = code_seen('V') && code_has_value() ? code_value_int() : 0; if (!WITHIN(verbose_level, 0, 4)) { - SERIAL_PROTOCOLLNPGM("?(V)erbose Level is implausible (0-4)."); + SERIAL_PROTOCOLLNPGM("?(V)erbose level is implausible (0-4)."); return; } @@ -5081,7 +5081,7 @@ void home_all_axes() { gcode_G28(); } const int8_t verbose_level = code_seen('V') ? code_value_byte() : 1; if (!WITHIN(verbose_level, 0, 2)) { - SERIAL_PROTOCOLLNPGM("?(V)erbose Level is implausible (0-2)."); + SERIAL_PROTOCOLLNPGM("?(V)erbose level is implausible (0-2)."); return; } @@ -6183,7 +6183,7 @@ inline void gcode_M42() { const int8_t verbose_level = code_seen('V') ? code_value_byte() : 1; if (!WITHIN(verbose_level, 0, 4)) { - SERIAL_PROTOCOLLNPGM("?Verbose Level not plausible (0-4)."); + SERIAL_PROTOCOLLNPGM("?(V)erbose level is implausible (0-4)."); return; } diff --git a/Marlin/least_squares_fit.cpp b/Marlin/least_squares_fit.cpp index 59a23ca4a..271aae11f 100644 --- a/Marlin/least_squares_fit.cpp +++ b/Marlin/least_squares_fit.cpp @@ -73,8 +73,9 @@ int finish_incremental_LSF(struct linear_fit_data *lsf) { lsf->yzbar = lsf->yzbar / N - lsf->ybar * lsf->zbar; lsf->xzbar = lsf->xzbar / N - lsf->xbar * lsf->zbar; const float DD = lsf->x2bar * lsf->y2bar - sq(lsf->xybar); + if (fabs(DD) <= 1e-10 * (lsf->max_absx + lsf->max_absy)) - return -1; + return 1; lsf->A = (lsf->yzbar * lsf->xybar - lsf->xzbar * lsf->y2bar) / DD; lsf->B = (lsf->xzbar * lsf->xybar - lsf->yzbar * lsf->x2bar) / DD; diff --git a/Marlin/ubl.cpp b/Marlin/ubl.cpp old mode 100755 new mode 100644 index aa1fc8873..5471b178e --- a/Marlin/ubl.cpp +++ b/Marlin/ubl.cpp @@ -50,13 +50,6 @@ safe_delay(10); } - static void serial_echo_mspaces(const uint8_t cnt) { - for (uint8_t i = GRID_MAX_POINTS_X - 1; --i;) { - SERIAL_ECHO_SP((uint8_t)cnt); - safe_delay(10); - } - } - ubl_state unified_bed_leveling::state; float unified_bed_leveling::z_values[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y], @@ -148,12 +141,11 @@ if (map0) { SERIAL_PROTOCOLLNPGM("\nBed Topography Report:\n"); serial_echo_xy(0, GRID_MAX_POINTS_Y - 1); - SERIAL_ECHO_SP(3); - serial_echo_mspaces(spaces); + SERIAL_ECHO_SP(spaces * (GRID_MAX_POINTS_X - 2) + 3); serial_echo_xy(GRID_MAX_POINTS_X - 1, GRID_MAX_POINTS_Y - 1); SERIAL_EOL; serial_echo_xy(UBL_MESH_MIN_X, UBL_MESH_MAX_Y); - serial_echo_mspaces(spaces); + SERIAL_ECHO_SP(spaces * (GRID_MAX_POINTS_X - 2)); serial_echo_xy(UBL_MESH_MAX_X, UBL_MESH_MAX_Y); SERIAL_EOL; } @@ -198,13 +190,11 @@ if (map0) { serial_echo_xy(UBL_MESH_MIN_X, UBL_MESH_MIN_Y); - SERIAL_ECHO_SP(4); - serial_echo_mspaces(spaces); + SERIAL_ECHO_SP(spaces * (GRID_MAX_POINTS_X - 2) + 4); serial_echo_xy(UBL_MESH_MAX_X, UBL_MESH_MIN_Y); SERIAL_EOL; serial_echo_xy(0, 0); - SERIAL_ECHO_SP(5); - serial_echo_mspaces(spaces); + SERIAL_ECHO_SP(spaces * (GRID_MAX_POINTS_X - 2) + 5); serial_echo_xy(GRID_MAX_POINTS_X - 1, 0); SERIAL_EOL; } diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index b26096a97..326f39d16 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -311,17 +311,16 @@ #define USE_PROBE_AS_REFERENCE 1 // The simple parameter flags and values are 'static' so parameter parsing can be in a support routine. - static int g29_verbose_level, phase_value = -1, repetition_cnt, + static int g29_verbose_level, phase_value, repetition_cnt, storage_slot = 0, map_type, grid_size; static bool repeat_flag, c_flag, x_flag, y_flag; static float x_pos, y_pos, measured_z, card_thickness = 0.0, ubl_constant = 0.0; - extern void lcd_setstatus(const char* message, const bool persist); - extern void lcd_setstatuspgm(const char* message, const uint8_t level); + extern void lcd_setstatus(const char* message, const bool persist); + extern void lcd_setstatuspgm(const char* message, const uint8_t level); void __attribute__((optimize("O0"))) gcode_G29() { - if (ubl.eeprom_start < 0) { SERIAL_PROTOCOLLNPGM("?You need to enable your EEPROM and initialize it"); SERIAL_PROTOCOLLNPGM("with M502, M500, M501 in that order.\n"); @@ -384,21 +383,17 @@ } if (code_seen('J')) { - if (!WITHIN(grid_size, 2, 9)) { - SERIAL_PROTOCOLLNPGM("ERROR - grid size must be between 2 and 9"); - return; - } ubl.save_ubl_active_state_and_disable(); ubl.tilt_mesh_based_on_probed_grid(code_seen('O') || code_seen('M')); ubl.restore_ubl_active_state_and_leave(); } if (code_seen('P')) { - phase_value = code_value_int(); - if (!WITHIN(phase_value, 0, 7)) { - SERIAL_PROTOCOLLNPGM("Invalid Phase value. (0-4)\n"); - return; + if (WITHIN(phase_value,0,1) && ubl.state.eeprom_storage_slot==-1) { + ubl.state.eeprom_storage_slot=0; + SERIAL_PROTOCOLLNPGM("Default storage slot 0 selected.\n"); } + switch (phase_value) { case 0: // @@ -420,7 +415,7 @@ SERIAL_PROTOCOLPAIR("Probing Mesh Points Closest to (", x_pos); SERIAL_PROTOCOLCHAR(','); SERIAL_PROTOCOL(y_pos); - SERIAL_PROTOCOLLNPGM(")\n"); + SERIAL_PROTOCOLLNPGM(").\n"); } ubl.probe_entire_mesh(x_pos + X_PROBE_OFFSET_FROM_EXTRUDER, y_pos + Y_PROBE_OFFSET_FROM_EXTRUDER, code_seen('O') || code_seen('M'), code_seen('E'), code_seen('U')); @@ -460,7 +455,7 @@ } } manually_probe_remaining_mesh(x_pos, y_pos, height, card_thickness, code_seen('O') || code_seen('M')); - SERIAL_PROTOCOLLNPGM("G29 P2 finished"); + SERIAL_PROTOCOLLNPGM("G29 P2 finished."); } break; @@ -757,8 +752,6 @@ } void unified_bed_leveling::tilt_mesh_based_on_3pts(const float &z1, const float &z2, const float &z3) { - int i, j; - matrix_3x3 rotation; vector_3 v1 = vector_3( (UBL_PROBE_PT_1_X - UBL_PROBE_PT_2_X), (UBL_PROBE_PT_1_Y - UBL_PROBE_PT_2_Y), @@ -892,14 +885,14 @@ //, min(planner.max_feedrate_mm_s[X_AXIS], planner.max_feedrate_mm_s[Y_AXIS]) / 2.0); stepper.synchronize(); - SERIAL_PROTOCOLPGM("Place shim under nozzle"); + SERIAL_PROTOCOLPGM("Place shim under nozzle."); say_and_take_a_measurement(); const float z1 = use_encoder_wheel_to_measure_point(); do_blocking_move_to_z(current_position[Z_AXIS] + SIZE_OF_LITTLE_RAISE); stepper.synchronize(); - SERIAL_PROTOCOLPGM("Remove shim"); + SERIAL_PROTOCOLPGM("Remove shim."); say_and_take_a_measurement(); const float z2 = use_encoder_wheel_to_measure_point(); @@ -1039,14 +1032,22 @@ g29_verbose_level = code_seen('V') ? code_value_int() : 0; if (!WITHIN(g29_verbose_level, 0, 4)) { - SERIAL_PROTOCOLLNPGM("?(V)erbose Level is implausible (0-4)\n"); + SERIAL_PROTOCOLLNPGM("?(V)erbose level is implausible (0-4).\n"); err_flag = true; } + if (code_seen('P')) { + phase_value = code_value_int(); + if (!WITHIN(phase_value, 0, 6)) { + SERIAL_PROTOCOLLNPGM("?(P)hase value invalid (0-6).\n"); + err_flag = true; + } + } + if (code_seen('J')) { grid_size = code_has_value() ? code_value_int() : 3; - if (!WITHIN(grid_size, 2, 5)) { - SERIAL_PROTOCOLLNPGM("Invalid grid probe points specified.\n"); + if (!WITHIN(grid_size, 2, 9)) { + SERIAL_PROTOCOLLNPGM("?Invalid grid size (J) specified (2-9).\n"); err_flag = true; } } @@ -1607,7 +1608,10 @@ zig_zag ^= true; } - const int status = finish_incremental_LSF(&lsf_results); + if (finish_incremental_LSF(&lsf_results)) { + SERIAL_ECHOPGM("Could not complete LSF!"); + return; + } if (g29_verbose_level > 3) { SERIAL_ECHOPGM("LSF Results A="); From ce507deb9f5d4438ae2eeb6acc30740ce5cd4030 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 6 May 2017 19:41:50 -0500 Subject: [PATCH 012/189] Support temperature units in M503 --- Marlin/Marlin_main.cpp | 15 ++++++++------- Marlin/configuration_store.cpp | 30 +++++++++++++++++++++++++++--- 2 files changed, 35 insertions(+), 10 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index e5dcc5fea..43639d99a 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -1294,25 +1294,26 @@ inline bool code_value_bool() { return !code_has_value() || code_value_byte() > #if ENABLED(TEMPERATURE_UNITS_SUPPORT) inline void set_input_temp_units(TempUnit units) { input_temp_units = units; } - int16_t code_value_temp_abs() { + float temp_abs(const float &c) { switch (input_temp_units) { case TEMPUNIT_F: - return (code_value_float() - 32) * 0.5555555556; + return (c - 32.0) * 0.5555555556; case TEMPUNIT_K: - return code_value_float() - 273.15; + return c - 273.15; case TEMPUNIT_C: default: - return code_value_int(); + return c; } } + int16_t code_value_temp_abs() { return temp_abs(code_value_float()); } + int16_t code_value_temp_diff() { switch (input_temp_units) { - case TEMPUNIT_C: - case TEMPUNIT_K: - return code_value_float(); case TEMPUNIT_F: return code_value_float() * 0.5555555556; + case TEMPUNIT_C: + case TEMPUNIT_K: default: return code_value_float(); } diff --git a/Marlin/configuration_store.cpp b/Marlin/configuration_store.cpp index 039c69acb..0a8796970 100644 --- a/Marlin/configuration_store.cpp +++ b/Marlin/configuration_store.cpp @@ -1239,7 +1239,10 @@ void MarlinSettings::reset() { extern float linear_unit_factor, volumetric_unit_factor; #define LINEAR_UNIT(N) ((N) / linear_unit_factor) #define VOLUMETRIC_UNIT(N) ((N) / (volumetric_enabled ? volumetric_unit_factor : linear_unit_factor)) - serialprintPGM(linear_unit_factor == 1.0 ? PSTR(" G21 ; Units in mm\n") : PSTR(" G20 ; Units in inches\n")); + SERIAL_ECHOPGM(" G2"); + SERIAL_CHAR(linear_unit_factor == 1.0 ? '1' : '0'); + SERIAL_ECHOPGM(" ; Units in "); + serialprintPGM(linear_unit_factor == 1.0 ? PSTR("mm\n") : PSTR("inches\n")); #else #define LINEAR_UNIT(N) N #define VOLUMETRIC_UNIT(N) N @@ -1247,6 +1250,27 @@ void MarlinSettings::reset() { #endif SERIAL_EOL; + #if ENABLED(ULTIPANEL) + + // Temperature units - for Ultipanel temperature options + + CONFIG_ECHO_START; + #if ENABLED(TEMPERATURE_UNITS_SUPPORT) + extern TempUnit input_temp_units; + extern float temp_abs(float &f); + #define TEMP_UNIT(N) temp_abs(N) + SERIAL_ECHOPGM(" M149 "); + SERIAL_CHAR(input_temp_units == TEMPUNIT_K ? 'K' : input_temp_units == TEMPUNIT_F ? 'F' : 'C'); + SERIAL_ECHOPGM(" ; Units in "); + serialprintPGM(input_temp_units == TEMPUNIT_K ? PSTR("Kelvin\n") : input_temp_units == TEMPUNIT_F ? PSTR("Fahrenheit\n") : PSTR("Celsius\n")); + #else + #define TEMP_UNIT(N) N + SERIAL_ECHOLNPGM(" M149 C ; Units in Celsius\n"); + #endif + SERIAL_EOL; + + #endif + /** * Volumetric extrusion M200 */ @@ -1519,8 +1543,8 @@ void MarlinSettings::reset() { CONFIG_ECHO_START; for (uint8_t i = 0; i < COUNT(lcd_preheat_hotend_temp); i++) { SERIAL_ECHOPAIR(" M145 S", (int)i); - SERIAL_ECHOPAIR(" H", lcd_preheat_hotend_temp[i]); - SERIAL_ECHOPAIR(" B", lcd_preheat_bed_temp[i]); + SERIAL_ECHOPAIR(" H", TEMP_UNIT(lcd_preheat_hotend_temp[i])); + SERIAL_ECHOPAIR(" B", TEMP_UNIT(lcd_preheat_bed_temp[i])); SERIAL_ECHOLNPAIR(" F", lcd_preheat_fan_speed[i]); } #endif // ULTIPANEL From d66e9efac5b18eabb59e98970e677c9aee3f49bc Mon Sep 17 00:00:00 2001 From: lrpirlet Date: Sun, 7 May 2017 15:07:26 +0200 Subject: [PATCH 013/189] G29 P1 stops reporting Invalid location with this patch --- Marlin/ubl_G29.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 326f39d16..414315b2c 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -1057,12 +1057,12 @@ err_flag = true; } - if (!WITHIN(RAW_X_POSITION(x_pos), UBL_MESH_MIN_X, UBL_MESH_MAX_X)) { + if (!WITHIN(RAW_X_POSITION(x_pos), X_MIN_POS, X_MAX_POS)) { SERIAL_PROTOCOLLNPGM("Invalid X location specified.\n"); err_flag = true; } - if (!WITHIN(RAW_Y_POSITION(y_pos), UBL_MESH_MIN_Y, UBL_MESH_MAX_Y)) { + if (!WITHIN(RAW_Y_POSITION(y_pos), Y_MIN_POS, Y_MAX_POS)) { SERIAL_PROTOCOLLNPGM("Invalid Y location specified.\n"); err_flag = true; } From faa270071dfa34b906b5ebb74864f2a20ab10ead Mon Sep 17 00:00:00 2001 From: Brian Date: Sun, 7 May 2017 07:06:06 -0400 Subject: [PATCH 014/189] Improve BLTOUCH_HEATERS_OFF functionality - rename to PROBING_HEATERS_OFF - move heater pausing functionality into thermalManager - add variables, pause(), ispaused(), other functions - add fan pausing functionality -> PROBING_FANS_OFF - add probing_pause() wrapper - move pausing into do_homing_move() and do_probe_move() to minimize quiet time and so other probe types can benefit - example configs --- Marlin/Conditionals_post.h | 9 ++ Marlin/Configuration.h | 13 +- Marlin/Marlin.h | 4 + Marlin/Marlin_main.cpp | 130 +++++++++++------- .../Cartesio/Configuration.h | 13 +- .../Felix/Configuration.h | 13 +- .../Felix/DUAL/Configuration.h | 13 +- .../FolgerTech-i3-2020/Configuration.h | 13 +- .../Hephestos/Configuration.h | 13 +- .../Hephestos_2/Configuration.h | 13 +- .../K8200/Configuration.h | 13 +- .../K8400/Configuration.h | 13 +- .../K8400/Dual-head/Configuration.h | 13 +- .../RepRapWorld/Megatronics/Configuration.h | 13 +- .../RigidBot/Configuration.h | 13 +- .../SCARA/Configuration.h | 13 +- .../TAZ4/Configuration.h | 13 +- .../TinyBoy2/Configuration.h | 13 +- .../WITBOX/Configuration.h | 13 +- .../adafruit/ST7565/Configuration.h | 13 +- .../FLSUN/auto_calibrate/Configuration.h | 13 +- .../delta/FLSUN/kossel_mini/Configuration.h | 13 +- .../delta/generic/Configuration.h | 13 +- .../delta/kossel_mini/Configuration.h | 13 +- .../delta/kossel_pro/Configuration.h | 13 +- .../delta/kossel_xl/Configuration.h | 13 +- .../gCreate_gMax1.5+/Configuration.h | 17 ++- .../makibox/Configuration.h | 13 +- .../tvrrug/Round2/Configuration.h | 13 +- .../wt150/Configuration.h | 13 +- Marlin/temperature.cpp | 64 +++++++++ Marlin/temperature.h | 14 ++ 32 files changed, 468 insertions(+), 108 deletions(-) diff --git a/Marlin/Conditionals_post.h b/Marlin/Conditionals_post.h index ce2a002b2..0a5e1820c 100644 --- a/Marlin/Conditionals_post.h +++ b/Marlin/Conditionals_post.h @@ -645,6 +645,15 @@ #endif #define WRITE_FAN_N(n, v) WRITE_FAN##n(v) + + /** + * Heater & Fan Pausing + */ + #if ENABLED(PROBING_FANS_OFF) && FAN_COUNT == 0 + #undef PROBING_FANS_OFF + #endif + #define QUIET_PROBING (ENABLED(PROBING_HEATERS_OFF) || ENABLED(PROBING_FANS_OFF)) + /** * Servos and probes */ diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 4c1a39b8f..b2f0cc639 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -584,14 +584,23 @@ //#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles /** - * The BLTouch probe is a Hall effect sensor that emulates a servo. + * The BLTouch probe uses a Hall effect sensor and emulates a servo. */ //#define BLTOUCH #if ENABLED(BLTOUCH) //#define BLTOUCH_DELAY 375 // (ms) Enable and increase if needed - //#define BLTOUCH_HEATERS_OFF // Enable if the probe seems unreliable. Heaters will be disabled for each probe. #endif +/** + * Enable if probing seems unreliable. Heaters and/or fans - consistent with the + * options selected below - will be disabled during probing so as to minimize + * potential EM interference by quieting/silencing the source of the 'noise' (the change + * in current flowing through the wires). This is likely most useful to users of the + * BLTouch probe, but may also help those with inductive or other probe types. + */ +//#define PROBING_HEATERS_OFF // Turn heaters off when probing +//#define PROBING_FANS_OFF // Turn fans off when probing + // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/Marlin.h b/Marlin/Marlin.h index e7bf2df73..a5c2b81c2 100644 --- a/Marlin/Marlin.h +++ b/Marlin/Marlin.h @@ -362,6 +362,10 @@ int16_t code_value_temp_diff(); #if FAN_COUNT > 0 extern int16_t fanSpeeds[FAN_COUNT]; + #if ENABLED(PROBING_FANS_OFF) + extern bool fans_paused; + extern int16_t paused_fanSpeeds[FAN_COUNT]; + #endif #endif #if ENABLED(BARICUDA) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 43639d99a..6baecec08 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -441,6 +441,10 @@ float soft_endstop_min[XYZ] = { X_MIN_POS, Y_MIN_POS, Z_MIN_POS }, #if FAN_COUNT > 0 int16_t fanSpeeds[FAN_COUNT] = { 0 }; + #if ENABLED(PROBING_FANS_OFF) + bool fans_paused = false; + int16_t paused_fanSpeeds[FAN_COUNT] = { 0 }; + #endif #endif // The active extruder (tool). Set with T command. @@ -2041,6 +2045,35 @@ static void clean_up_after_endstop_or_probe_move() { #endif +#if ENABLED(PROBING_FANS_OFF) + void fans_pause(bool p) { + if (p && fans_paused) { // If called out of order something is wrong + SERIAL_ERROR_START; + SERIAL_ERRORLNPGM("Fans already paused!"); + return; + } + + if (!p && !fans_paused) { + SERIAL_ERROR_START; + SERIAL_ERRORLNPGM("Fans already unpaused!"); + return; + } + + if (p) { + for (uint8_t x = 0;x < FAN_COUNT;x++) { + paused_fanSpeeds[x] = fanSpeeds[x]; + fanSpeeds[x] = 0; + } + } + else { + for (uint8_t x = 0;x < FAN_COUNT;x++) + fanSpeeds[x] = paused_fanSpeeds[x]; + } + + fans_paused = p; + } +#endif + #if HAS_BED_PROBE // TRIGGERED_WHEN_STOWED_TEST can easily be extended to servo probes, ... if needed. @@ -2052,6 +2085,20 @@ static void clean_up_after_endstop_or_probe_move() { #endif #endif + #if QUIET_PROBING + void probing_pause(bool pause) { + #if ENABLED(PROBING_HEATERS_OFF) + thermalManager.pause(pause); + #endif + + #if ENABLED(PROBING_FANS_OFF) + fans_pause(pause); + #endif + + if(pause) safe_delay(25); + } + #endif + #if ENABLED(BLTOUCH) void bltouch_command(int angle) { @@ -2059,51 +2106,6 @@ static void clean_up_after_endstop_or_probe_move() { safe_delay(BLTOUCH_DELAY); } - /** - * BLTouch probes have a Hall effect sensor. The high currents switching - * on and off cause a magnetic field that can affect the repeatability of the - * sensor. So for BLTouch probes, heaters are turned off during the probe, - * then quickly turned back on after the point is sampled. - */ - #if ENABLED(BLTOUCH_HEATERS_OFF) - - void set_heaters_for_bltouch(const bool deploy) { - static bool heaters_were_disabled = false; - static millis_t next_emi_protection = 0; - static int16_t temps_at_entry[HOTENDS]; - - #if HAS_TEMP_BED - static int16_t bed_temp_at_entry; - #endif - - // If called out of order or far apart something is seriously wrong - if (deploy == heaters_were_disabled - || (next_emi_protection && ELAPSED(millis(), next_emi_protection))) - kill(PSTR(MSG_KILLED)); - - if (deploy) { - next_emi_protection = millis() + 20 * 1000UL; - HOTEND_LOOP() { - temps_at_entry[e] = thermalManager.degTargetHotend(e); - thermalManager.setTargetHotend(0, e); - } - #if HAS_TEMP_BED - bed_temp_at_entry = thermalManager.degTargetBed(); - thermalManager.setTargetBed(0); - #endif - } - else { - next_emi_protection = 0; - HOTEND_LOOP() thermalManager.setTargetHotend(temps_at_entry[e], e); - #if HAS_TEMP_BED - thermalManager.setTargetBed(bed_temp_at_entry); - #endif - } - heaters_were_disabled = deploy; - } - - #endif // BLTOUCH_HEATERS_OFF - void set_bltouch_deployed(const bool deploy) { if (deploy && TEST_BLTOUCH()) { // If BL-Touch says it's triggered bltouch_command(BLTOUCH_RESET); // try to reset it. @@ -2118,9 +2120,6 @@ static void clean_up_after_endstop_or_probe_move() { stop(); // punt! } } - #if ENABLED(BLTOUCH_HEATERS_OFF) - set_heaters_for_bltouch(deploy); - #endif bltouch_command(deploy ? BLTOUCH_DEPLOY : BLTOUCH_STOW); @@ -2249,9 +2248,17 @@ static void clean_up_after_endstop_or_probe_move() { set_bltouch_deployed(true); #endif + #if QUIET_PROBING + probing_pause(true); + #endif + // Move down until probe triggered do_blocking_move_to_z(LOGICAL_Z_POSITION(z), MMM_TO_MMS(fr_mm_m)); + #if QUIET_PROBING + probing_pause(false); + #endif + // Retract BLTouch immediately after a probe #if ENABLED(BLTOUCH) set_bltouch_deployed(false); @@ -2809,6 +2816,10 @@ static void do_homing_move(const AxisEnum axis, float distance, float fr_mm_s=0. if (deploy_bltouch) set_bltouch_deployed(true); #endif + #if QUIET_PROBING + if (axis == Z_AXIS) probing_pause(true); + #endif + // Tell the planner we're at Z=0 current_position[axis] = 0; @@ -2825,6 +2836,10 @@ static void do_homing_move(const AxisEnum axis, float distance, float fr_mm_s=0. stepper.synchronize(); + #if QUIET_PROBING + if (axis == Z_AXIS) probing_pause(false); + #endif + #if HOMING_Z_WITH_PROBE && ENABLED(BLTOUCH) if (deploy_bltouch) set_bltouch_deployed(false); #endif @@ -6468,6 +6483,7 @@ inline void gcode_M104() { if (code_seen('S')) { const int16_t temp = code_value_temp_abs(); thermalManager.setTargetHotend(temp, target_extruder); + #if ENABLED(DUAL_X_CARRIAGE) if (dual_x_carriage_mode == DXC_DUPLICATION_MODE && target_extruder == 0) thermalManager.setTargetHotend(temp ? temp + duplicate_extruder_temp_offset : 0, 1); @@ -6663,6 +6679,7 @@ inline void gcode_M109() { if (no_wait_for_cooling || code_seen('R')) { const int16_t temp = code_value_temp_abs(); thermalManager.setTargetHotend(temp, target_extruder); + #if ENABLED(DUAL_X_CARRIAGE) if (dual_x_carriage_mode == DXC_DUPLICATION_MODE && target_extruder == 0) thermalManager.setTargetHotend(temp ? temp + duplicate_extruder_temp_offset : 0, 1); @@ -6814,6 +6831,7 @@ inline void gcode_M109() { const bool no_wait_for_cooling = code_seen('S'); if (no_wait_for_cooling || code_seen('R')) { thermalManager.setTargetBed(code_value_temp_abs()); + #if ENABLED(PRINTJOB_TIMER_AUTOSTART) if (code_value_temp_abs() > BED_MINTEMP) print_job_timer.start(); @@ -7107,10 +7125,11 @@ inline void gcode_M81() { thermalManager.disable_all_heaters(); stepper.finish_and_disable(); #if FAN_COUNT > 0 - #if FAN_COUNT > 1 - for (uint8_t i = 0; i < FAN_COUNT; i++) fanSpeeds[i] = 0; - #else - fanSpeeds[0] = 0; + for (uint8_t i = 0; i < FAN_COUNT; i++) fanSpeeds[i] = 0; + + #if ENABLED(PROBING_FANS_OFF) + fans_paused = false; + ZERO(paused_fanSpeeds); #endif #endif safe_delay(1000); // Wait 1 second before switching off @@ -12087,7 +12106,12 @@ void kill(const char* lcd_msg) { * After a stop the machine may be resumed with M999 */ void stop() { - thermalManager.disable_all_heaters(); + thermalManager.disable_all_heaters(); // 'unpause' taken care of in here + + #if ENABLED(PROBING_FANS_OFF) + if (fans_paused) fans_pause(false); // put things back the way they were + #endif + if (IsRunning()) { Stopped_gcode_LastN = gcode_LastN; // Save last g_code for restart SERIAL_ERROR_START; diff --git a/Marlin/example_configurations/Cartesio/Configuration.h b/Marlin/example_configurations/Cartesio/Configuration.h index f38780bd2..b029b4b53 100644 --- a/Marlin/example_configurations/Cartesio/Configuration.h +++ b/Marlin/example_configurations/Cartesio/Configuration.h @@ -582,14 +582,23 @@ //#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles /** - * The BLTouch probe is a Hall effect sensor that emulates a servo. + * The BLTouch probe uses a Hall effect sensor and emulates a servo. */ //#define BLTOUCH #if ENABLED(BLTOUCH) //#define BLTOUCH_DELAY 375 // (ms) Enable and increase if needed - //#define BLTOUCH_HEATERS_OFF // Enable if the probe seems unreliable. Heaters will be disabled for each probe. #endif +/** + * Enable if probing seems unreliable. Heaters and/or fans - consistent with the + * options selected below - will be disabled during probing so as to minimize + * potential EM interference by quieting/silencing the source of the 'noise' (the change + * in current flowing through the wires). This is likely most useful to users of the + * BLTouch probe, but may also help those with inductive or other probe types. + */ +//#define PROBING_HEATERS_OFF // Turn heaters off when probing +//#define PROBING_FANS_OFF // Turn fans off when probing + // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/Felix/Configuration.h b/Marlin/example_configurations/Felix/Configuration.h index ec12db1ab..eaf92c943 100644 --- a/Marlin/example_configurations/Felix/Configuration.h +++ b/Marlin/example_configurations/Felix/Configuration.h @@ -566,14 +566,23 @@ //#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles /** - * The BLTouch probe is a Hall effect sensor that emulates a servo. + * The BLTouch probe uses a Hall effect sensor and emulates a servo. */ //#define BLTOUCH #if ENABLED(BLTOUCH) //#define BLTOUCH_DELAY 375 // (ms) Enable and increase if needed - //#define BLTOUCH_HEATERS_OFF // Enable if the probe seems unreliable. Heaters will be disabled for each probe. #endif +/** + * Enable if probing seems unreliable. Heaters and/or fans - consistent with the + * options selected below - will be disabled during probing so as to minimize + * potential EM interference by quieting/silencing the source of the 'noise' (the change + * in current flowing through the wires). This is likely most useful to users of the + * BLTouch probe, but may also help those with inductive or other probe types. + */ +//#define PROBING_HEATERS_OFF // Turn heaters off when probing +//#define PROBING_FANS_OFF // Turn fans off when probing + // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/Felix/DUAL/Configuration.h b/Marlin/example_configurations/Felix/DUAL/Configuration.h index 88c750fb3..506faaf03 100644 --- a/Marlin/example_configurations/Felix/DUAL/Configuration.h +++ b/Marlin/example_configurations/Felix/DUAL/Configuration.h @@ -566,14 +566,23 @@ //#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles /** - * The BLTouch probe is a Hall effect sensor that emulates a servo. + * The BLTouch probe uses a Hall effect sensor and emulates a servo. */ //#define BLTOUCH #if ENABLED(BLTOUCH) //#define BLTOUCH_DELAY 375 // (ms) Enable and increase if needed - //#define BLTOUCH_HEATERS_OFF // Enable if the probe seems unreliable. Heaters will be disabled for each probe. #endif +/** + * Enable if probing seems unreliable. Heaters and/or fans - consistent with the + * options selected below - will be disabled during probing so as to minimize + * potential EM interference by quieting/silencing the source of the 'noise' (the change + * in current flowing through the wires). This is likely most useful to users of the + * BLTouch probe, but may also help those with inductive or other probe types. + */ +//#define PROBING_HEATERS_OFF // Turn heaters off when probing +//#define PROBING_FANS_OFF // Turn fans off when probing + // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h index 0e131869f..7c3944637 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h @@ -590,14 +590,23 @@ #define Z_SERVO_ANGLES {40,85} // Z Servo Deploy and Stow angles /** - * The BLTouch probe is a Hall effect sensor that emulates a servo. + * The BLTouch probe uses a Hall effect sensor and emulates a servo. */ //#define BLTOUCH #if ENABLED(BLTOUCH) //#define BLTOUCH_DELAY 375 // (ms) Enable and increase if needed - //#define BLTOUCH_HEATERS_OFF // Enable if the probe seems unreliable. Heaters will be disabled for each probe. #endif +/** + * Enable if probing seems unreliable. Heaters and/or fans - consistent with the + * options selected below - will be disabled during probing so as to minimize + * potential EM interference by quieting/silencing the source of the 'noise' (the change + * in current flowing through the wires). This is likely most useful to users of the + * BLTouch probe, but may also help those with inductive or other probe types. + */ +//#define PROBING_HEATERS_OFF // Turn heaters off when probing +//#define PROBING_FANS_OFF // Turn fans off when probing + // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/Hephestos/Configuration.h b/Marlin/example_configurations/Hephestos/Configuration.h index 02dfe9c4f..43be117b7 100644 --- a/Marlin/example_configurations/Hephestos/Configuration.h +++ b/Marlin/example_configurations/Hephestos/Configuration.h @@ -574,14 +574,23 @@ //#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles /** - * The BLTouch probe is a Hall effect sensor that emulates a servo. + * The BLTouch probe uses a Hall effect sensor and emulates a servo. */ //#define BLTOUCH #if ENABLED(BLTOUCH) //#define BLTOUCH_DELAY 375 // (ms) Enable and increase if needed - //#define BLTOUCH_HEATERS_OFF // Enable if the probe seems unreliable. Heaters will be disabled for each probe. #endif +/** + * Enable if probing seems unreliable. Heaters and/or fans - consistent with the + * options selected below - will be disabled during probing so as to minimize + * potential EM interference by quieting/silencing the source of the 'noise' (the change + * in current flowing through the wires). This is likely most useful to users of the + * BLTouch probe, but may also help those with inductive or other probe types. + */ +//#define PROBING_HEATERS_OFF // Turn heaters off when probing +//#define PROBING_FANS_OFF // Turn fans off when probing + // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/Hephestos_2/Configuration.h b/Marlin/example_configurations/Hephestos_2/Configuration.h index 5c81632d8..e40dbb786 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration.h @@ -577,14 +577,23 @@ //#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles /** - * The BLTouch probe is a Hall effect sensor that emulates a servo. + * The BLTouch probe uses a Hall effect sensor and emulates a servo. */ //#define BLTOUCH #if ENABLED(BLTOUCH) //#define BLTOUCH_DELAY 375 // (ms) Enable and increase if needed - //#define BLTOUCH_HEATERS_OFF // Enable if the probe seems unreliable. Heaters will be disabled for each probe. #endif +/** + * Enable if probing seems unreliable. Heaters and/or fans - consistent with the + * options selected below - will be disabled during probing so as to minimize + * potential EM interference by quieting/silencing the source of the 'noise' (the change + * in current flowing through the wires). This is likely most useful to users of the + * BLTouch probe, but may also help those with inductive or other probe types. + */ +//#define PROBING_HEATERS_OFF // Turn heaters off when probing +//#define PROBING_FANS_OFF // Turn fans off when probing + // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/K8200/Configuration.h b/Marlin/example_configurations/K8200/Configuration.h index 914deba96..d370fc8a7 100644 --- a/Marlin/example_configurations/K8200/Configuration.h +++ b/Marlin/example_configurations/K8200/Configuration.h @@ -612,14 +612,23 @@ //#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles /** - * The BLTouch probe is a Hall effect sensor that emulates a servo. + * The BLTouch probe uses a Hall effect sensor and emulates a servo. */ //#define BLTOUCH #if ENABLED(BLTOUCH) //#define BLTOUCH_DELAY 375 // (ms) Enable and increase if needed - //#define BLTOUCH_HEATERS_OFF // Enable if the probe seems unreliable. Heaters will be disabled for each probe. #endif +/** + * Enable if probing seems unreliable. Heaters and/or fans - consistent with the + * options selected below - will be disabled during probing so as to minimize + * potential EM interference by quieting/silencing the source of the 'noise' (the change + * in current flowing through the wires). This is likely most useful to users of the + * BLTouch probe, but may also help those with inductive or other probe types. + */ +//#define PROBING_HEATERS_OFF // Turn heaters off when probing +//#define PROBING_FANS_OFF // Turn fans off when probing + // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/K8400/Configuration.h b/Marlin/example_configurations/K8400/Configuration.h index 1a0bd3e03..4b11a6a38 100644 --- a/Marlin/example_configurations/K8400/Configuration.h +++ b/Marlin/example_configurations/K8400/Configuration.h @@ -583,14 +583,23 @@ //#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles /** - * The BLTouch probe is a Hall effect sensor that emulates a servo. + * The BLTouch probe uses a Hall effect sensor and emulates a servo. */ //#define BLTOUCH #if ENABLED(BLTOUCH) //#define BLTOUCH_DELAY 375 // (ms) Enable and increase if needed - //#define BLTOUCH_HEATERS_OFF // Enable if the probe seems unreliable. Heaters will be disabled for each probe. #endif +/** + * Enable if probing seems unreliable. Heaters and/or fans - consistent with the + * options selected below - will be disabled during probing so as to minimize + * potential EM interference by quieting/silencing the source of the 'noise' (the change + * in current flowing through the wires). This is likely most useful to users of the + * BLTouch probe, but may also help those with inductive or other probe types. + */ +//#define PROBING_HEATERS_OFF // Turn heaters off when probing +//#define PROBING_FANS_OFF // Turn fans off when probing + // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/K8400/Dual-head/Configuration.h b/Marlin/example_configurations/K8400/Dual-head/Configuration.h index 4d04d6ea6..bd27e511b 100644 --- a/Marlin/example_configurations/K8400/Dual-head/Configuration.h +++ b/Marlin/example_configurations/K8400/Dual-head/Configuration.h @@ -583,14 +583,23 @@ //#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles /** - * The BLTouch probe is a Hall effect sensor that emulates a servo. + * The BLTouch probe uses a Hall effect sensor and emulates a servo. */ //#define BLTOUCH #if ENABLED(BLTOUCH) //#define BLTOUCH_DELAY 375 // (ms) Enable and increase if needed - //#define BLTOUCH_HEATERS_OFF // Enable if the probe seems unreliable. Heaters will be disabled for each probe. #endif +/** + * Enable if probing seems unreliable. Heaters and/or fans - consistent with the + * options selected below - will be disabled during probing so as to minimize + * potential EM interference by quieting/silencing the source of the 'noise' (the change + * in current flowing through the wires). This is likely most useful to users of the + * BLTouch probe, but may also help those with inductive or other probe types. + */ +//#define PROBING_HEATERS_OFF // Turn heaters off when probing +//#define PROBING_FANS_OFF // Turn fans off when probing + // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h index 1b18f8ba9..d03524625 100644 --- a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h +++ b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h @@ -583,14 +583,23 @@ //#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles /** - * The BLTouch probe is a Hall effect sensor that emulates a servo. + * The BLTouch probe uses a Hall effect sensor and emulates a servo. */ //#define BLTOUCH #if ENABLED(BLTOUCH) //#define BLTOUCH_DELAY 375 // (ms) Enable and increase if needed - //#define BLTOUCH_HEATERS_OFF // Enable if the probe seems unreliable. Heaters will be disabled for each probe. #endif +/** + * Enable if probing seems unreliable. Heaters and/or fans - consistent with the + * options selected below - will be disabled during probing so as to minimize + * potential EM interference by quieting/silencing the source of the 'noise' (the change + * in current flowing through the wires). This is likely most useful to users of the + * BLTouch probe, but may also help those with inductive or other probe types. + */ +//#define PROBING_HEATERS_OFF // Turn heaters off when probing +//#define PROBING_FANS_OFF // Turn fans off when probing + // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/RigidBot/Configuration.h b/Marlin/example_configurations/RigidBot/Configuration.h index 4a109a5c9..023e01653 100644 --- a/Marlin/example_configurations/RigidBot/Configuration.h +++ b/Marlin/example_configurations/RigidBot/Configuration.h @@ -582,14 +582,23 @@ //#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles /** - * The BLTouch probe is a Hall effect sensor that emulates a servo. + * The BLTouch probe uses a Hall effect sensor and emulates a servo. */ //#define BLTOUCH #if ENABLED(BLTOUCH) //#define BLTOUCH_DELAY 375 // (ms) Enable and increase if needed - //#define BLTOUCH_HEATERS_OFF // Enable if the probe seems unreliable. Heaters will be disabled for each probe. #endif +/** + * Enable if probing seems unreliable. Heaters and/or fans - consistent with the + * options selected below - will be disabled during probing so as to minimize + * potential EM interference by quieting/silencing the source of the 'noise' (the change + * in current flowing through the wires). This is likely most useful to users of the + * BLTouch probe, but may also help those with inductive or other probe types. + */ +//#define PROBING_HEATERS_OFF // Turn heaters off when probing +//#define PROBING_FANS_OFF // Turn fans off when probing + // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/SCARA/Configuration.h b/Marlin/example_configurations/SCARA/Configuration.h index 63bc0f333..251b46689 100644 --- a/Marlin/example_configurations/SCARA/Configuration.h +++ b/Marlin/example_configurations/SCARA/Configuration.h @@ -598,14 +598,23 @@ //#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles /** - * The BLTouch probe is a Hall effect sensor that emulates a servo. + * The BLTouch probe uses a Hall effect sensor and emulates a servo. */ //#define BLTOUCH #if ENABLED(BLTOUCH) //#define BLTOUCH_DELAY 375 // (ms) Enable and increase if needed - //#define BLTOUCH_HEATERS_OFF // Enable if the probe seems unreliable. Heaters will be disabled for each probe. #endif +/** + * Enable if probing seems unreliable. Heaters and/or fans - consistent with the + * options selected below - will be disabled during probing so as to minimize + * potential EM interference by quieting/silencing the source of the 'noise' (the change + * in current flowing through the wires). This is likely most useful to users of the + * BLTouch probe, but may also help those with inductive or other probe types. + */ +//#define PROBING_HEATERS_OFF // Turn heaters off when probing +//#define PROBING_FANS_OFF // Turn fans off when probing + // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/TAZ4/Configuration.h b/Marlin/example_configurations/TAZ4/Configuration.h index 1b3d640a4..117dab65e 100644 --- a/Marlin/example_configurations/TAZ4/Configuration.h +++ b/Marlin/example_configurations/TAZ4/Configuration.h @@ -603,14 +603,23 @@ //#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles /** - * The BLTouch probe is a Hall effect sensor that emulates a servo. + * The BLTouch probe uses a Hall effect sensor and emulates a servo. */ //#define BLTOUCH #if ENABLED(BLTOUCH) //#define BLTOUCH_DELAY 375 // (ms) Enable and increase if needed - //#define BLTOUCH_HEATERS_OFF // Enable if the probe seems unreliable. Heaters will be disabled for each probe. #endif +/** + * Enable if probing seems unreliable. Heaters and/or fans - consistent with the + * options selected below - will be disabled during probing so as to minimize + * potential EM interference by quieting/silencing the source of the 'noise' (the change + * in current flowing through the wires). This is likely most useful to users of the + * BLTouch probe, but may also help those with inductive or other probe types. + */ +//#define PROBING_HEATERS_OFF // Turn heaters off when probing +//#define PROBING_FANS_OFF // Turn fans off when probing + // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/TinyBoy2/Configuration.h b/Marlin/example_configurations/TinyBoy2/Configuration.h index 39b4ca6b1..48f8708ce 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration.h @@ -634,14 +634,23 @@ //#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles /** - * The BLTouch probe is a Hall effect sensor that emulates a servo. + * The BLTouch probe uses a Hall effect sensor and emulates a servo. */ //#define BLTOUCH #if ENABLED(BLTOUCH) //#define BLTOUCH_DELAY 375 // (ms) Enable and increase if needed - //#define BLTOUCH_HEATERS_OFF // Enable if the probe seems unreliable. Heaters will be disabled for each probe. #endif +/** + * Enable if probing seems unreliable. Heaters and/or fans - consistent with the + * options selected below - will be disabled during probing so as to minimize + * potential EM interference by quieting/silencing the source of the 'noise' (the change + * in current flowing through the wires). This is likely most useful to users of the + * BLTouch probe, but may also help those with inductive or other probe types. + */ +//#define PROBING_HEATERS_OFF // Turn heaters off when probing +//#define PROBING_FANS_OFF // Turn fans off when probing + // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/WITBOX/Configuration.h b/Marlin/example_configurations/WITBOX/Configuration.h index 4c6ac763b..c28c8613d 100644 --- a/Marlin/example_configurations/WITBOX/Configuration.h +++ b/Marlin/example_configurations/WITBOX/Configuration.h @@ -574,14 +574,23 @@ //#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles /** - * The BLTouch probe is a Hall effect sensor that emulates a servo. + * The BLTouch probe uses a Hall effect sensor and emulates a servo. */ //#define BLTOUCH #if ENABLED(BLTOUCH) //#define BLTOUCH_DELAY 375 // (ms) Enable and increase if needed - //#define BLTOUCH_HEATERS_OFF // Enable if the probe seems unreliable. Heaters will be disabled for each probe. #endif +/** + * Enable if probing seems unreliable. Heaters and/or fans - consistent with the + * options selected below - will be disabled during probing so as to minimize + * potential EM interference by quieting/silencing the source of the 'noise' (the change + * in current flowing through the wires). This is likely most useful to users of the + * BLTouch probe, but may also help those with inductive or other probe types. + */ +//#define PROBING_HEATERS_OFF // Turn heaters off when probing +//#define PROBING_FANS_OFF // Turn fans off when probing + // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/adafruit/ST7565/Configuration.h b/Marlin/example_configurations/adafruit/ST7565/Configuration.h index a620b8029..e5d040e03 100644 --- a/Marlin/example_configurations/adafruit/ST7565/Configuration.h +++ b/Marlin/example_configurations/adafruit/ST7565/Configuration.h @@ -583,14 +583,23 @@ //#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles /** - * The BLTouch probe is a Hall effect sensor that emulates a servo. + * The BLTouch probe uses a Hall effect sensor and emulates a servo. */ //#define BLTOUCH #if ENABLED(BLTOUCH) //#define BLTOUCH_DELAY 375 // (ms) Enable and increase if needed - //#define BLTOUCH_HEATERS_OFF // Enable if the probe seems unreliable. Heaters will be disabled for each probe. #endif +/** + * Enable if probing seems unreliable. Heaters and/or fans - consistent with the + * options selected below - will be disabled during probing so as to minimize + * potential EM interference by quieting/silencing the source of the 'noise' (the change + * in current flowing through the wires). This is likely most useful to users of the + * BLTouch probe, but may also help those with inductive or other probe types. + */ +//#define PROBING_HEATERS_OFF // Turn heaters off when probing +//#define PROBING_FANS_OFF // Turn fans off when probing + // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h index f31c8f9e8..42f6b3f3e 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h @@ -651,14 +651,23 @@ //#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles /** - * The BLTouch probe is a Hall effect sensor that emulates a servo. + * The BLTouch probe uses a Hall effect sensor and emulates a servo. */ //#define BLTOUCH #if ENABLED(BLTOUCH) //#define BLTOUCH_DELAY 375 // (ms) Enable and increase if needed - //#define BLTOUCH_HEATERS_OFF // Enable if the probe seems unreliable. Heaters will be disabled for each probe. #endif +/** + * Enable if probing seems unreliable. Heaters and/or fans - consistent with the + * options selected below - will be disabled during probing so as to minimize + * potential EM interference by quieting/silencing the source of the 'noise' (the change + * in current flowing through the wires). This is likely most useful to users of the + * BLTouch probe, but may also help those with inductive or other probe types. + */ +//#define PROBING_HEATERS_OFF // Turn heaters off when probing +//#define PROBING_FANS_OFF // Turn fans off when probing + // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h index 7e312bfcb..09122c2ac 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h @@ -658,14 +658,23 @@ //#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles /** - * The BLTouch probe is a Hall effect sensor that emulates a servo. + * The BLTouch probe uses a Hall effect sensor and emulates a servo. */ //#define BLTOUCH #if ENABLED(BLTOUCH) //#define BLTOUCH_DELAY 375 // (ms) Enable and increase if needed - //#define BLTOUCH_HEATERS_OFF // Enable if the probe seems unreliable. Heaters will be disabled for each probe. #endif +/** + * Enable if probing seems unreliable. Heaters and/or fans - consistent with the + * options selected below - will be disabled during probing so as to minimize + * potential EM interference by quieting/silencing the source of the 'noise' (the change + * in current flowing through the wires). This is likely most useful to users of the + * BLTouch probe, but may also help those with inductive or other probe types. + */ +//#define PROBING_HEATERS_OFF // Turn heaters off when probing +//#define PROBING_FANS_OFF // Turn fans off when probing + // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index 0cceaf4c7..aeee57b4d 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -647,14 +647,23 @@ //#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles /** - * The BLTouch probe is a Hall effect sensor that emulates a servo. + * The BLTouch probe uses a Hall effect sensor and emulates a servo. */ //#define BLTOUCH #if ENABLED(BLTOUCH) //#define BLTOUCH_DELAY 375 // (ms) Enable and increase if needed - //#define BLTOUCH_HEATERS_OFF // Enable if the probe seems unreliable. Heaters will be disabled for each probe. #endif +/** + * Enable if probing seems unreliable. Heaters and/or fans - consistent with the + * options selected below - will be disabled during probing so as to minimize + * potential EM interference by quieting/silencing the source of the 'noise' (the change + * in current flowing through the wires). This is likely most useful to users of the + * BLTouch probe, but may also help those with inductive or other probe types. + */ +//#define PROBING_HEATERS_OFF // Turn heaters off when probing +//#define PROBING_FANS_OFF // Turn fans off when probing + // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index ff3f5b286..2bfb11415 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -642,14 +642,23 @@ //#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles /** - * The BLTouch probe is a Hall effect sensor that emulates a servo. + * The BLTouch probe uses a Hall effect sensor and emulates a servo. */ //#define BLTOUCH #if ENABLED(BLTOUCH) //#define BLTOUCH_DELAY 375 // (ms) Enable and increase if needed - //#define BLTOUCH_HEATERS_OFF // Enable if the probe seems unreliable. Heaters will be disabled for each probe. #endif +/** + * Enable if probing seems unreliable. Heaters and/or fans - consistent with the + * options selected below - will be disabled during probing so as to minimize + * potential EM interference by quieting/silencing the source of the 'noise' (the change + * in current flowing through the wires). This is likely most useful to users of the + * BLTouch probe, but may also help those with inductive or other probe types. + */ +//#define PROBING_HEATERS_OFF // Turn heaters off when probing +//#define PROBING_FANS_OFF // Turn fans off when probing + // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration.h b/Marlin/example_configurations/delta/kossel_pro/Configuration.h index 2128469ea..a5d7161ed 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration.h @@ -641,14 +641,23 @@ //#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles /** - * The BLTouch probe is a Hall effect sensor that emulates a servo. + * The BLTouch probe uses a Hall effect sensor and emulates a servo. */ //#define BLTOUCH #if ENABLED(BLTOUCH) //#define BLTOUCH_DELAY 375 // (ms) Enable and increase if needed - //#define BLTOUCH_HEATERS_OFF // Enable if the probe seems unreliable. Heaters will be disabled for each probe. #endif +/** + * Enable if probing seems unreliable. Heaters and/or fans - consistent with the + * options selected below - will be disabled during probing so as to minimize + * potential EM interference by quieting/silencing the source of the 'noise' (the change + * in current flowing through the wires). This is likely most useful to users of the + * BLTouch probe, but may also help those with inductive or other probe types. + */ +//#define PROBING_HEATERS_OFF // Turn heaters off when probing +//#define PROBING_FANS_OFF // Turn fans off when probing + // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration.h b/Marlin/example_configurations/delta/kossel_xl/Configuration.h index 479b4e466..d35301732 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration.h @@ -660,14 +660,23 @@ //#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles /** - * The BLTouch probe is a Hall effect sensor that emulates a servo. + * The BLTouch probe uses a Hall effect sensor and emulates a servo. */ //#define BLTOUCH #if ENABLED(BLTOUCH) //#define BLTOUCH_DELAY 375 // (ms) Enable and increase if needed - //#define BLTOUCH_HEATERS_OFF // Enable if the probe seems unreliable. Heaters will be disabled for each probe. #endif +/** + * Enable if probing seems unreliable. Heaters and/or fans - consistent with the + * options selected below - will be disabled during probing so as to minimize + * potential EM interference by quieting/silencing the source of the 'noise' (the change + * in current flowing through the wires). This is likely most useful to users of the + * BLTouch probe, but may also help those with inductive or other probe types. + */ +//#define PROBING_HEATERS_OFF // Turn heaters off when probing +//#define PROBING_FANS_OFF // Turn fans off when probing + // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h index 62ccbfefa..9fda1367c 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h @@ -569,11 +569,22 @@ //#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles /** - * The BLTouch probe is a Hall effect sensor that emulates a servo. + * The BLTouch probe uses a Hall effect sensor and emulates a servo. */ #define BLTOUCH -#define BLTOUCH_DELAY 500 // (ms) Enable and increase if needed -#define BLTOUCH_HEATERS_OFF // if defined the printer's heaters are turned off during probe event +#if ENABLED(BLTOUCH) + #define BLTOUCH_DELAY 500 // (ms) Enable and increase if needed +#endif + +/** + * Enable if probing seems unreliable. Heaters and/or fans - consistent with the + * options selected below - will be disabled during probing so as to minimize + * potential EM interference by quieting/silencing the source of the 'noise' (the change + * in current flowing through the wires). This is likely most useful to users of the + * BLTouch probe, but may also help those with inductive or other probe types. + */ +//#define PROBING_HEATERS_OFF // Turn heaters off when probing +//#define PROBING_FANS_OFF // Turn fans off when probing // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/makibox/Configuration.h b/Marlin/example_configurations/makibox/Configuration.h index 735278440..dbe6e2e09 100644 --- a/Marlin/example_configurations/makibox/Configuration.h +++ b/Marlin/example_configurations/makibox/Configuration.h @@ -586,14 +586,23 @@ //#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles /** - * The BLTouch probe is a Hall effect sensor that emulates a servo. + * The BLTouch probe uses a Hall effect sensor and emulates a servo. */ //#define BLTOUCH #if ENABLED(BLTOUCH) //#define BLTOUCH_DELAY 375 // (ms) Enable and increase if needed - //#define BLTOUCH_HEATERS_OFF // Enable if the probe seems unreliable. Heaters will be disabled for each probe. #endif +/** + * Enable if probing seems unreliable. Heaters and/or fans - consistent with the + * options selected below - will be disabled during probing so as to minimize + * potential EM interference by quieting/silencing the source of the 'noise' (the change + * in current flowing through the wires). This is likely most useful to users of the + * BLTouch probe, but may also help those with inductive or other probe types. + */ +//#define PROBING_HEATERS_OFF // Turn heaters off when probing +//#define PROBING_FANS_OFF // Turn fans off when probing + // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration.h b/Marlin/example_configurations/tvrrug/Round2/Configuration.h index ec6485eab..9ce54e88f 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration.h @@ -579,14 +579,23 @@ //#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles /** - * The BLTouch probe is a Hall effect sensor that emulates a servo. + * The BLTouch probe uses a Hall effect sensor and emulates a servo. */ //#define BLTOUCH #if ENABLED(BLTOUCH) //#define BLTOUCH_DELAY 375 // (ms) Enable and increase if needed - //#define BLTOUCH_HEATERS_OFF // Enable if the probe seems unreliable. Heaters will be disabled for each probe. #endif +/** + * Enable if probing seems unreliable. Heaters and/or fans - consistent with the + * options selected below - will be disabled during probing so as to minimize + * potential EM interference by quieting/silencing the source of the 'noise' (the change + * in current flowing through the wires). This is likely most useful to users of the + * BLTouch probe, but may also help those with inductive or other probe types. + */ +//#define PROBING_HEATERS_OFF // Turn heaters off when probing +//#define PROBING_FANS_OFF // Turn fans off when probing + // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/wt150/Configuration.h b/Marlin/example_configurations/wt150/Configuration.h index 5deaccf7d..acf6b1155 100644 --- a/Marlin/example_configurations/wt150/Configuration.h +++ b/Marlin/example_configurations/wt150/Configuration.h @@ -588,14 +588,23 @@ //#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles /** - * The BLTouch probe is a Hall effect sensor that emulates a servo. + * The BLTouch probe uses a Hall effect sensor and emulates a servo. */ //#define BLTOUCH #if ENABLED(BLTOUCH) //#define BLTOUCH_DELAY 375 // (ms) Enable and increase if needed - //#define BLTOUCH_HEATERS_OFF // Enable if the probe seems unreliable. Heaters will be disabled for each probe. #endif +/** + * Enable if probing seems unreliable. Heaters and/or fans - consistent with the + * options selected below - will be disabled during probing so as to minimize + * potential EM interference by quieting/silencing the source of the 'noise' (the change + * in current flowing through the wires). This is likely most useful to users of the + * BLTouch probe, but may also help those with inductive or other probe types. + */ +//#define PROBING_HEATERS_OFF // Turn heaters off when probing +//#define PROBING_FANS_OFF // Turn fans off when probing + // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/temperature.cpp b/Marlin/temperature.cpp index 7a480b87a..dbadd06f3 100644 --- a/Marlin/temperature.cpp +++ b/Marlin/temperature.cpp @@ -204,6 +204,14 @@ uint8_t Temperature::soft_pwm[HOTENDS]; int Temperature::current_raw_filwidth = 0; //Holds measured filament diameter - one extruder only #endif +#if ENABLED(PROBING_HEATERS_OFF) + bool Temperature::paused; + int16_t Temperature::paused_hotend_temps[HOTENDS]; + #if HAS_TEMP_BED + int16_t Temperature::paused_bed_temp; + #endif +#endif + #if HAS_PID_HEATING void Temperature::PID_autotune(float temp, int hotend, int ncycles, bool set_result/*=false*/) { @@ -1194,6 +1202,14 @@ void Temperature::init() { #endif } #endif //BED_MAXTEMP + + #if ENABLED(PROBING_HEATERS_OFF) + paused = false; + ZERO(paused_hotend_temps); + #if HAS_TEMP_BED + paused_bed_temp = 0; + #endif + #endif } #if WATCH_HOTENDS @@ -1297,6 +1313,15 @@ void Temperature::disable_all_heaters() { HOTEND_LOOP() setTargetHotend(0, e); setTargetBed(0); + // Unpause and reset everything + #if ENABLED(PROBING_HEATERS_OFF) + paused = false; + ZERO(paused_hotend_temps); + #if HAS_TEMP_BED + paused_bed_temp = 0; + #endif + #endif + // If all heaters go down then for sure our print job has stopped print_job_timer.stop(); @@ -1331,6 +1356,45 @@ void Temperature::disable_all_heaters() { #endif } +#if ENABLED(PROBING_HEATERS_OFF) + void Temperature::pause(bool p) { + if (p && paused) { // If called out of order something is wrong + SERIAL_ERROR_START; + SERIAL_ERRORLNPGM("Heaters already paused!"); + return; + } + + if (!p && !paused) { + SERIAL_ERROR_START; + SERIAL_ERRORLNPGM("Heaters already unpaused!"); + return; + } + + if (p) { + HOTEND_LOOP() { + paused_hotend_temps[e] = degTargetHotend(e); + setTargetHotend(0, e); + } + #if HAS_TEMP_BED + paused_bed_temp = degTargetBed(); + setTargetBed(0); + #endif + } + else { + HOTEND_LOOP() setTargetHotend(paused_hotend_temps[e], e); + #if HAS_TEMP_BED + setTargetBed(paused_bed_temp); + #endif + } + + paused = p; + } + + bool Temperature::ispaused() { + return paused; + } +#endif + #if ENABLED(HEATER_0_USES_MAX6675) #define MAX6675_HEAT_INTERVAL 250u diff --git a/Marlin/temperature.h b/Marlin/temperature.h index 35d80731e..7fc9926c3 100644 --- a/Marlin/temperature.h +++ b/Marlin/temperature.h @@ -259,6 +259,15 @@ class Temperature { static int current_raw_filwidth; //Holds measured filament diameter - one extruder only #endif + #if ENABLED(PROBING_HEATERS_OFF) + static bool paused; + static int16_t paused_hotend_temps[HOTENDS]; + + #if HAS_TEMP_BED + static int16_t paused_bed_temp; + #endif + #endif + public: /** @@ -452,6 +461,11 @@ class Temperature { #endif // BABYSTEPPING + #if ENABLED(PROBING_HEATERS_OFF) + static void pause(bool p); + static bool ispaused(); + #endif + private: static void set_current_temp_raw(); From d92fa40c62912720eaa09012102c24fcb8370e2c Mon Sep 17 00:00:00 2001 From: Roxy-3D Date: Sun, 7 May 2017 18:23:48 -0500 Subject: [PATCH 015/189] misc. UBL fixes (#6631) * Restore LSF functionality Some of the typo's persisted... Hopefully this gets them all fixed. * Restore user's expectations of how G28 should behave * Allow Nozzle size control with ornery host programs --- Marlin/G26_Mesh_Validation_Tool.cpp | 3 ++- Marlin/Marlin_main.cpp | 6 ++++++ Marlin/least_squares_fit.cpp | 6 +++--- 3 files changed, 11 insertions(+), 4 deletions(-) diff --git a/Marlin/G26_Mesh_Validation_Tool.cpp b/Marlin/G26_Mesh_Validation_Tool.cpp index 0924d7d8b..3d93baa91 100644 --- a/Marlin/G26_Mesh_Validation_Tool.cpp +++ b/Marlin/G26_Mesh_Validation_Tool.cpp @@ -92,6 +92,7 @@ * un-retraction is at 1.2mm These numbers will be scaled by the specified amount * * N # Nozzle Used to control the size of nozzle diameter. If not specified, a .4mm nozzle is assumed. + * 'n' can be used instead if your host program does not appreciate you using 'N'. * * O # Ooooze How much your nozzle will Ooooze filament while getting in position to print. This * is over kill, but using this parameter will let you get the very first 'cicle' perfect @@ -674,7 +675,7 @@ } } - if (code_seen('N')) { + if (code_seen('N') || code_seen('n')) { nozzle = code_value_float(); if (!WITHIN(nozzle, 0.1, 1.0)) { SERIAL_PROTOCOLLNPGM("?Specified nozzle size not plausible."); diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 43639d99a..90bcacc40 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -3741,6 +3741,9 @@ inline void gcode_G28() { // Disable the leveling matrix before homing #if HAS_LEVELING + #if ENABLED(AUTO_BED_LEVELING_UBL) + const bool bed_leveling_state_at_entry = ubl.state.active; + #endif set_bed_leveling_enabled(false); #endif @@ -3882,6 +3885,9 @@ inline void gcode_G28() { // move to a height where we can use the full xy-area do_blocking_move_to_z(delta_clip_start_height); #endif + #if ENABLED(AUTO_BED_LEVELING_UBL) + set_bed_leveling_enabled(bed_leveling_state_at_entry); + #endif clean_up_after_endstop_or_probe_move(); diff --git a/Marlin/least_squares_fit.cpp b/Marlin/least_squares_fit.cpp index 271aae11f..f7b8163e8 100644 --- a/Marlin/least_squares_fit.cpp +++ b/Marlin/least_squares_fit.cpp @@ -52,9 +52,9 @@ void incremental_LSF(struct linear_fit_data *lsf, float x, float y, float z) { lsf->x2bar += sq(x); lsf->y2bar += sq(y); lsf->z2bar += sq(z); - lsf->xybar += sq(x); - lsf->xzbar += sq(x); - lsf->yzbar += sq(y); + lsf->xybar += x*y; + lsf->xzbar += x*z; + lsf->yzbar += y*z; lsf->max_absx = max(fabs(x), lsf->max_absx); lsf->max_absy = max(fabs(y), lsf->max_absy); lsf->n++; From 110afff4151fee954d7aa8132fb64bf0d172617c Mon Sep 17 00:00:00 2001 From: Roxy-3D Date: Sun, 7 May 2017 19:02:24 -0500 Subject: [PATCH 016/189] More misc UBL fixes and update gMax examples (#6632) I think I forgot to Sync before I committed last time. Some UBL changes did not stick. Also, update the gMax configuaration.h file so other than unique numbers and settings, it exactly matches the default configuration.h file. --- .../gCreate_gMax1.5+/Configuration.h | 44 ++++++++++++++++--- Marlin/ubl.cpp | 6 +-- Marlin/ubl_motion.cpp | 3 +- 3 files changed, 42 insertions(+), 11 deletions(-) diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h index 62ccbfefa..c83f9ddfa 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h @@ -532,21 +532,51 @@ #define DEFAULT_ZJERK 1.0 #define DEFAULT_EJERK 4.0 +//=========================================================================== +//============================= Z Probe Options ============================= +//=========================================================================== +// @section probes + +// +// See http://marlinfw.org/configuration/probes.html +// + + +/** + * Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN + * + * Enable this option for a probe connected to the Z Min endstop pin. + */ +#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN + /** - * =========================================================================== - * ============================= Z Probe Options ============================= - * =========================================================================== - * @section probes + * Z_MIN_PROBE_ENDSTOP + * + * Enable this option for a probe connected to any pin except Z-Min. + * (By default Marlin assumes the Z-Max endstop pin.) + * To use a custom Z Probe pin, set Z_MIN_PROBE_PIN below. + * + * - The simplest option is to use a free endstop connector. + * - Use 5V for powered (usually inductive) sensors. + * + * - RAMPS 1.3/1.4 boards may use the 5V, GND, and Aux4->D32 pin: + * - For simple switches connect... + * - normally-closed switches to GND and D32. + * - normally-open switches to 5V and D32. * + * WARNING: Setting the wrong pin may have unexpected and potentially + * disastrous consequences. Use with caution and do your homework. * + */ +//#define Z_MIN_PROBE_ENDSTOP +//#define Z_MIN_PROBE_PIN Z_MAX_PIN + +/** * Probe Type - * Probes are sensors/switches that are activated / deactivated before/after use. * * Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc. * You must activate one of these to use Auto Bed Leveling below. - * - * Use M851 to set the Z probe vertical offset from the nozzle. Store with M500. */ /** diff --git a/Marlin/ubl.cpp b/Marlin/ubl.cpp index 5471b178e..b1d31fe68 100644 --- a/Marlin/ubl.cpp +++ b/Marlin/ubl.cpp @@ -136,7 +136,7 @@ void unified_bed_leveling::display_map(const int map_type) { const bool map0 = map_type == 0; - const uint8_t spaces = 9; + const uint8_t spaces = 11; if (map0) { SERIAL_PROTOCOLLNPGM("\nBed Topography Report:\n"); @@ -145,7 +145,7 @@ serial_echo_xy(GRID_MAX_POINTS_X - 1, GRID_MAX_POINTS_Y - 1); SERIAL_EOL; serial_echo_xy(UBL_MESH_MIN_X, UBL_MESH_MAX_Y); - SERIAL_ECHO_SP(spaces * (GRID_MAX_POINTS_X - 2)); + SERIAL_ECHO_SP(spaces * (GRID_MAX_POINTS_X - 2)-3); serial_echo_xy(UBL_MESH_MAX_X, UBL_MESH_MAX_Y); SERIAL_EOL; } @@ -190,7 +190,7 @@ if (map0) { serial_echo_xy(UBL_MESH_MIN_X, UBL_MESH_MIN_Y); - SERIAL_ECHO_SP(spaces * (GRID_MAX_POINTS_X - 2) + 4); + SERIAL_ECHO_SP(spaces * (GRID_MAX_POINTS_X - 2) + 1); serial_echo_xy(UBL_MESH_MAX_X, UBL_MESH_MIN_Y); SERIAL_EOL; serial_echo_xy(0, 0); diff --git a/Marlin/ubl_motion.cpp b/Marlin/ubl_motion.cpp index b1f8946e5..a6065dab5 100644 --- a/Marlin/ubl_motion.cpp +++ b/Marlin/ubl_motion.cpp @@ -225,7 +225,8 @@ const float e_normalized_dist = e_position / on_axis_distance, z_normalized_dist = z_position / on_axis_distance; - int current_xi = cell_start_xi, current_yi = cell_start_yi; + int current_xi = cell_start_xi, + current_yi = cell_start_yi; const float m = dy / dx, c = start[Y_AXIS] - m * start[X_AXIS]; From 6ed52fb765f6dbf55859c8bee9f06abc05f7528f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 7 May 2017 19:11:52 -0500 Subject: [PATCH 017/189] Adjust spacing in LSF --- Marlin/least_squares_fit.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/least_squares_fit.cpp b/Marlin/least_squares_fit.cpp index f7b8163e8..e91c58d17 100644 --- a/Marlin/least_squares_fit.cpp +++ b/Marlin/least_squares_fit.cpp @@ -52,9 +52,9 @@ void incremental_LSF(struct linear_fit_data *lsf, float x, float y, float z) { lsf->x2bar += sq(x); lsf->y2bar += sq(y); lsf->z2bar += sq(z); - lsf->xybar += x*y; - lsf->xzbar += x*z; - lsf->yzbar += y*z; + lsf->xybar += x * y; + lsf->xzbar += x * z; + lsf->yzbar += y * z; lsf->max_absx = max(fabs(x), lsf->max_absx); lsf->max_absy = max(fabs(y), lsf->max_absy); lsf->n++; From 6e4a5cc8c633dd385b44a844d5145f1081fb5352 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 7 May 2017 21:13:44 -0500 Subject: [PATCH 018/189] Patch missing const in temp_abs --- Marlin/configuration_store.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/configuration_store.cpp b/Marlin/configuration_store.cpp index 0a8796970..ef7e04014 100644 --- a/Marlin/configuration_store.cpp +++ b/Marlin/configuration_store.cpp @@ -1257,7 +1257,7 @@ void MarlinSettings::reset() { CONFIG_ECHO_START; #if ENABLED(TEMPERATURE_UNITS_SUPPORT) extern TempUnit input_temp_units; - extern float temp_abs(float &f); + extern float temp_abs(const float &f); #define TEMP_UNIT(N) temp_abs(N) SERIAL_ECHOPGM(" M149 "); SERIAL_CHAR(input_temp_units == TEMPUNIT_K ? 'K' : input_temp_units == TEMPUNIT_F ? 'F' : 'C'); From 1c4ed8b106f65cecda9ed369bf241230185e8034 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 7 May 2017 00:28:06 -0500 Subject: [PATCH 019/189] Note 5 extruders in config comments --- Marlin/Configuration.h | 6 +++--- Marlin/example_configurations/Cartesio/Configuration.h | 6 +++--- Marlin/example_configurations/Felix/Configuration.h | 6 +++--- Marlin/example_configurations/Felix/DUAL/Configuration.h | 6 +++--- .../FolgerTech-i3-2020/Configuration.h | 6 +++--- Marlin/example_configurations/Hephestos/Configuration.h | 6 +++--- Marlin/example_configurations/Hephestos_2/Configuration.h | 6 +++--- Marlin/example_configurations/K8200/Configuration.h | 6 +++--- Marlin/example_configurations/K8400/Configuration.h | 6 +++--- .../example_configurations/K8400/Dual-head/Configuration.h | 6 +++--- .../RepRapWorld/Megatronics/Configuration.h | 6 +++--- Marlin/example_configurations/RigidBot/Configuration.h | 6 +++--- Marlin/example_configurations/SCARA/Configuration.h | 6 +++--- Marlin/example_configurations/TAZ4/Configuration.h | 6 +++--- Marlin/example_configurations/TinyBoy2/Configuration.h | 6 +++--- Marlin/example_configurations/WITBOX/Configuration.h | 6 +++--- .../example_configurations/adafruit/ST7565/Configuration.h | 6 +++--- .../delta/FLSUN/auto_calibrate/Configuration.h | 6 +++--- .../delta/FLSUN/kossel_mini/Configuration.h | 6 +++--- Marlin/example_configurations/delta/generic/Configuration.h | 6 +++--- .../delta/kossel_mini/Configuration.h | 6 +++--- .../example_configurations/delta/kossel_pro/Configuration.h | 6 +++--- .../example_configurations/delta/kossel_xl/Configuration.h | 6 +++--- .../example_configurations/gCreate_gMax1.5+/Configuration.h | 6 +++--- Marlin/example_configurations/makibox/Configuration.h | 6 +++--- Marlin/example_configurations/tvrrug/Round2/Configuration.h | 6 +++--- Marlin/example_configurations/wt150/Configuration.h | 6 +++--- 27 files changed, 81 insertions(+), 81 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index b2f0cc639..10aeda5e8 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -474,14 +474,14 @@ /** * Default Axis Steps Per Unit (steps/mm) * Override with M92 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_AXIS_STEPS_PER_UNIT { 80, 80, 4000, 500 } /** * Default Max Feed Rate (mm/s) * Override with M203 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_FEEDRATE { 300, 300, 5, 25 } @@ -489,7 +489,7 @@ * Default Max Acceleration (change/s) change = mm/s * (Maximum start speed for accelerated moves) * Override with M201 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_ACCELERATION { 3000, 3000, 100, 10000 } diff --git a/Marlin/example_configurations/Cartesio/Configuration.h b/Marlin/example_configurations/Cartesio/Configuration.h index b029b4b53..39f857d9c 100644 --- a/Marlin/example_configurations/Cartesio/Configuration.h +++ b/Marlin/example_configurations/Cartesio/Configuration.h @@ -473,14 +473,14 @@ /** * Default Axis Steps Per Unit (steps/mm) * Override with M92 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_AXIS_STEPS_PER_UNIT { 71.128, 71.128, 640, 152 } /** * Default Max Feed Rate (mm/s) * Override with M203 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_FEEDRATE { 200, 200, 20, 20 } @@ -488,7 +488,7 @@ * Default Max Acceleration (change/s) change = mm/s * (Maximum start speed for accelerated moves) * Override with M201 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_ACCELERATION { 1000, 1000, 100, 10000 } diff --git a/Marlin/example_configurations/Felix/Configuration.h b/Marlin/example_configurations/Felix/Configuration.h index eaf92c943..bb74b12d1 100644 --- a/Marlin/example_configurations/Felix/Configuration.h +++ b/Marlin/example_configurations/Felix/Configuration.h @@ -457,14 +457,14 @@ /** * Default Axis Steps Per Unit (steps/mm) * Override with M92 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_AXIS_STEPS_PER_UNIT { 76.190476, 76.190476, 1600, 164 } /** * Default Max Feed Rate (mm/s) * Override with M203 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_FEEDRATE { 500, 500, 5, 25 } @@ -472,7 +472,7 @@ * Default Max Acceleration (change/s) change = mm/s * (Maximum start speed for accelerated moves) * Override with M201 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_ACCELERATION { 5000, 5000, 100, 80000 } diff --git a/Marlin/example_configurations/Felix/DUAL/Configuration.h b/Marlin/example_configurations/Felix/DUAL/Configuration.h index 506faaf03..14fc25e83 100644 --- a/Marlin/example_configurations/Felix/DUAL/Configuration.h +++ b/Marlin/example_configurations/Felix/DUAL/Configuration.h @@ -457,14 +457,14 @@ /** * Default Axis Steps Per Unit (steps/mm) * Override with M92 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_AXIS_STEPS_PER_UNIT { 76.190476, 76.190476, 1600, 164 } /** * Default Max Feed Rate (mm/s) * Override with M203 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_FEEDRATE { 500, 500, 5, 25 } @@ -472,7 +472,7 @@ * Default Max Acceleration (change/s) change = mm/s * (Maximum start speed for accelerated moves) * Override with M201 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_ACCELERATION { 5000, 5000, 100, 80000 } diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h index 7c3944637..1c473e035 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h @@ -480,14 +480,14 @@ /** * Default Axis Steps Per Unit (steps/mm) * Override with M92 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_AXIS_STEPS_PER_UNIT { 80, 80, 4000, 52.2 } /** * Default Max Feed Rate (mm/s) * Override with M203 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_FEEDRATE { 250, 250, 2, 17 } @@ -495,7 +495,7 @@ * Default Max Acceleration (change/s) change = mm/s * (Maximum start speed for accelerated moves) * Override with M201 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_ACCELERATION { 1000, 1000, 4, 750 } diff --git a/Marlin/example_configurations/Hephestos/Configuration.h b/Marlin/example_configurations/Hephestos/Configuration.h index 43be117b7..2e483b1c2 100644 --- a/Marlin/example_configurations/Hephestos/Configuration.h +++ b/Marlin/example_configurations/Hephestos/Configuration.h @@ -465,14 +465,14 @@ /** * Default Axis Steps Per Unit (steps/mm) * Override with M92 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_AXIS_STEPS_PER_UNIT { 80, 80, 4000, 100.47095761381482 } /** * Default Max Feed Rate (mm/s) * Override with M203 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_FEEDRATE { 200, 200, 3.3, 25 } @@ -480,7 +480,7 @@ * Default Max Acceleration (change/s) change = mm/s * (Maximum start speed for accelerated moves) * Override with M201 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_ACCELERATION { 1100, 1100, 100, 10000 } diff --git a/Marlin/example_configurations/Hephestos_2/Configuration.h b/Marlin/example_configurations/Hephestos_2/Configuration.h index e40dbb786..35f6aea29 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration.h @@ -468,14 +468,14 @@ /** * Default Axis Steps Per Unit (steps/mm) * Override with M92 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_AXIS_STEPS_PER_UNIT { 160, 160, 8000, 204 } /** * Default Max Feed Rate (mm/s) * Override with M203 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_FEEDRATE { 250, 250, 2, 200 } @@ -483,7 +483,7 @@ * Default Max Acceleration (change/s) change = mm/s * (Maximum start speed for accelerated moves) * Override with M201 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_ACCELERATION { 800, 800, 20, 1000 } diff --git a/Marlin/example_configurations/K8200/Configuration.h b/Marlin/example_configurations/K8200/Configuration.h index d370fc8a7..bd79a11a5 100644 --- a/Marlin/example_configurations/K8200/Configuration.h +++ b/Marlin/example_configurations/K8200/Configuration.h @@ -504,13 +504,13 @@ /** * Default Axis Steps Per Unit (steps/mm) * Override with M92 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_AXIS_STEPS_PER_UNIT { 64.25, 64.25, 2560, 600 } /** * Default Max Feed Rate (mm/s) * Override with M203 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_FEEDRATE { 500, 500, 5, 25 } @@ -518,7 +518,7 @@ * Default Max Acceleration (change/s) change = mm/s * (Maximum start speed for accelerated moves) * Override with M201 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_ACCELERATION { 9000, 9000, 100, 10000 } diff --git a/Marlin/example_configurations/K8400/Configuration.h b/Marlin/example_configurations/K8400/Configuration.h index 4b11a6a38..429f37cda 100644 --- a/Marlin/example_configurations/K8400/Configuration.h +++ b/Marlin/example_configurations/K8400/Configuration.h @@ -474,14 +474,14 @@ /** * Default Axis Steps Per Unit (steps/mm) * Override with M92 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_AXIS_STEPS_PER_UNIT { 134.74, 134.74, 4266.66, 148.7 } /** * Default Max Feed Rate (mm/s) * Override with M203 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_FEEDRATE { 160, 160, 10, 10000 } @@ -489,7 +489,7 @@ * Default Max Acceleration (change/s) change = mm/s * (Maximum start speed for accelerated moves) * Override with M201 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_ACCELERATION { 9000, 9000, 100, 10000 } diff --git a/Marlin/example_configurations/K8400/Dual-head/Configuration.h b/Marlin/example_configurations/K8400/Dual-head/Configuration.h index bd27e511b..2b7a0b3e3 100644 --- a/Marlin/example_configurations/K8400/Dual-head/Configuration.h +++ b/Marlin/example_configurations/K8400/Dual-head/Configuration.h @@ -474,14 +474,14 @@ /** * Default Axis Steps Per Unit (steps/mm) * Override with M92 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_AXIS_STEPS_PER_UNIT { 134.74, 134.74, 4266.66, 148.7 } /** * Default Max Feed Rate (mm/s) * Override with M203 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_FEEDRATE { 160, 160, 10, 10000 } @@ -489,7 +489,7 @@ * Default Max Acceleration (change/s) change = mm/s * (Maximum start speed for accelerated moves) * Override with M201 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_ACCELERATION { 9000, 9000, 100, 10000 } diff --git a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h index d03524625..fad021c52 100644 --- a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h +++ b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h @@ -474,14 +474,14 @@ /** * Default Axis Steps Per Unit (steps/mm) * Override with M92 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_AXIS_STEPS_PER_UNIT { 78.7402*2, 78.7402*2, 5120.00, 760*1*1.5 } /** * Default Max Feed Rate (mm/s) * Override with M203 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_FEEDRATE { 300, 300, 5, 25 } @@ -489,7 +489,7 @@ * Default Max Acceleration (change/s) change = mm/s * (Maximum start speed for accelerated moves) * Override with M201 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_ACCELERATION { 3000, 3000, 100, 10000 } diff --git a/Marlin/example_configurations/RigidBot/Configuration.h b/Marlin/example_configurations/RigidBot/Configuration.h index 023e01653..b00a75d8e 100644 --- a/Marlin/example_configurations/RigidBot/Configuration.h +++ b/Marlin/example_configurations/RigidBot/Configuration.h @@ -471,7 +471,7 @@ /** * Default Axis Steps Per Unit (steps/mm) * Override with M92 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ // default steps per unit for RigidBot with standard hardware #define DEFAULT_AXIS_STEPS_PER_UNIT { 44.3090, 22.1545, 1600, 53.5 } @@ -480,7 +480,7 @@ /** * Default Max Feed Rate (mm/s) * Override with M203 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_FEEDRATE { 500, 500, 5, 25 } @@ -488,7 +488,7 @@ * Default Max Acceleration (change/s) change = mm/s * (Maximum start speed for accelerated moves) * Override with M201 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_ACCELERATION { 800, 800, 100, 10000 } diff --git a/Marlin/example_configurations/SCARA/Configuration.h b/Marlin/example_configurations/SCARA/Configuration.h index 251b46689..fcaf75b4e 100644 --- a/Marlin/example_configurations/SCARA/Configuration.h +++ b/Marlin/example_configurations/SCARA/Configuration.h @@ -489,14 +489,14 @@ /** * Default Axis Steps Per Unit (steps/mm) * Override with M92 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_AXIS_STEPS_PER_UNIT { 103.69, 106.65, 200/1.25, 1000 } // default steps per unit for SCARA /** * Default Max Feed Rate (mm/s) * Override with M203 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_FEEDRATE { 300, 300, 30, 25 } @@ -504,7 +504,7 @@ * Default Max Acceleration (change/s) change = mm/s * (Maximum start speed for accelerated moves) * Override with M201 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_ACCELERATION { 300, 300, 20, 1000 } diff --git a/Marlin/example_configurations/TAZ4/Configuration.h b/Marlin/example_configurations/TAZ4/Configuration.h index 117dab65e..c31994a38 100644 --- a/Marlin/example_configurations/TAZ4/Configuration.h +++ b/Marlin/example_configurations/TAZ4/Configuration.h @@ -494,14 +494,14 @@ /** * Default Axis Steps Per Unit (steps/mm) * Override with M92 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_AXIS_STEPS_PER_UNIT { 100.5, 100.5, 400, 850 } /** * Default Max Feed Rate (mm/s) * Override with M203 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_FEEDRATE { 800, 800, 8, 50 } @@ -509,7 +509,7 @@ * Default Max Acceleration (change/s) change = mm/s * (Maximum start speed for accelerated moves) * Override with M201 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_ACCELERATION { 9000, 9000, 100, 10000 } diff --git a/Marlin/example_configurations/TinyBoy2/Configuration.h b/Marlin/example_configurations/TinyBoy2/Configuration.h index 48f8708ce..662bd133e 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration.h @@ -525,14 +525,14 @@ /** * Default Axis Steps Per Unit (steps/mm) * Override with M92 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_AXIS_STEPS_PER_UNIT { 100, 100, 6400, 88.16 } /** * Default Max Feed Rate (mm/s) * Override with M203 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_FEEDRATE { 300, 300, 7, 35 } @@ -540,7 +540,7 @@ * Default Max Acceleration (change/s) change = mm/s * (Maximum start speed for accelerated moves) * Override with M201 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_ACCELERATION { 3000, 3000, 100, 10000 } diff --git a/Marlin/example_configurations/WITBOX/Configuration.h b/Marlin/example_configurations/WITBOX/Configuration.h index c28c8613d..25ec69ac6 100644 --- a/Marlin/example_configurations/WITBOX/Configuration.h +++ b/Marlin/example_configurations/WITBOX/Configuration.h @@ -465,14 +465,14 @@ /** * Default Axis Steps Per Unit (steps/mm) * Override with M92 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_AXIS_STEPS_PER_UNIT { 80, 80, 600.0*8/3, 102.073 } /** * Default Max Feed Rate (mm/s) * Override with M203 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_FEEDRATE { 350, 350, 7.2, 80 } @@ -480,7 +480,7 @@ * Default Max Acceleration (change/s) change = mm/s * (Maximum start speed for accelerated moves) * Override with M201 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_ACCELERATION { 1000, 1000, 10, 1000 } diff --git a/Marlin/example_configurations/adafruit/ST7565/Configuration.h b/Marlin/example_configurations/adafruit/ST7565/Configuration.h index e5d040e03..f95dfcc9c 100644 --- a/Marlin/example_configurations/adafruit/ST7565/Configuration.h +++ b/Marlin/example_configurations/adafruit/ST7565/Configuration.h @@ -474,14 +474,14 @@ /** * Default Axis Steps Per Unit (steps/mm) * Override with M92 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_AXIS_STEPS_PER_UNIT { 80, 80, 4000, 500 } /** * Default Max Feed Rate (mm/s) * Override with M203 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_FEEDRATE { 300, 300, 5, 25 } @@ -489,7 +489,7 @@ * Default Max Acceleration (change/s) change = mm/s * (Maximum start speed for accelerated moves) * Override with M201 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_ACCELERATION { 3000, 3000, 100, 10000 } diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h index 42f6b3f3e..c92671783 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h @@ -542,14 +542,14 @@ /** * Default Axis Steps Per Unit (steps/mm) * Override with M92 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_AXIS_STEPS_PER_UNIT { 100, 100, 100, 100 } // default steps per unit for Kossel (GT2, 20 tooth) /** * Default Max Feed Rate (mm/s) * Override with M203 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_FEEDRATE { 200, 200, 200, 25 } @@ -557,7 +557,7 @@ * Default Max Acceleration (change/s) change = mm/s * (Maximum start speed for accelerated moves) * Override with M201 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_ACCELERATION { 4000, 4000, 4000, 4000 } diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h index 09122c2ac..22e338003 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h @@ -549,14 +549,14 @@ /** * Default Axis Steps Per Unit (steps/mm) * Override with M92 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_AXIS_STEPS_PER_UNIT { 100, 100, 100, 90 } // default steps per unit for Kossel (GT2, 20 tooth) /** * Default Max Feed Rate (mm/s) * Override with M203 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_FEEDRATE { 200, 200, 200, 200 } @@ -564,7 +564,7 @@ * Default Max Acceleration (change/s) change = mm/s * (Maximum start speed for accelerated moves) * Override with M201 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_ACCELERATION { 4000, 4000, 4000, 4000 } diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index aeee57b4d..996100182 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -538,14 +538,14 @@ /** * Default Axis Steps Per Unit (steps/mm) * Override with M92 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_AXIS_STEPS_PER_UNIT { 80, 80, 80, 760*1.1 } // default steps per unit for Kossel (GT2, 20 tooth) /** * Default Max Feed Rate (mm/s) * Override with M203 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_FEEDRATE { 500, 500, 500, 25 } @@ -553,7 +553,7 @@ * Default Max Acceleration (change/s) change = mm/s * (Maximum start speed for accelerated moves) * Override with M201 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_ACCELERATION { 9000, 9000, 9000, 10000 } diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index 2bfb11415..0bf14708d 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -538,14 +538,14 @@ /** * Default Axis Steps Per Unit (steps/mm) * Override with M92 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_AXIS_STEPS_PER_UNIT { 80, 80, 80, 760*1.1 } // default steps per unit for Kossel (GT2, 20 tooth) /** * Default Max Feed Rate (mm/s) * Override with M203 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_FEEDRATE { 500, 500, 500, 25 } @@ -553,7 +553,7 @@ * Default Max Acceleration (change/s) change = mm/s * (Maximum start speed for accelerated moves) * Override with M201 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_ACCELERATION { 9000, 9000, 9000, 10000 } diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration.h b/Marlin/example_configurations/delta/kossel_pro/Configuration.h index a5d7161ed..bb769b172 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration.h @@ -532,14 +532,14 @@ /** * Default Axis Steps Per Unit (steps/mm) * Override with M92 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_AXIS_STEPS_PER_UNIT { XYZ_STEPS, XYZ_STEPS, XYZ_STEPS, 184.8 } /** * Default Max Feed Rate (mm/s) * Override with M203 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_FEEDRATE { 200, 200, 200, 200 } @@ -547,7 +547,7 @@ * Default Max Acceleration (change/s) change = mm/s * (Maximum start speed for accelerated moves) * Override with M201 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_ACCELERATION { 9000, 9000, 9000, 9000 } diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration.h b/Marlin/example_configurations/delta/kossel_xl/Configuration.h index d35301732..b8038252e 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration.h @@ -551,14 +551,14 @@ /** * Default Axis Steps Per Unit (steps/mm) * Override with M92 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_AXIS_STEPS_PER_UNIT { XYZ_STEPS, XYZ_STEPS, XYZ_STEPS, 158 } // default steps per unit for PowerWasp /** * Default Max Feed Rate (mm/s) * Override with M203 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_FEEDRATE { 200, 200, 200, 25 } @@ -566,7 +566,7 @@ * Default Max Acceleration (change/s) change = mm/s * (Maximum start speed for accelerated moves) * Override with M201 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_ACCELERATION { 9000, 9000, 9000, 10000 } diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h index 984b22569..1e172d5f9 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h @@ -488,14 +488,14 @@ /** * Default Axis Steps Per Unit (steps/mm) * Override with M92 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_AXIS_STEPS_PER_UNIT { 80, 80, 400, 96 } /** * Default Max Feed Rate (mm/s) * Override with M203 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_FEEDRATE { 500, 500, 25, 25 } @@ -503,7 +503,7 @@ * Default Max Acceleration (change/s) change = mm/s * (Maximum start speed for accelerated moves) * Override with M201 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_ACCELERATION { 800, 800, 700, 10000 } diff --git a/Marlin/example_configurations/makibox/Configuration.h b/Marlin/example_configurations/makibox/Configuration.h index dbe6e2e09..ea04d6101 100644 --- a/Marlin/example_configurations/makibox/Configuration.h +++ b/Marlin/example_configurations/makibox/Configuration.h @@ -477,14 +477,14 @@ /** * Default Axis Steps Per Unit (steps/mm) * Override with M92 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_AXIS_STEPS_PER_UNIT { 400, 400, 400, 163 } // default steps per unit for ***** MakiBox A6 ***** /** * Default Max Feed Rate (mm/s) * Override with M203 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_FEEDRATE { 60, 60, 20, 45 } @@ -492,7 +492,7 @@ * Default Max Acceleration (change/s) change = mm/s * (Maximum start speed for accelerated moves) * Override with M201 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_ACCELERATION { 2000, 2000, 30, 10000 } diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration.h b/Marlin/example_configurations/tvrrug/Round2/Configuration.h index 9ce54e88f..ecbca415f 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration.h @@ -464,7 +464,7 @@ /** * Default Axis Steps Per Unit (steps/mm) * Override with M92 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_AXIS_STEPS_PER_UNIT { 71.1, 71.1, 2560, 600 } // David TVRR @@ -475,7 +475,7 @@ /** * Default Max Feed Rate (mm/s) * Override with M203 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_FEEDRATE { 500, 500, 5, 45 } // David TVRR @@ -483,7 +483,7 @@ * Default Max Acceleration (change/s) change = mm/s * (Maximum start speed for accelerated moves) * Override with M201 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_ACCELERATION { 9000, 9000, 100, 10000 } diff --git a/Marlin/example_configurations/wt150/Configuration.h b/Marlin/example_configurations/wt150/Configuration.h index acf6b1155..5d221d701 100644 --- a/Marlin/example_configurations/wt150/Configuration.h +++ b/Marlin/example_configurations/wt150/Configuration.h @@ -479,14 +479,14 @@ /** * Default Axis Steps Per Unit (steps/mm) * Override with M92 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_AXIS_STEPS_PER_UNIT { 71.699959, 71.699959, 71.699959, 100.470955 } /** * Default Max Feed Rate (mm/s) * Override with M203 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_FEEDRATE { 83.333333, 83.333333, 19.5, 26.666666 } @@ -494,7 +494,7 @@ * Default Max Acceleration (change/s) change = mm/s * (Maximum start speed for accelerated moves) * Override with M201 - * X, Y, Z, E0 [, E1[, E2[, E3]]] + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ #define DEFAULT_MAX_ACCELERATION { 1200, 1200, 100, 10000 } From 6c2e6ea38e31bcd282a0d4102ca09c36bd5cef2a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 7 May 2017 01:22:45 -0500 Subject: [PATCH 020/189] Patch mfqp for use directly with MarlinDocumentation --- buildroot/share/git/mfdoc | 2 +- buildroot/share/git/mfqp | 17 +++++++++++++++-- 2 files changed, 16 insertions(+), 3 deletions(-) diff --git a/buildroot/share/git/mfdoc b/buildroot/share/git/mfdoc index 89bc5a9f1..3880c6dac 100755 --- a/buildroot/share/git/mfdoc +++ b/buildroot/share/git/mfdoc @@ -37,7 +37,7 @@ opensite() { echo "Previewing MarlinDocumentation..." # wait to open the url for about 8s -( sleep 8; opensite ) & +( sleep 45; opensite ) & bundle exec jekyll serve --watch --incremental diff --git a/buildroot/share/git/mfqp b/buildroot/share/git/mfqp index 2420f4888..67a385c2e 100755 --- a/buildroot/share/git/mfqp +++ b/buildroot/share/git/mfqp @@ -8,6 +8,10 @@ MFINFO=$(mfinfo) || exit IFS=' ' read -a INFO <<< "$MFINFO" +if [[ ${INFO[4]} == "(no" ]]; then + echo "Branch is unavailable!" ; exit 1 +fi + case "$#" in 0 ) ;; * ) echo "Usage: `basename $0`" 1>&2 ; exit 1 ;; @@ -15,5 +19,14 @@ esac git add * .travis.yml git commit -m "patch" -mfrb -git push -f + +if [[ ${INFO[3]} == ${INFO[4]} ]]; then + if [[ ${INFO[2]} == "MarlinDocumentation" ]]; then + git rebase -i HEAD~2 + else + echo "Don't alter the PR target branch."; exit 1 + fi +else + mfrb + git push -f +fi From 34b5041576ac7b36e238dbaf4604de66268818ef Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 7 May 2017 01:29:37 -0500 Subject: [PATCH 021/189] Spacing adjustment, ubl_G29 --- Marlin/ubl_G29.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 414315b2c..247ae27d6 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -389,8 +389,8 @@ } if (code_seen('P')) { - if (WITHIN(phase_value,0,1) && ubl.state.eeprom_storage_slot==-1) { - ubl.state.eeprom_storage_slot=0; + if (WITHIN(phase_value, 0, 1) && ubl.state.eeprom_storage_slot == -1) { + ubl.state.eeprom_storage_slot = 0; SERIAL_PROTOCOLLNPGM("Default storage slot 0 selected.\n"); } From 26dba44cd38a63148ddfaf8a71d6907a9b43eec8 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 7 May 2017 02:13:23 -0500 Subject: [PATCH 022/189] Patch redundant lcd settings --- Marlin/example_configurations/Hephestos/Configuration.h | 2 +- Marlin/example_configurations/K8400/Configuration.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/example_configurations/Hephestos/Configuration.h b/Marlin/example_configurations/Hephestos/Configuration.h index 2e483b1c2..8c611552a 100644 --- a/Marlin/example_configurations/Hephestos/Configuration.h +++ b/Marlin/example_configurations/Hephestos/Configuration.h @@ -1149,7 +1149,7 @@ * IMPORTANT: The U8glib library is required for Full Graphic Display! * https://github.com/olikraus/U8glib_Arduino */ -#define ULTRA_LCD // Character based +//#define ULTRA_LCD // Character based //#define DOGLCD // Full graphics display /** diff --git a/Marlin/example_configurations/K8400/Configuration.h b/Marlin/example_configurations/K8400/Configuration.h index 429f37cda..027ad29bc 100644 --- a/Marlin/example_configurations/K8400/Configuration.h +++ b/Marlin/example_configurations/K8400/Configuration.h @@ -1158,7 +1158,7 @@ * IMPORTANT: The U8glib library is required for Full Graphic Display! * https://github.com/olikraus/U8glib_Arduino */ -#define ULTRA_LCD // Character based +//#define ULTRA_LCD // Character based //#define DOGLCD // Full graphics display /** From 421dd628006fcd2009711e68622ec6119acffeeb Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 7 May 2017 19:37:57 -0500 Subject: [PATCH 023/189] Adjust spacing of "spaces" --- Marlin/ubl.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/Marlin/ubl.cpp b/Marlin/ubl.cpp index b1d31fe68..0f0c928e2 100644 --- a/Marlin/ubl.cpp +++ b/Marlin/ubl.cpp @@ -136,16 +136,16 @@ void unified_bed_leveling::display_map(const int map_type) { const bool map0 = map_type == 0; - const uint8_t spaces = 11; + constexpr uint8_t spaces = 11 * (GRID_MAX_POINTS_X - 2); if (map0) { SERIAL_PROTOCOLLNPGM("\nBed Topography Report:\n"); serial_echo_xy(0, GRID_MAX_POINTS_Y - 1); - SERIAL_ECHO_SP(spaces * (GRID_MAX_POINTS_X - 2) + 3); + SERIAL_ECHO_SP(spaces + 3); serial_echo_xy(GRID_MAX_POINTS_X - 1, GRID_MAX_POINTS_Y - 1); SERIAL_EOL; serial_echo_xy(UBL_MESH_MIN_X, UBL_MESH_MAX_Y); - SERIAL_ECHO_SP(spaces * (GRID_MAX_POINTS_X - 2)-3); + SERIAL_ECHO_SP(spaces - 3); serial_echo_xy(UBL_MESH_MAX_X, UBL_MESH_MAX_Y); SERIAL_EOL; } @@ -190,11 +190,11 @@ if (map0) { serial_echo_xy(UBL_MESH_MIN_X, UBL_MESH_MIN_Y); - SERIAL_ECHO_SP(spaces * (GRID_MAX_POINTS_X - 2) + 1); + SERIAL_ECHO_SP(spaces + 1); serial_echo_xy(UBL_MESH_MAX_X, UBL_MESH_MIN_Y); SERIAL_EOL; serial_echo_xy(0, 0); - SERIAL_ECHO_SP(spaces * (GRID_MAX_POINTS_X - 2) + 5); + SERIAL_ECHO_SP(spaces + 5); serial_echo_xy(GRID_MAX_POINTS_X - 1, 0); SERIAL_EOL; } From 56ca47ab9d3e4c3c5711995f80a50c7d5f84d7e4 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 7 May 2017 21:32:01 -0500 Subject: [PATCH 024/189] Patch configuration temp units --- Marlin/Marlin_main.cpp | 19 +++++++++++++++---- Marlin/configuration_store.cpp | 4 ++-- 2 files changed, 17 insertions(+), 6 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index e470fc88f..8a174aeb7 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -1298,19 +1298,30 @@ inline bool code_value_bool() { return !code_has_value() || code_value_byte() > #if ENABLED(TEMPERATURE_UNITS_SUPPORT) inline void set_input_temp_units(TempUnit units) { input_temp_units = units; } - float temp_abs(const float &c) { + float to_temp_units(const float &c) { switch (input_temp_units) { case TEMPUNIT_F: - return (c - 32.0) * 0.5555555556; + return c * 0.5555555556 + 32.0; case TEMPUNIT_K: - return c - 273.15; + return c + 273.15; case TEMPUNIT_C: default: return c; } } - int16_t code_value_temp_abs() { return temp_abs(code_value_float()); } + int16_t code_value_temp_abs() { + const float c = code_value_float(); + switch (input_temp_units) { + case TEMPUNIT_F: + return (int16_t)((c - 32.0) * 0.5555555556); + case TEMPUNIT_K: + return (int16_t)(c - 273.15); + case TEMPUNIT_C: + default: + return (int16_t)(c); + } + } int16_t code_value_temp_diff() { switch (input_temp_units) { diff --git a/Marlin/configuration_store.cpp b/Marlin/configuration_store.cpp index ef7e04014..99495997b 100644 --- a/Marlin/configuration_store.cpp +++ b/Marlin/configuration_store.cpp @@ -1257,8 +1257,8 @@ void MarlinSettings::reset() { CONFIG_ECHO_START; #if ENABLED(TEMPERATURE_UNITS_SUPPORT) extern TempUnit input_temp_units; - extern float temp_abs(const float &f); - #define TEMP_UNIT(N) temp_abs(N) + extern float to_temp_units(const float &f); + #define TEMP_UNIT(N) to_temp_units(N) SERIAL_ECHOPGM(" M149 "); SERIAL_CHAR(input_temp_units == TEMPUNIT_K ? 'K' : input_temp_units == TEMPUNIT_F ? 'F' : 'C'); SERIAL_ECHOPGM(" ; Units in "); From 6cb0fa412862f2e50eb542d99893c4f67a3fa8bf Mon Sep 17 00:00:00 2001 From: Brian Date: Mon, 8 May 2017 07:40:50 -0400 Subject: [PATCH 025/189] Cleanup previous implementation of new quiet probing Saves a few lines of code. --- Marlin/Marlin_main.cpp | 18 +++++------------- Marlin/temperature.cpp | 12 +++--------- 2 files changed, 8 insertions(+), 22 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 8a174aeb7..45bfac5c0 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -2058,32 +2058,24 @@ static void clean_up_after_endstop_or_probe_move() { #if ENABLED(PROBING_FANS_OFF) void fans_pause(bool p) { - if (p && fans_paused) { // If called out of order something is wrong + if (p == fans_paused) { // If called out of order something is wrong SERIAL_ERROR_START; - SERIAL_ERRORLNPGM("Fans already paused!"); + serialprintPGM(fans_paused ? PSTR("Fans already paused!") : PSTR("Fans already unpaused!")); return; } - if (!p && !fans_paused) { - SERIAL_ERROR_START; - SERIAL_ERRORLNPGM("Fans already unpaused!"); - return; - } - - if (p) { + if (p) for (uint8_t x = 0;x < FAN_COUNT;x++) { paused_fanSpeeds[x] = fanSpeeds[x]; fanSpeeds[x] = 0; } - } - else { + else for (uint8_t x = 0;x < FAN_COUNT;x++) fanSpeeds[x] = paused_fanSpeeds[x]; - } fans_paused = p; } -#endif +#endif // PROBING_FANS_OFF #if HAS_BED_PROBE diff --git a/Marlin/temperature.cpp b/Marlin/temperature.cpp index dbadd06f3..3b9454ccc 100644 --- a/Marlin/temperature.cpp +++ b/Marlin/temperature.cpp @@ -1358,15 +1358,9 @@ void Temperature::disable_all_heaters() { #if ENABLED(PROBING_HEATERS_OFF) void Temperature::pause(bool p) { - if (p && paused) { // If called out of order something is wrong + if (p == paused) { // If called out of order something is wrong SERIAL_ERROR_START; - SERIAL_ERRORLNPGM("Heaters already paused!"); - return; - } - - if (!p && !paused) { - SERIAL_ERROR_START; - SERIAL_ERRORLNPGM("Heaters already unpaused!"); + serialprintPGM(paused ? PSTR("Heaters already paused!") : PSTR("Heaters already unpaused!")); return; } @@ -1393,7 +1387,7 @@ void Temperature::disable_all_heaters() { bool Temperature::ispaused() { return paused; } -#endif +#endif // PROBING_HEATERS_OFF #if ENABLED(HEATER_0_USES_MAX6675) From 3279337f47682c6488f7fb1680f53cc22c93aa08 Mon Sep 17 00:00:00 2001 From: Thomas Moore Date: Mon, 8 May 2017 15:21:01 +0000 Subject: [PATCH 026/189] Move BLTouch LCD menu from Main to Main/Control --- Marlin/ultralcd.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 2ba3ee5bd..83cd04527 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -815,10 +815,6 @@ void kill_screen(const char* lcd_msg) { MENU_ITEM(function, MSG_LIGHTS_ON, toggle_case_light); #endif - #if ENABLED(BLTOUCH) - MENU_ITEM(submenu, MSG_BLTOUCH, bltouch_menu); - #endif - if (planner.movesplanned() || IS_SD_PRINTING) { MENU_ITEM(submenu, MSG_TUNE, lcd_tune_menu); } @@ -2152,6 +2148,10 @@ void kill_screen(const char* lcd_msg) { MENU_ITEM(submenu, MSG_DRIVE_STRENGTH, lcd_dac_menu); #endif + #if ENABLED(BLTOUCH) + MENU_ITEM(submenu, MSG_BLTOUCH, bltouch_menu); + #endif + #if ENABLED(EEPROM_SETTINGS) MENU_ITEM(function, MSG_STORE_EEPROM, lcd_store_settings); MENU_ITEM(function, MSG_LOAD_EEPROM, lcd_load_settings); From a20d0794e6eb3737c5f6736620266f87d4585224 Mon Sep 17 00:00:00 2001 From: Thomas Moore Date: Mon, 8 May 2017 16:28:44 +0000 Subject: [PATCH 027/189] Automatically define Z_MIN_PROBE_ENDSTOP_INVERTING for BLTouch --- Marlin/Conditionals_LCD.h | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/Marlin/Conditionals_LCD.h b/Marlin/Conditionals_LCD.h index 576139045..453468953 100644 --- a/Marlin/Conditionals_LCD.h +++ b/Marlin/Conditionals_LCD.h @@ -360,8 +360,12 @@ #if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) #undef Z_MIN_ENDSTOP_INVERTING #define Z_MIN_ENDSTOP_INVERTING false + #undef Z_MIN_PROBE_ENDSTOP_INVERTING + #define Z_MIN_PROBE_ENDSTOP_INVERTING false #define TEST_BLTOUCH() _TEST_BLTOUCH(Z_MIN) #else + #undef Z_MIN_PROBE_ENDSTOP_INVERTING + #define Z_MIN_PROBE_ENDSTOP_INVERTING false #define TEST_BLTOUCH() _TEST_BLTOUCH(Z_MIN_PROBE) #endif #endif From a1e04942a2c8e10dca3e6e017276cd24eea932d9 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 20 Apr 2017 14:04:26 -0500 Subject: [PATCH 028/189] Cleanup to software PWM variables --- Marlin/Marlin_main.cpp | 2 +- Marlin/planner.cpp | 6 +- Marlin/temperature.cpp | 150 ++++++++++++++++++++--------------------- Marlin/temperature.h | 14 ++-- 4 files changed, 82 insertions(+), 90 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 45bfac5c0..3c9eabab2 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -11516,7 +11516,7 @@ void prepare_move_to_destination() { const millis_t ms = millis(); if (ELAPSED(ms, nextMotorCheck)) { nextMotorCheck = ms + 2500UL; // Not a time critical function, so only check every 2.5s - if (X_ENABLE_READ == X_ENABLE_ON || Y_ENABLE_READ == Y_ENABLE_ON || Z_ENABLE_READ == Z_ENABLE_ON || thermalManager.soft_pwm_bed > 0 + if (X_ENABLE_READ == X_ENABLE_ON || Y_ENABLE_READ == Y_ENABLE_ON || Z_ENABLE_READ == Z_ENABLE_ON || thermalManager.soft_pwm_amount_bed > 0 || E0_ENABLE_READ == E_ENABLE_ON // If any of the drivers are enabled... #if E_STEPPERS > 1 || E1_ENABLE_READ == E_ENABLE_ON diff --git a/Marlin/planner.cpp b/Marlin/planner.cpp index 2a0bfe2a7..f95d8ab6e 100644 --- a/Marlin/planner.cpp +++ b/Marlin/planner.cpp @@ -491,13 +491,13 @@ void Planner::check_axes_activity() { #if ENABLED(FAN_SOFT_PWM) #if HAS_FAN0 - thermalManager.fanSpeedSoftPwm[0] = CALC_FAN_SPEED(0); + thermalManager.soft_pwm_amount_fan[0] = CALC_FAN_SPEED(0); #endif #if HAS_FAN1 - thermalManager.fanSpeedSoftPwm[1] = CALC_FAN_SPEED(1); + thermalManager.soft_pwm_amount_fan[1] = CALC_FAN_SPEED(1); #endif #if HAS_FAN2 - thermalManager.fanSpeedSoftPwm[2] = CALC_FAN_SPEED(2); + thermalManager.soft_pwm_amount_fan[2] = CALC_FAN_SPEED(2); #endif #else #if HAS_FAN0 diff --git a/Marlin/temperature.cpp b/Marlin/temperature.cpp index 3b9454ccc..e39b1fde1 100644 --- a/Marlin/temperature.cpp +++ b/Marlin/temperature.cpp @@ -74,12 +74,6 @@ int16_t Temperature::current_temperature_raw[HOTENDS] = { 0 }, float Temperature::redundant_temperature = 0.0; #endif -uint8_t Temperature::soft_pwm_bed; - -#if ENABLED(FAN_SOFT_PWM) - uint8_t Temperature::fanSpeedSoftPwm[FAN_COUNT]; -#endif - #if ENABLED(PIDTEMP) #if ENABLED(PID_PARAMS_PER_HOTEND) && HOTENDS > 1 float Temperature::Kp[HOTENDS] = ARRAY_BY_HOTENDS1(DEFAULT_Kp), @@ -194,10 +188,12 @@ int16_t Temperature::minttemp_raw[HOTENDS] = ARRAY_BY_HOTENDS(HEATER_0_RAW_LO_TE millis_t Temperature::next_auto_fan_check_ms = 0; #endif -uint8_t Temperature::soft_pwm[HOTENDS]; +uint8_t Temperature::soft_pwm_amount[HOTENDS], + Temperature::soft_pwm_amount_bed; #if ENABLED(FAN_SOFT_PWM) - uint8_t Temperature::soft_pwm_fan[FAN_COUNT]; + uint8_t Temperature::soft_pwm_amount_fan[FAN_COUNT], + Temperature::soft_pwm_count_fan[FAN_COUNT]; #endif #if ENABLED(FILAMENT_WIDTH_SENSOR) @@ -206,7 +202,7 @@ uint8_t Temperature::soft_pwm[HOTENDS]; #if ENABLED(PROBING_HEATERS_OFF) bool Temperature::paused; - int16_t Temperature::paused_hotend_temps[HOTENDS]; + int16_t Temperature::paused_hotend_temp[HOTENDS]; #if HAS_TEMP_BED int16_t Temperature::paused_bed_temp; #endif @@ -254,13 +250,13 @@ uint8_t Temperature::soft_pwm[HOTENDS]; #if HAS_PID_FOR_BOTH if (hotend < 0) - soft_pwm_bed = bias = d = (MAX_BED_POWER) >> 1; + soft_pwm_amount_bed = bias = d = (MAX_BED_POWER) >> 1; else - soft_pwm[hotend] = bias = d = (PID_MAX) >> 1; + soft_pwm_amount[hotend] = bias = d = (PID_MAX) >> 1; #elif ENABLED(PIDTEMP) - soft_pwm[hotend] = bias = d = (PID_MAX) >> 1; + soft_pwm_amount[hotend] = bias = d = (PID_MAX) >> 1; #else - soft_pwm_bed = bias = d = (MAX_BED_POWER) >> 1; + soft_pwm_amount_bed = bias = d = (MAX_BED_POWER) >> 1; #endif wait_for_heatup = true; @@ -298,13 +294,13 @@ uint8_t Temperature::soft_pwm[HOTENDS]; heating = false; #if HAS_PID_FOR_BOTH if (hotend < 0) - soft_pwm_bed = (bias - d) >> 1; + soft_pwm_amount_bed = (bias - d) >> 1; else - soft_pwm[hotend] = (bias - d) >> 1; + soft_pwm_amount[hotend] = (bias - d) >> 1; #elif ENABLED(PIDTEMP) - soft_pwm[hotend] = (bias - d) >> 1; + soft_pwm_amount[hotend] = (bias - d) >> 1; #elif ENABLED(PIDTEMPBED) - soft_pwm_bed = (bias - d) >> 1; + soft_pwm_amount_bed = (bias - d) >> 1; #endif t1 = ms; t_high = t1 - t2; @@ -367,13 +363,13 @@ uint8_t Temperature::soft_pwm[HOTENDS]; } #if HAS_PID_FOR_BOTH if (hotend < 0) - soft_pwm_bed = (bias + d) >> 1; + soft_pwm_amount_bed = (bias + d) >> 1; else - soft_pwm[hotend] = (bias + d) >> 1; + soft_pwm_amount[hotend] = (bias + d) >> 1; #elif ENABLED(PIDTEMP) - soft_pwm[hotend] = (bias + d) >> 1; + soft_pwm_amount[hotend] = (bias + d) >> 1; #else - soft_pwm_bed = (bias + d) >> 1; + soft_pwm_amount_bed = (bias + d) >> 1; #endif cycles++; min = temp; @@ -466,7 +462,7 @@ void Temperature::updatePID() { } int Temperature::getHeaterPower(int heater) { - return heater < 0 ? soft_pwm_bed : soft_pwm[heater]; + return heater < 0 ? soft_pwm_amount_bed : soft_pwm_amount[heater]; } #if HAS_AUTO_FAN @@ -717,7 +713,7 @@ void Temperature::manage_heater() { float pid_output = get_pid_output(e); // Check if temperature is within the correct range - soft_pwm[e] = (current_temperature[e] > minttemp[e] || is_preheating(e)) && current_temperature[e] < maxttemp[e] ? (int)pid_output >> 1 : 0; + soft_pwm_amount[e] = (current_temperature[e] > minttemp[e] || is_preheating(e)) && current_temperature[e] < maxttemp[e] ? (int)pid_output >> 1 : 0; // Check if the temperature is failing to increase #if WATCH_HOTENDS @@ -798,27 +794,27 @@ void Temperature::manage_heater() { #if ENABLED(PIDTEMPBED) float pid_output = get_pid_output_bed(); - soft_pwm_bed = WITHIN(current_temperature_bed, BED_MINTEMP, BED_MAXTEMP) ? (int)pid_output >> 1 : 0; + soft_pwm_amount_bed = WITHIN(current_temperature_bed, BED_MINTEMP, BED_MAXTEMP) ? (int)pid_output >> 1 : 0; #elif ENABLED(BED_LIMIT_SWITCHING) // Check if temperature is within the correct band if (WITHIN(current_temperature_bed, BED_MINTEMP, BED_MAXTEMP)) { if (current_temperature_bed >= target_temperature_bed + BED_HYSTERESIS) - soft_pwm_bed = 0; + soft_pwm_amount_bed = 0; else if (current_temperature_bed <= target_temperature_bed - (BED_HYSTERESIS)) - soft_pwm_bed = MAX_BED_POWER >> 1; + soft_pwm_amount_bed = MAX_BED_POWER >> 1; } else { - soft_pwm_bed = 0; + soft_pwm_amount_bed = 0; WRITE_HEATER_BED(LOW); } #else // !PIDTEMPBED && !BED_LIMIT_SWITCHING // Check if temperature is within the correct range if (WITHIN(current_temperature_bed, BED_MINTEMP, BED_MAXTEMP)) { - soft_pwm_bed = current_temperature_bed < target_temperature_bed ? MAX_BED_POWER >> 1 : 0; + soft_pwm_amount_bed = current_temperature_bed < target_temperature_bed ? MAX_BED_POWER >> 1 : 0; } else { - soft_pwm_bed = 0; + soft_pwm_amount_bed = 0; WRITE_HEATER_BED(LOW); } #endif @@ -1205,7 +1201,7 @@ void Temperature::init() { #if ENABLED(PROBING_HEATERS_OFF) paused = false; - ZERO(paused_hotend_temps); + ZERO(paused_hotend_temp); #if HAS_TEMP_BED paused_bed_temp = 0; #endif @@ -1316,7 +1312,7 @@ void Temperature::disable_all_heaters() { // Unpause and reset everything #if ENABLED(PROBING_HEATERS_OFF) paused = false; - ZERO(paused_hotend_temps); + ZERO(paused_hotend_temp); #if HAS_TEMP_BED paused_bed_temp = 0; #endif @@ -1327,7 +1323,7 @@ void Temperature::disable_all_heaters() { #define DISABLE_HEATER(NR) { \ setTargetHotend(0, NR); \ - soft_pwm[NR] = 0; \ + soft_pwm_amount[NR] = 0; \ WRITE_HEATER_ ##NR (LOW); \ } @@ -1349,7 +1345,7 @@ void Temperature::disable_all_heaters() { #if HAS_TEMP_BED target_temperature_bed = 0; - soft_pwm_bed = 0; + soft_pwm_amount_bed = 0; #if HAS_HEATER_BED WRITE_HEATER_BED(LOW); #endif @@ -1366,7 +1362,7 @@ void Temperature::disable_all_heaters() { if (p) { HOTEND_LOOP() { - paused_hotend_temps[e] = degTargetHotend(e); + paused_hotend_temp[e] = degTargetHotend(e); setTargetHotend(0, e); } #if HAS_TEMP_BED @@ -1375,7 +1371,7 @@ void Temperature::disable_all_heaters() { #endif } else { - HOTEND_LOOP() setTargetHotend(paused_hotend_temps[e], e); + HOTEND_LOOP() setTargetHotend(paused_hotend_temp[e], e); #if HAS_TEMP_BED setTargetBed(paused_bed_temp); #endif @@ -1613,11 +1609,11 @@ void Temperature::isr() { #if ENABLED(SLOW_PWM_HEATERS) static uint8_t slow_pwm_count = 0; #define ISR_STATICS(n) \ - static uint8_t soft_pwm_ ## n; \ - static uint8_t state_heater_ ## n = 0; \ - static uint8_t state_timer_heater_ ## n = 0 + static uint8_t soft_pwm_count_ ## n, \ + state_heater_ ## n = 0, \ + state_timer_heater_ ## n = 0 #else - #define ISR_STATICS(n) static uint8_t soft_pwm_ ## n = 0 + #define ISR_STATICS(n) static uint8_t soft_pwm_count_ ## n = 0 #endif // Statics per heater @@ -1656,73 +1652,73 @@ void Temperature::isr() { */ if (pwm_count_tmp >= 127) { pwm_count_tmp -= 127; - soft_pwm_0 = (soft_pwm_0 & pwm_mask) + soft_pwm[0]; - WRITE_HEATER_0(soft_pwm_0 > pwm_mask ? HIGH : LOW); + soft_pwm_count_0 = (soft_pwm_count_0 & pwm_mask) + soft_pwm_amount[0]; + WRITE_HEATER_0(soft_pwm_count_0 > pwm_mask ? HIGH : LOW); #if HOTENDS > 1 - soft_pwm_1 = (soft_pwm_1 & pwm_mask) + soft_pwm[1]; - WRITE_HEATER_1(soft_pwm_1 > pwm_mask ? HIGH : LOW); + soft_pwm_count_1 = (soft_pwm_count_1 & pwm_mask) + soft_pwm_amount[1]; + WRITE_HEATER_1(soft_pwm_count_1 > pwm_mask ? HIGH : LOW); #if HOTENDS > 2 - soft_pwm_2 = (soft_pwm_2 & pwm_mask) + soft_pwm[2]; - WRITE_HEATER_2(soft_pwm_2 > pwm_mask ? HIGH : LOW); + soft_pwm_count_2 = (soft_pwm_count_2 & pwm_mask) + soft_pwm_amount[2]; + WRITE_HEATER_2(soft_pwm_count_2 > pwm_mask ? HIGH : LOW); #if HOTENDS > 3 - soft_pwm_3 = (soft_pwm_3 & pwm_mask) + soft_pwm[3]; - WRITE_HEATER_3(soft_pwm_3 > pwm_mask ? HIGH : LOW); + soft_pwm_count_3 = (soft_pwm_count_3 & pwm_mask) + soft_pwm_amount[3]; + WRITE_HEATER_3(soft_pwm_count_3 > pwm_mask ? HIGH : LOW); #if HOTENDS > 4 - soft_pwm_4 = (soft_pwm_4 & pwm_mask) + soft_pwm[4]; - WRITE_HEATER_4(soft_pwm_4 > pwm_mask ? HIGH : LOW); + soft_pwm_count_4 = (soft_pwm_count_4 & pwm_mask) + soft_pwm_amount[4]; + WRITE_HEATER_4(soft_pwm_count_4 > pwm_mask ? HIGH : LOW); #endif // HOTENDS > 4 #endif // HOTENDS > 3 #endif // HOTENDS > 2 #endif // HOTENDS > 1 #if HAS_HEATER_BED - soft_pwm_BED = (soft_pwm_BED & pwm_mask) + soft_pwm_bed; - WRITE_HEATER_BED(soft_pwm_BED > pwm_mask ? HIGH : LOW); + soft_pwm_count_BED = (soft_pwm_count_BED & pwm_mask) + soft_pwm_amount_bed; + WRITE_HEATER_BED(soft_pwm_count_BED > pwm_mask ? HIGH : LOW); #endif #if ENABLED(FAN_SOFT_PWM) #if HAS_FAN0 - soft_pwm_fan[0] = (soft_pwm_fan[0] & pwm_mask) + fanSpeedSoftPwm[0] >> 1; - WRITE_FAN(soft_pwm_fan[0] > pwm_mask ? HIGH : LOW); + soft_pwm_count_fan[0] = (soft_pwm_count_fan[0] & pwm_mask) + soft_pwm_amount_fan[0] >> 1; + WRITE_FAN(soft_pwm_count_fan[0] > pwm_mask ? HIGH : LOW); #endif #if HAS_FAN1 - soft_pwm_fan[1] = (soft_pwm_fan[1] & pwm_mask) + fanSpeedSoftPwm[1] >> 1; - WRITE_FAN1(soft_pwm_fan[1] > pwm_mask ? HIGH : LOW); + soft_pwm_count_fan[1] = (soft_pwm_count_fan[1] & pwm_mask) + soft_pwm_amount_fan[1] >> 1; + WRITE_FAN1(soft_pwm_count_fan[1] > pwm_mask ? HIGH : LOW); #endif #if HAS_FAN2 - soft_pwm_fan[2] = (soft_pwm_fan[2] & pwm_mask) + fanSpeedSoftPwm[2] >> 1; - WRITE_FAN2(soft_pwm_fan[2] > pwm_mask ? HIGH : LOW); + soft_pwm_count_fan[2] = (soft_pwm_count_fan[2] & pwm_mask) + soft_pwm_amount_fan[2] >> 1; + WRITE_FAN2(soft_pwm_count_fan[2] > pwm_mask ? HIGH : LOW); #endif #endif } else { - if (soft_pwm_0 <= pwm_count_tmp) WRITE_HEATER_0(0); + if (soft_pwm_count_0 <= pwm_count_tmp) WRITE_HEATER_0(0); #if HOTENDS > 1 - if (soft_pwm_1 <= pwm_count_tmp) WRITE_HEATER_1(0); + if (soft_pwm_count_1 <= pwm_count_tmp) WRITE_HEATER_1(0); #if HOTENDS > 2 - if (soft_pwm_2 <= pwm_count_tmp) WRITE_HEATER_2(0); + if (soft_pwm_count_2 <= pwm_count_tmp) WRITE_HEATER_2(0); #if HOTENDS > 3 - if (soft_pwm_3 <= pwm_count_tmp) WRITE_HEATER_3(0); + if (soft_pwm_count_3 <= pwm_count_tmp) WRITE_HEATER_3(0); #if HOTENDS > 4 - if (soft_pwm_4 <= pwm_count_tmp) WRITE_HEATER_4(0); + if (soft_pwm_count_4 <= pwm_count_tmp) WRITE_HEATER_4(0); #endif // HOTENDS > 4 #endif // HOTENDS > 3 #endif // HOTENDS > 2 #endif // HOTENDS > 1 #if HAS_HEATER_BED - if (soft_pwm_BED <= pwm_count_tmp) WRITE_HEATER_BED(0); + if (soft_pwm_count_BED <= pwm_count_tmp) WRITE_HEATER_BED(0); #endif #if ENABLED(FAN_SOFT_PWM) #if HAS_FAN0 - if (soft_pwm_fan[0] <= pwm_count_tmp) WRITE_FAN(0); + if (soft_pwm_count_fan[0] <= pwm_count_tmp) WRITE_FAN(0); #endif #if HAS_FAN1 - if (soft_pwm_fan[1] <= pwm_count_tmp) WRITE_FAN1(0); + if (soft_pwm_count_fan[1] <= pwm_count_tmp) WRITE_FAN1(0); #endif #if HAS_FAN2 - if (soft_pwm_fan[2] <= pwm_count_tmp) WRITE_FAN2(0); + if (soft_pwm_count_fan[2] <= pwm_count_tmp) WRITE_FAN2(0); #endif #endif } @@ -1765,7 +1761,7 @@ void Temperature::isr() { WRITE_HEATER_ ##NR(0); \ } \ } - #define SLOW_PWM_ROUTINE(n) _SLOW_PWM_ROUTINE(n, soft_pwm[n]) + #define SLOW_PWM_ROUTINE(n) _SLOW_PWM_ROUTINE(n, soft_pwm_amount[n]) #define PWM_OFF_ROUTINE(NR) \ if (soft_pwm_ ##NR < slow_pwm_count) { \ @@ -1792,7 +1788,7 @@ void Temperature::isr() { #endif // HOTENDS > 2 #endif // HOTENDS > 1 #if HAS_HEATER_BED - _SLOW_PWM_ROUTINE(BED, soft_pwm_bed); // BED + _SLOW_PWM_ROUTINE(BED, soft_pwm_amount_bed); // BED #endif } // slow_pwm_count == 0 @@ -1818,26 +1814,26 @@ void Temperature::isr() { if (pwm_count_tmp >= 127) { pwm_count_tmp = 0; #if HAS_FAN0 - soft_pwm_fan[0] = fanSpeedSoftPwm[0] >> 1; - WRITE_FAN(soft_pwm_fan[0] > 0 ? HIGH : LOW); + soft_pwm_count_fan[0] = soft_pwm_amount_fan[0] >> 1; + WRITE_FAN(soft_pwm_count_fan[0] > 0 ? HIGH : LOW); #endif #if HAS_FAN1 - soft_pwm_fan[1] = fanSpeedSoftPwm[1] >> 1; - WRITE_FAN1(soft_pwm_fan[1] > 0 ? HIGH : LOW); + soft_pwm_count_fan[1] = soft_pwm_amount_fan[1] >> 1; + WRITE_FAN1(soft_pwm_count_fan[1] > 0 ? HIGH : LOW); #endif #if HAS_FAN2 - soft_pwm_fan[2] = fanSpeedSoftPwm[2] >> 1; - WRITE_FAN2(soft_pwm_fan[2] > 0 ? HIGH : LOW); + soft_pwm_count_fan[2] = soft_pwm_amount_fan[2] >> 1; + WRITE_FAN2(soft_pwm_count_fan[2] > 0 ? HIGH : LOW); #endif } #if HAS_FAN0 - if (soft_pwm_fan[0] <= pwm_count_tmp) WRITE_FAN(0); + if (soft_pwm_count_fan[0] <= pwm_count_tmp) WRITE_FAN(0); #endif #if HAS_FAN1 - if (soft_pwm_fan[1] <= pwm_count_tmp) WRITE_FAN1(0); + if (soft_pwm_count_fan[1] <= pwm_count_tmp) WRITE_FAN1(0); #endif #if HAS_FAN2 - if (soft_pwm_fan[2] <= pwm_count_tmp) WRITE_FAN2(0); + if (soft_pwm_count_fan[2] <= pwm_count_tmp) WRITE_FAN2(0); #endif #endif // FAN_SOFT_PWM diff --git a/Marlin/temperature.h b/Marlin/temperature.h index 7fc9926c3..073341895 100644 --- a/Marlin/temperature.h +++ b/Marlin/temperature.h @@ -109,10 +109,12 @@ class Temperature { static float redundant_temperature; #endif - static uint8_t soft_pwm_bed; + static uint8_t soft_pwm_amount[HOTENDS], + soft_pwm_amount_bed; #if ENABLED(FAN_SOFT_PWM) - static uint8_t fanSpeedSoftPwm[FAN_COUNT]; + static uint8_t soft_pwm_amount_fan[FAN_COUNT], + soft_pwm_count_fan[FAN_COUNT]; #endif #if ENABLED(PIDTEMP) || ENABLED(PIDTEMPBED) @@ -249,19 +251,13 @@ class Temperature { static millis_t next_auto_fan_check_ms; #endif - static uint8_t soft_pwm[HOTENDS]; - - #if ENABLED(FAN_SOFT_PWM) - static uint8_t soft_pwm_fan[FAN_COUNT]; - #endif - #if ENABLED(FILAMENT_WIDTH_SENSOR) static int current_raw_filwidth; //Holds measured filament diameter - one extruder only #endif #if ENABLED(PROBING_HEATERS_OFF) static bool paused; - static int16_t paused_hotend_temps[HOTENDS]; + static int16_t paused_hotend_temp[HOTENDS]; #if HAS_TEMP_BED static int16_t paused_bed_temp; From a6dafb058eba43588de40738292bc5d9da0d26ad Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 8 May 2017 13:58:09 -0500 Subject: [PATCH 029/189] Small reduction in error code size --- Marlin/Marlin_main.cpp | 4 +++- Marlin/temperature.cpp | 4 +++- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 3c9eabab2..f55d62be2 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -2060,7 +2060,9 @@ static void clean_up_after_endstop_or_probe_move() { void fans_pause(bool p) { if (p == fans_paused) { // If called out of order something is wrong SERIAL_ERROR_START; - serialprintPGM(fans_paused ? PSTR("Fans already paused!") : PSTR("Fans already unpaused!")); + SERIAL_ERRORPGM("Fans already "); + if (!fans_paused) SERIAL_ERRORPGM("un"); + SERIAL_ERRORLNPGM("paused!"); return; } diff --git a/Marlin/temperature.cpp b/Marlin/temperature.cpp index e39b1fde1..074b9ce13 100644 --- a/Marlin/temperature.cpp +++ b/Marlin/temperature.cpp @@ -1356,7 +1356,9 @@ void Temperature::disable_all_heaters() { void Temperature::pause(bool p) { if (p == paused) { // If called out of order something is wrong SERIAL_ERROR_START; - serialprintPGM(paused ? PSTR("Heaters already paused!") : PSTR("Heaters already unpaused!")); + SERIAL_ERRORPGM("Heaters already "); + if (!paused) SERIAL_ERRORPGM("un"); + SERIAL_ERRORLNPGM("paused!"); return; } From dca48f0e63d9b5ce7ee40799517cc43a1f94e269 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 8 May 2017 14:14:11 -0500 Subject: [PATCH 030/189] Move platformio.ini back to Marlin folder - it works there --- platformio.ini => Marlin/platformio.ini | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename platformio.ini => Marlin/platformio.ini (100%) diff --git a/platformio.ini b/Marlin/platformio.ini similarity index 100% rename from platformio.ini rename to Marlin/platformio.ini From 71396f77d3c6a65a18d4b6bf4ef29dc077d83100 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 8 May 2017 14:09:37 -0500 Subject: [PATCH 031/189] Cleanups following recent commits --- Marlin/Conditionals_post.h | 2 +- Marlin/Marlin_main.cpp | 43 +++++++++++++++--------------------- Marlin/temperature.cpp | 45 +++++++++++++++----------------------- Marlin/temperature.h | 3 +-- Marlin/ubl_G29.cpp | 2 +- Marlin/ubl_motion.cpp | 2 +- 6 files changed, 40 insertions(+), 57 deletions(-) diff --git a/Marlin/Conditionals_post.h b/Marlin/Conditionals_post.h index 0a5e1820c..3edc8dfe8 100644 --- a/Marlin/Conditionals_post.h +++ b/Marlin/Conditionals_post.h @@ -649,7 +649,7 @@ /** * Heater & Fan Pausing */ - #if ENABLED(PROBING_FANS_OFF) && FAN_COUNT == 0 + #if FAN_COUNT == 0 #undef PROBING_FANS_OFF #endif #define QUIET_PROBING (ENABLED(PROBING_HEATERS_OFF) || ENABLED(PROBING_FANS_OFF)) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index f55d62be2..482d0f257 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -2057,26 +2057,21 @@ static void clean_up_after_endstop_or_probe_move() { #endif #if ENABLED(PROBING_FANS_OFF) - void fans_pause(bool p) { - if (p == fans_paused) { // If called out of order something is wrong - SERIAL_ERROR_START; - SERIAL_ERRORPGM("Fans already "); - if (!fans_paused) SERIAL_ERRORPGM("un"); - SERIAL_ERRORLNPGM("paused!"); - return; - } - if (p) - for (uint8_t x = 0;x < FAN_COUNT;x++) { - paused_fanSpeeds[x] = fanSpeeds[x]; - fanSpeeds[x] = 0; - } - else - for (uint8_t x = 0;x < FAN_COUNT;x++) - fanSpeeds[x] = paused_fanSpeeds[x]; - - fans_paused = p; + void fans_pause(const bool p) { + if (p != fans_paused) { + fans_paused = p; + if (p) + for (uint8_t x = 0; x < FAN_COUNT; x++) { + paused_fanSpeeds[x] = fanSpeeds[x]; + fanSpeeds[x] = 0; + } + else + for (uint8_t x = 0; x < FAN_COUNT; x++) + fanSpeeds[x] = paused_fanSpeeds[x]; + } } + #endif // PROBING_FANS_OFF #if HAS_BED_PROBE @@ -2091,18 +2086,16 @@ static void clean_up_after_endstop_or_probe_move() { #endif #if QUIET_PROBING - void probing_pause(bool pause) { + void probing_pause(const bool p) { #if ENABLED(PROBING_HEATERS_OFF) - thermalManager.pause(pause); + thermalManager.pause(p); #endif - #if ENABLED(PROBING_FANS_OFF) - fans_pause(pause); + fans_pause(p); #endif - - if(pause) safe_delay(25); + if (p) safe_delay(25); } - #endif + #endif // QUIET_PROBING #if ENABLED(BLTOUCH) diff --git a/Marlin/temperature.cpp b/Marlin/temperature.cpp index 074b9ce13..6021d899a 100644 --- a/Marlin/temperature.cpp +++ b/Marlin/temperature.cpp @@ -1353,38 +1353,29 @@ void Temperature::disable_all_heaters() { } #if ENABLED(PROBING_HEATERS_OFF) - void Temperature::pause(bool p) { - if (p == paused) { // If called out of order something is wrong - SERIAL_ERROR_START; - SERIAL_ERRORPGM("Heaters already "); - if (!paused) SERIAL_ERRORPGM("un"); - SERIAL_ERRORLNPGM("paused!"); - return; - } - if (p) { - HOTEND_LOOP() { - paused_hotend_temp[e] = degTargetHotend(e); - setTargetHotend(0, e); + void Temperature::pause(const bool p) { + if (p != paused) { + paused = p; + if (p) { + HOTEND_LOOP() { + paused_hotend_temp[e] = degTargetHotend(e); + setTargetHotend(0, e); + } + #if HAS_TEMP_BED + paused_bed_temp = degTargetBed(); + setTargetBed(0); + #endif + } + else { + HOTEND_LOOP() setTargetHotend(paused_hotend_temp[e], e); + #if HAS_TEMP_BED + setTargetBed(paused_bed_temp); + #endif } - #if HAS_TEMP_BED - paused_bed_temp = degTargetBed(); - setTargetBed(0); - #endif - } - else { - HOTEND_LOOP() setTargetHotend(paused_hotend_temp[e], e); - #if HAS_TEMP_BED - setTargetBed(paused_bed_temp); - #endif } - - paused = p; } - bool Temperature::ispaused() { - return paused; - } #endif // PROBING_HEATERS_OFF #if ENABLED(HEATER_0_USES_MAX6675) diff --git a/Marlin/temperature.h b/Marlin/temperature.h index 073341895..e8632311d 100644 --- a/Marlin/temperature.h +++ b/Marlin/temperature.h @@ -458,8 +458,7 @@ class Temperature { #endif // BABYSTEPPING #if ENABLED(PROBING_HEATERS_OFF) - static void pause(bool p); - static bool ispaused(); + static void pause(const bool p); #endif private: diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 247ae27d6..7a174f702 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -1006,7 +1006,7 @@ if (!ubl.state.active) SERIAL_PROTOCOLPGM("de"); SERIAL_PROTOCOLLNPGM("activated.\n"); } - + bool g29_parameter_parsing() { bool err_flag = false; diff --git a/Marlin/ubl_motion.cpp b/Marlin/ubl_motion.cpp index a6065dab5..5fbf141ab 100644 --- a/Marlin/ubl_motion.cpp +++ b/Marlin/ubl_motion.cpp @@ -225,7 +225,7 @@ const float e_normalized_dist = e_position / on_axis_distance, z_normalized_dist = z_position / on_axis_distance; - int current_xi = cell_start_xi, + int current_xi = cell_start_xi, current_yi = cell_start_yi; const float m = dy / dx, From f04d1096d4ed70b0da01117956c3b550cdaaf735 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 8 May 2017 14:00:38 -0500 Subject: [PATCH 032/189] Link to users in README.md --- README.md | 58 +++++++++++++++++++++++++++---------------------------- 1 file changed, 29 insertions(+), 29 deletions(-) diff --git a/README.md b/README.md index 393cb20bd..730a0bdd6 100644 --- a/README.md +++ b/README.md @@ -113,37 +113,37 @@ Proposed patches should be submitted as a Pull Request against this branch ([bug ## Credits The current Marlin dev team consists of: - - Roxanne Neufeld [@Roxy-3D] - English - - Scott Lahteine [@thinkyhead] - English - - Bob Kuhn [@Bob-the-Kuhn] - English - - Andreas Hardtung [@AnHardt] - Deutsch, English - - Nico Tonnhofer [@Wurstnase] - Deutsch, English - - Jochen Groppe [@CONSULitAS] - Deutsch, English - - João Brazio [@jbrazio] - Portuguese, English - - Bo Hermannsen [@boelle] - Danish, English - - Bob Cousins [@bobc] - English - - [@maverikou] - - Chris Palmer [@nophead] - - [@paclema] - - Erik van der Zalm [@ErikZalm] - - David Braam [@daid] - - Bernhard Kubicek [@bkubicek] + - Roxanne Neufeld [[@Roxy-3D](https://github.com/Roxy-3D)] - English + - Scott Lahteine [[@thinkyhead](https://github.com/thinkyhead)] - English + - Bob Kuhn [[@Bob-the-Kuhn](https://github.com/Bob-the-Kuhn)] - English + - Andreas Hardtung [[@AnHardt](https://github.com/AnHardt)] - Deutsch, English + - Nico Tonnhofer [[@Wurstnase](https://github.com/Wurstnase)] - Deutsch, English + - Jochen Groppe [[@CONSULitAS](https://github.com/CONSULitAS)] - Deutsch, English + - João Brazio [[@jbrazio](https://github.com/jbrazio)] - Portuguese, English + - Bo Hermannsen [[@boelle](https://github.com/boelle)] - Danish, English + - Bob Cousins [[@bobc](https://github.com/bobc)] - English + - [[@maverikou](https://github.com/maverikou)] + - Chris Palmer [[@nophead](https://github.com/nophead)] + - [[@paclema](https://github.com/paclema)] + - Erik van der Zalm [[@ErikZalm](https://github.com/ErikZalm)] + - David Braam [[@daid](https://github.com/daid)] + - Bernhard Kubicek [[@bkubicek](https://github.com/bkubicek)] More features have been added by: - - Alberto Cotronei [@MagoKimbra] - English, Italian - - Thomas Moore [@tcm0116] - - Ernesto Martinez [@emartinez167] - - Petr Zahradnik [@clexpert] - - Kai [@Kaibob2] - - Edward Patel [@epatel] - - F. Malpartida [@fmalpartida] - English, Spanish - - [@esenapaj] - English, Japanese - - [@benlye] - - [@Tannoo] - - [@teemuatlut] - - [@bgort] - - [@LVD-AC] - - [@paulusjacobus] + - Alberto Cotronei [[@MagoKimbra](https://github.com/MagoKimbra)] - English, Italian + - Thomas Moore [[@tcm0116](https://github.com/tcm0116)] + - Ernesto Martinez [[@emartinez167](https://github.com/emartinez167)] + - Petr Zahradnik [[@clexpert](https://github.com/clexpert)] + - Kai [[@Kaibob2](https://github.com/Kaibob2)] + - Edward Patel [[@epatel](https://github.com/epatel)] + - F. Malpartida [[@fmalpartida](https://github.com/fmalpartida)] - English, Spanish + - [[@esenapaj](https://github.com/esenapaj)] - English, Japanese + - [[@benlye](https://github.com/benlye)] + - [[@Tannoo](https://github.com/Tannoo)] + - [[@teemuatlut](https://github.com/teemuatlut)] + - [[@bgort](https://github.com/bgort)] + - [[@LVD-AC](https://github.com/LVD-AC)] + - [[@paulusjacobus](https://github.com/paulusjacobus)] - ...and many others ## License From 911a87e006bd79a6b493be7c674d5c20979d20ab Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 8 May 2017 14:41:03 -0500 Subject: [PATCH 033/189] Disable SCARA feedrate scaling by default --- Marlin/Marlin_main.cpp | 6 +++--- Marlin/example_configurations/SCARA/Configuration.h | 1 + 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 482d0f257..2d685e311 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -11136,7 +11136,7 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) { // SERIAL_ECHOPAIR(" seconds=", seconds); // SERIAL_ECHOLNPAIR(" segments=", segments); - #if IS_SCARA + #if IS_SCARA && ENABLED(SCARA_FEEDRATE_SCALING) // SCARA needs to scale the feed rate from mm/s to degrees/s const float inv_segment_length = min(10.0, float(segments) / cartesian_mm), // 1/mm/segs feed_factor = inv_segment_length * _feedrate_mm_s; @@ -11163,7 +11163,7 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) { ADJUST_DELTA(logical); // Adjust Z if bed leveling is enabled - #if IS_SCARA + #if IS_SCARA && ENABLED(SCARA_FEEDRATE_SCALING) // For SCARA scale the feed rate from mm/s to degrees/s // Use ratio between the length of the move and the larger angle change const float adiff = abs(delta[A_AXIS] - oldA), @@ -11179,7 +11179,7 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) { // Since segment_distance is only approximate, // the final move must be to the exact destination. - #if IS_SCARA + #if IS_SCARA && ENABLED(SCARA_FEEDRATE_SCALING) // For SCARA scale the feed rate from mm/s to degrees/s // With segments > 1 length is 1 segment, otherwise total length inverse_kinematics(ltarget); diff --git a/Marlin/example_configurations/SCARA/Configuration.h b/Marlin/example_configurations/SCARA/Configuration.h index fcaf75b4e..d464efd3c 100644 --- a/Marlin/example_configurations/SCARA/Configuration.h +++ b/Marlin/example_configurations/SCARA/Configuration.h @@ -76,6 +76,7 @@ #if ENABLED(MORGAN_SCARA) || ENABLED(MAKERARM_SCARA) //#define DEBUG_SCARA_KINEMATICS + //#define SCARA_FEEDRATE_SCALING // Convert XY feedrate from mm/s to degrees/s on the fly // If movement is choppy try lowering this value #define SCARA_SEGMENTS_PER_SECOND 200 From 47cae2929f55e284c8a029a4459ecd57b720323c Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 8 May 2017 20:05:57 -0500 Subject: [PATCH 034/189] Patch platformio.ini to fix build error in DevIoT For compatibility with DevIoT, until that can be solved. --- .gitignore | 1 + Marlin/platformio.ini => platformio.ini | 4 ++-- 2 files changed, 3 insertions(+), 2 deletions(-) rename Marlin/platformio.ini => platformio.ini (96%) diff --git a/.gitignore b/.gitignore index bc9226570..a51a27fed 100755 --- a/.gitignore +++ b/.gitignore @@ -119,6 +119,7 @@ tags .pioenvs .piolib .piolibdeps +lib/readme.txt #Visual Studio *.sln diff --git a/Marlin/platformio.ini b/platformio.ini similarity index 96% rename from Marlin/platformio.ini rename to platformio.ini index 2cc47133b..ec62931eb 100644 --- a/Marlin/platformio.ini +++ b/platformio.ini @@ -24,7 +24,7 @@ lib_deps = U8glib@1.19.1 [env:mega2560] platform = atmelavr framework = arduino -board = megaatmega2560 +board = mega2560 build_flags = -I $BUILDSRC_DIR board_f_cpu = 16000000L lib_deps = ${common.lib_deps} @@ -32,7 +32,7 @@ lib_deps = ${common.lib_deps} [env:mega1280] platform = atmelavr framework = arduino -board = megaatmega1280 +board = mega1280 build_flags = -I $BUILDSRC_DIR board_f_cpu = 16000000L lib_deps = ${common.lib_deps} From fe96376a73532c29c265bc3f572a53c4f3ef0b40 Mon Sep 17 00:00:00 2001 From: Florian Heilmann Date: Tue, 9 May 2017 13:54:57 +0200 Subject: [PATCH 035/189] Fix FWRetract with positive z-moves during retracted state --- Marlin/Marlin_main.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 2d685e311..7bdc39e7f 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -3071,8 +3071,8 @@ static void homeaxis(const AxisEnum axis) { } else { - // If the height hasn't been altered, undo the Z hop - if (retract_zlift > 0.01 && hop_height == current_position[Z_AXIS]) { + // If the height hasn't been lowered, undo the Z hop + if (retract_zlift > 0.01 && hop_height <= current_position[Z_AXIS]) { // Pretend current position is higher. Z will lower on the next move current_position[Z_AXIS] += retract_zlift; SYNC_PLAN_POSITION_KINEMATIC(); From fe1fce5f56dd222491e561355625cfece15772c6 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 9 May 2017 11:28:39 -0500 Subject: [PATCH 036/189] DevIoT patch 2 --- platformio.ini | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/platformio.ini b/platformio.ini index ec62931eb..4182e53fc 100644 --- a/platformio.ini +++ b/platformio.ini @@ -21,18 +21,18 @@ env_default = mega2560 [common] lib_deps = U8glib@1.19.1 -[env:mega2560] +[env:megaatmega2560] platform = atmelavr framework = arduino -board = mega2560 +board = megaatmega2560 build_flags = -I $BUILDSRC_DIR board_f_cpu = 16000000L lib_deps = ${common.lib_deps} -[env:mega1280] +[env:megaatmega1280] platform = atmelavr framework = arduino -board = mega1280 +board = megaatmega1280 build_flags = -I $BUILDSRC_DIR board_f_cpu = 16000000L lib_deps = ${common.lib_deps} @@ -41,7 +41,7 @@ lib_deps = ${common.lib_deps} platform = teensy framework = arduino board = teensy20pp -build_flags = -I $BUILDSRC_DIR -D MOTHERBOARD=BOARD_PRINTRBOARD +build_flags = -I $BUILDSRC_DIR -D MOTHERBOARD=BOARD_PRINTRBOARD # Bug in arduino framework does not allow boards running at 20Mhz #board_f_cpu = 20000000L lib_deps = ${common.lib_deps} From 8d961b51cc3a00c671572fe5defac67a53a45533 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 7 May 2017 23:35:04 -0500 Subject: [PATCH 037/189] Eliminate M100 compiler warnings? --- Marlin/M100_Free_Mem_Chk.cpp | 18 +++++++++--------- Marlin/Marlin_main.cpp | 2 +- 2 files changed, 10 insertions(+), 10 deletions(-) diff --git a/Marlin/M100_Free_Mem_Chk.cpp b/Marlin/M100_Free_Mem_Chk.cpp index 9c31aa6f9..047f4225d 100644 --- a/Marlin/M100_Free_Mem_Chk.cpp +++ b/Marlin/M100_Free_Mem_Chk.cpp @@ -78,7 +78,7 @@ char* top_of_stack() { } // Count the number of test bytes at the specified location. -int16_t count_test_bytes(const uint8_t * const ptr) { +int16_t count_test_bytes(const char * const ptr) { for (uint16_t i = 0; i < 32000; i++) if (((char) ptr[i]) != TEST_BYTE) return i - 1; @@ -100,13 +100,13 @@ int16_t count_test_bytes(const uint8_t * const ptr) { * the block. If so, it may indicate memory corruption due to a bad pointer. * Unexpected bytes are flagged in the right column. */ - void dump_free_memory(const uint8_t *ptr, const uint8_t *sp) { + void dump_free_memory(const char *ptr, const char *sp) { // // Start and end the dump on a nice 16 byte boundary // (even though the values are not 16-byte aligned). // - ptr = (uint8_t *)((uint16_t)ptr & 0xFFF0); // Align to 16-byte boundary - sp = (uint8_t *)((uint16_t)sp | 0x000F); // Align sp to the 15th byte (at or above sp) + ptr = (char *)((uint16_t)ptr & 0xFFF0); // Align to 16-byte boundary + sp = (char *)((uint16_t)sp | 0x000F); // Align sp to the 15th byte (at or above sp) // Dump command main loop while (ptr < sp) { @@ -121,7 +121,7 @@ int16_t count_test_bytes(const uint8_t * const ptr) { SERIAL_CHAR('|'); // Point out non test bytes for (uint8_t i = 0; i < 16; i++) { char ccc = (char)ptr[i]; // cast to char before automatically casting to char on assignment, in case the compiler is broken - if (&ptr[i] >= command_queue && &ptr[i] < &command_queue[BUFSIZE][MAX_CMD_SIZE]) { // Print out ASCII in the command buffer area + if (&ptr[i] >= (const char*)command_queue && &ptr[i] < (const char*)(command_queue + sizeof(command_queue))) { // Print out ASCII in the command buffer area if (!WITHIN(ccc, ' ', 0x7E)) ccc = ' '; } else { // If not in the command buffer area, flag bytes that don't match the test byte @@ -153,13 +153,13 @@ void M100_dump_routine(const char * const title, const char *start, const char * * Return the number of free bytes in the memory pool, * with other vital statistics defining the pool. */ -void free_memory_pool_report(const char * const ptr, const uint16_t size) { +void free_memory_pool_report(char * const ptr, const uint16_t size) { int16_t max_cnt = -1; uint16_t block_cnt = 0; char *max_addr = NULL; // Find the longest block of test bytes in the buffer for (uint16_t i = 0; i < size; i++) { - char * const addr = ptr + i; + char *addr = ptr + i; if (*addr == TEST_BYTE) { const uint16_t j = count_test_bytes(addr); if (j > 8) { @@ -209,7 +209,7 @@ void free_memory_pool_report(const char * const ptr, const uint16_t size) { * M100 I * Init memory for the M100 tests. (Automatically applied on the first M100.) */ -void init_free_memory(uint8_t *ptr, int16_t size) { +void init_free_memory(char *ptr, int16_t size) { SERIAL_ECHOLNPGM("Initializing free memory block.\n\n"); size -= 250; // -250 to avoid interrupt activity that's altered the stack. @@ -292,7 +292,7 @@ int check_for_free_memory_corruption(const char * const title) { // idle(); safe_delay(20); #ifdef M100_FREE_MEMORY_DUMPER - M100_dump_routine(" Memory corruption detected with sp Date: Tue, 9 May 2017 11:51:46 -0500 Subject: [PATCH 038/189] Reduce redundancy in BLTOUCH conditionals --- Marlin/Conditionals_LCD.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/Conditionals_LCD.h b/Marlin/Conditionals_LCD.h index 453468953..b1a5b5a05 100644 --- a/Marlin/Conditionals_LCD.h +++ b/Marlin/Conditionals_LCD.h @@ -357,15 +357,15 @@ #define BLTOUCH_RESET 160 #define _TEST_BLTOUCH(P) (READ(P##_PIN) != P##_ENDSTOP_INVERTING) + // Always disable probe pin inverting for BLTouch + #undef Z_MIN_PROBE_ENDSTOP_INVERTING + #define Z_MIN_PROBE_ENDSTOP_INVERTING false + #if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) #undef Z_MIN_ENDSTOP_INVERTING #define Z_MIN_ENDSTOP_INVERTING false - #undef Z_MIN_PROBE_ENDSTOP_INVERTING - #define Z_MIN_PROBE_ENDSTOP_INVERTING false #define TEST_BLTOUCH() _TEST_BLTOUCH(Z_MIN) #else - #undef Z_MIN_PROBE_ENDSTOP_INVERTING - #define Z_MIN_PROBE_ENDSTOP_INVERTING false #define TEST_BLTOUCH() _TEST_BLTOUCH(Z_MIN_PROBE) #endif #endif From 9a364990d9a4c07d3d292ac35c8b5a185d09828c Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 9 May 2017 12:24:40 -0500 Subject: [PATCH 039/189] Update .gitignore --- .gitignore | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/.gitignore b/.gitignore index a51a27fed..a9267a2dc 100755 --- a/.gitignore +++ b/.gitignore @@ -115,10 +115,8 @@ tags *.dSYM/ *.su -#PlatformIO files/dirs -.pioenvs -.piolib -.piolibdeps +# PlatformIO files/dirs +.pio* lib/readme.txt #Visual Studio From 081bf1f8799db79e3d16597cf1832c2b7adb3818 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 9 May 2017 12:35:43 -0500 Subject: [PATCH 040/189] Patch #else / #endif comments --- Marlin/Conditionals_LCD.h | 4 ++-- Marlin/Marlin.h | 2 +- Marlin/Marlin_main.cpp | 16 +++++++-------- Marlin/blinkm.cpp | 2 +- Marlin/boards.h | 2 +- Marlin/cardreader.cpp | 4 ++-- Marlin/cardreader.h | 4 ++-- Marlin/configuration_store.cpp | 4 ++-- Marlin/digipot_mcp4451.cpp | 2 +- Marlin/endstop_interrupts.h | 2 +- Marlin/language.h | 2 +- Marlin/macros.h | 2 +- Marlin/mesh_bed_leveling.cpp | 2 +- Marlin/mesh_bed_leveling.h | 2 +- Marlin/nozzle.h | 2 +- Marlin/pins.h | 2 +- Marlin/pins_SAV_MKI.h | 2 +- Marlin/planner.cpp | 4 ++-- Marlin/servo.cpp | 2 +- Marlin/stepper.cpp | 2 +- Marlin/stopwatch.h | 2 +- Marlin/temperature.cpp | 18 ++++++++-------- Marlin/twibus.cpp | 2 +- Marlin/twibus.h | 2 +- Marlin/ultralcd.cpp | 32 ++++++++++++++--------------- Marlin/ultralcd.h | 2 +- Marlin/ultralcd_impl_DOGM.h | 2 +- Marlin/ultralcd_impl_HD44780.h | 4 ++-- Marlin/ultralcd_st7920_u8glib_rrd.h | 4 ++-- Marlin/watchdog.cpp | 4 ++-- 30 files changed, 68 insertions(+), 68 deletions(-) diff --git a/Marlin/Conditionals_LCD.h b/Marlin/Conditionals_LCD.h index b1a5b5a05..19c7f8109 100644 --- a/Marlin/Conditionals_LCD.h +++ b/Marlin/Conditionals_LCD.h @@ -205,7 +205,7 @@ #ifndef LCD_HEIGHT #define LCD_HEIGHT 4 #endif - #else //no panel but just LCD + #else // no panel but just LCD #if ENABLED(ULTRA_LCD) #ifndef LCD_WIDTH #define LCD_WIDTH 16 @@ -392,4 +392,4 @@ #define HAS_RESUME_CONTINUE (ENABLED(NEWPANEL) || ENABLED(EMERGENCY_PARSER)) #define HAS_COLOR_LEDS (ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED)) -#endif //CONDITIONALS_LCD_H +#endif // CONDITIONALS_LCD_H diff --git a/Marlin/Marlin.h b/Marlin/Marlin.h index a5c2b81c2..b10541b06 100644 --- a/Marlin/Marlin.h +++ b/Marlin/Marlin.h @@ -429,4 +429,4 @@ void do_blocking_move_to_xy(const float &x, const float &y, const float &fr_mm_s bool axis_unhomed_error(const bool x, const bool y, const bool z); #endif -#endif //MARLIN_H +#endif // MARLIN_H diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 0cb90c968..4047adb52 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -788,7 +788,7 @@ extern "C" { return free_memory; } } -#endif //!SDSUPPORT +#endif // !SDSUPPORT #if ENABLED(DIGIPOT_I2C) extern void digipot_i2c_set_current(int channel, float current); @@ -1841,7 +1841,7 @@ static void clean_up_after_endstop_or_probe_move() { do_blocking_move_to_z(z_dest); } -#endif //HAS_BED_PROBE +#endif // HAS_BED_PROBE #if HAS_PROBING_PROCEDURE || HOTENDS > 1 || ENABLED(Z_PROBE_ALLEN_KEY) || ENABLED(Z_PROBE_SLED) || ENABLED(NOZZLE_CLEAN_FEATURE) || ENABLED(NOZZLE_PARK_FEATURE) || ENABLED(DELTA_AUTO_CALIBRATION) @@ -3208,7 +3208,7 @@ void unknown_command_error() { next_busy_signal_ms = ms + host_keepalive_interval * 1000UL; } -#endif //HOST_KEEPALIVE_FEATURE +#endif // HOST_KEEPALIVE_FEATURE bool position_is_reachable(const float target[XYZ] #if HAS_BED_PROBE @@ -3421,7 +3421,7 @@ inline void gcode_G4() { ); } -#endif //FWRETRACT +#endif // FWRETRACT #if ENABLED(NOZZLE_CLEAN_FEATURE) /** @@ -7032,7 +7032,7 @@ inline void gcode_M111() { inline void gcode_M129() { baricuda_e_to_p_pressure = 0; } #endif -#endif //BARICUDA +#endif // BARICUDA /** * M140: Set bed temperature @@ -9385,7 +9385,7 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool n for (uint8_t j = 0; j < MIXING_STEPPERS; j++) mixing_factor[j] = mixing_virtual_tool_mix[tmp_extruder][j]; - #else //!MIXING_EXTRUDER || MIXING_VIRTUAL_TOOLS <= 1 + #else // !MIXING_EXTRUDER || MIXING_VIRTUAL_TOOLS <= 1 #if HOTENDS > 1 @@ -9677,7 +9677,7 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool n SERIAL_ECHO_START; SERIAL_ECHOLNPAIR(MSG_ACTIVE_EXTRUDER, (int)active_extruder); - #endif //!MIXING_EXTRUDER || MIXING_VIRTUAL_TOOLS <= 1 + #endif // !MIXING_EXTRUDER || MIXING_VIRTUAL_TOOLS <= 1 } /** @@ -9968,7 +9968,7 @@ void process_next_command() { case 928: // M928: Start SD write gcode_M928(); break; - #endif //SDSUPPORT + #endif // SDSUPPORT case 31: // M31: Report time since the start of SD print or last M109 gcode_M31(); break; diff --git a/Marlin/blinkm.cpp b/Marlin/blinkm.cpp index c495a5deb..1caf0a071 100644 --- a/Marlin/blinkm.cpp +++ b/Marlin/blinkm.cpp @@ -42,5 +42,5 @@ void SendColors(byte red, byte grn, byte blu) { Wire.endTransmission(); } -#endif //BLINKM +#endif // BLINKM diff --git a/Marlin/boards.h b/Marlin/boards.h index 14f1d27a1..32165f53c 100644 --- a/Marlin/boards.h +++ b/Marlin/boards.h @@ -98,4 +98,4 @@ #define MB(board) (MOTHERBOARD==BOARD_##board) -#endif //__BOARDS_H +#endif // __BOARDS_H diff --git a/Marlin/cardreader.cpp b/Marlin/cardreader.cpp index a37389e45..5681660d2 100644 --- a/Marlin/cardreader.cpp +++ b/Marlin/cardreader.cpp @@ -54,7 +54,7 @@ CardReader::CardReader() { //power to SD reader #if SDPOWER > -1 OUT_WRITE(SDPOWER, HIGH); - #endif //SDPOWER + #endif // SDPOWER next_autostart_ms = millis() + 5000; } @@ -882,4 +882,4 @@ void CardReader::printingHasFinished() { } } -#endif //SDSUPPORT +#endif // SDSUPPORT diff --git a/Marlin/cardreader.h b/Marlin/cardreader.h index 05e8ecf07..ca2968273 100644 --- a/Marlin/cardreader.h +++ b/Marlin/cardreader.h @@ -183,6 +183,6 @@ extern CardReader card; #define IS_SD_PRINTING (false) -#endif //SDSUPPORT +#endif // SDSUPPORT -#endif //__CARDREADER_H +#endif // __CARDREADER_H diff --git a/Marlin/configuration_store.cpp b/Marlin/configuration_store.cpp index 99495997b..997922550 100644 --- a/Marlin/configuration_store.cpp +++ b/Marlin/configuration_store.cpp @@ -418,7 +418,7 @@ void MarlinSettings::postprocess() { EEPROM_WRITE(ubl_active); EEPROM_WRITE(dummy); EEPROM_WRITE(eeprom_slot); - #endif //AUTO_BED_LEVELING_UBL + #endif // AUTO_BED_LEVELING_UBL // 9 floats for DELTA / Z_DUAL_ENDSTOPS #if ENABLED(DELTA) @@ -795,7 +795,7 @@ void MarlinSettings::postprocess() { EEPROM_READ(dummyb); EEPROM_READ(dummy); EEPROM_READ(dummyui8); - #endif //AUTO_BED_LEVELING_UBL + #endif // AUTO_BED_LEVELING_UBL #if ENABLED(DELTA) EEPROM_READ(endstop_adj); // 3 floats diff --git a/Marlin/digipot_mcp4451.cpp b/Marlin/digipot_mcp4451.cpp index 9c5e8d025..419d3a423 100644 --- a/Marlin/digipot_mcp4451.cpp +++ b/Marlin/digipot_mcp4451.cpp @@ -76,4 +76,4 @@ void digipot_i2c_init() { digipot_i2c_set_current(i, digipot_motor_current[i]); } -#endif //DIGIPOT_I2C +#endif // DIGIPOT_I2C diff --git a/Marlin/endstop_interrupts.h b/Marlin/endstop_interrupts.h index 642f78a58..7d37c77c6 100644 --- a/Marlin/endstop_interrupts.h +++ b/Marlin/endstop_interrupts.h @@ -203,4 +203,4 @@ void setup_endstop_interrupts( void ) { // If we arrive here without raising an assertion, each pin has either an EXT-interrupt or a PCI. } -#endif //_ENDSTOP_INTERRUPTS_H_ +#endif // _ENDSTOP_INTERRUPTS_H_ diff --git a/Marlin/language.h b/Marlin/language.h index f377ce248..1294eb6b6 100644 --- a/Marlin/language.h +++ b/Marlin/language.h @@ -305,4 +305,4 @@ #include "language_en.h" -#endif //__LANGUAGE_H +#endif // __LANGUAGE_H diff --git a/Marlin/macros.h b/Marlin/macros.h index a943e9cb5..8badc5c85 100644 --- a/Marlin/macros.h +++ b/Marlin/macros.h @@ -183,4 +183,4 @@ #define RECIPROCAL(x) (NEAR_ZERO(x) ? 0.0 : 1.0 / (x)) #define FIXFLOAT(f) (f + 0.00001) -#endif //__MACROS_H +#endif // __MACROS_H diff --git a/Marlin/mesh_bed_leveling.cpp b/Marlin/mesh_bed_leveling.cpp index 08fdd3f86..3da19d97e 100644 --- a/Marlin/mesh_bed_leveling.cpp +++ b/Marlin/mesh_bed_leveling.cpp @@ -47,4 +47,4 @@ ZERO(z_values); } -#endif // MESH_BED_LEVELING +#endif // MESH_BED_LEVELING diff --git a/Marlin/mesh_bed_leveling.h b/Marlin/mesh_bed_leveling.h index b2d503b4b..41ba2677c 100644 --- a/Marlin/mesh_bed_leveling.h +++ b/Marlin/mesh_bed_leveling.h @@ -119,4 +119,4 @@ extern mesh_bed_leveling mbl; -#endif // MESH_BED_LEVELING +#endif // MESH_BED_LEVELING diff --git a/Marlin/nozzle.h b/Marlin/nozzle.h index 6b3b4a1a2..944dd5d21 100644 --- a/Marlin/nozzle.h +++ b/Marlin/nozzle.h @@ -32,7 +32,7 @@ nozzle_clean_length = fabs(nozzle_clean_start_point[X_AXIS] - nozzle_clean_end_point[X_AXIS]), //abs x size of wipe pad nozzle_clean_height = fabs(nozzle_clean_start_point[Y_AXIS] - nozzle_clean_end_point[Y_AXIS]); //abs y size of wipe pad constexpr bool nozzle_clean_horizontal = nozzle_clean_length >= nozzle_clean_height; //whether to zig-zag horizontally or vertically -#endif //NOZZLE_CLEAN_FEATURE +#endif // NOZZLE_CLEAN_FEATURE /** * @brief Nozzle class diff --git a/Marlin/pins.h b/Marlin/pins.h index 7458d8cef..aef1083b9 100644 --- a/Marlin/pins.h +++ b/Marlin/pins.h @@ -568,4 +568,4 @@ #define SS_PIN AVR_SS_PIN #endif -#endif //__PINS_H +#endif // __PINS_H diff --git a/Marlin/pins_SAV_MKI.h b/Marlin/pins_SAV_MKI.h index c2ad00631..019139d1e 100644 --- a/Marlin/pins_SAV_MKI.h +++ b/Marlin/pins_SAV_MKI.h @@ -131,7 +131,7 @@ // For LCD SHIFT register LCD #define SR_DATA_PIN EXT_AUX_SDA_D1 #define SR_CLK_PIN EXT_AUX_SCL_D0 -#endif // SAV_3DLCD +#endif // SAV_3DLCD #if ENABLED(SAV_3DLCD) || ENABLED(SAV_3DGLCD) #define BTN_EN1 EXT_AUX_A1_IO diff --git a/Marlin/planner.cpp b/Marlin/planner.cpp index f95d8ab6e..af6808fa2 100644 --- a/Marlin/planner.cpp +++ b/Marlin/planner.cpp @@ -392,7 +392,7 @@ void Planner::recalculate() { thermalManager.setTargetHotend(t, 0); } -#endif //AUTOTEMP +#endif // AUTOTEMP /** * Maintain fans, paste extruder pressure, @@ -487,7 +487,7 @@ void Planner::check_axes_activity() { KICKSTART_FAN(2); #endif - #endif //FAN_KICKSTART_TIME + #endif // FAN_KICKSTART_TIME #if ENABLED(FAN_SOFT_PWM) #if HAS_FAN0 diff --git a/Marlin/servo.cpp b/Marlin/servo.cpp index bfe24c8b6..3536571c1 100644 --- a/Marlin/servo.cpp +++ b/Marlin/servo.cpp @@ -221,7 +221,7 @@ static void finISR(timer16_Sequence_t timer) { , OCIE3A); // disable the timer3 output compare A interrupt timerDetach(TIMER3OUTCOMPAREA_INT); } - #else //!WIRING + #else // !WIRING // For arduino - in future: call here to a currently undefined function to reset the timer UNUSED(timer); #endif diff --git a/Marlin/stepper.cpp b/Marlin/stepper.cpp index ff6d85f84..08612b490 100644 --- a/Marlin/stepper.cpp +++ b/Marlin/stepper.cpp @@ -1398,7 +1398,7 @@ void Stepper::report_positions() { //delay(10); } -#endif //HAS_DIGIPOTSS +#endif // HAS_DIGIPOTSS #if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM diff --git a/Marlin/stopwatch.h b/Marlin/stopwatch.h index 735983891..ae3c998fb 100644 --- a/Marlin/stopwatch.h +++ b/Marlin/stopwatch.h @@ -114,4 +114,4 @@ class Stopwatch { #endif }; -#endif //STOPWATCH_H +#endif // STOPWATCH_H diff --git a/Marlin/temperature.cpp b/Marlin/temperature.cpp index 6021d899a..8193d3c96 100644 --- a/Marlin/temperature.cpp +++ b/Marlin/temperature.cpp @@ -601,7 +601,7 @@ float Temperature::get_pid_output(int e) { } #else pid_output = constrain(target_temperature[HOTEND_INDEX], 0, PID_MAX); - #endif //PID_OPENLOOP + #endif // PID_OPENLOOP #if ENABLED(PID_DEBUG) SERIAL_ECHO_START; @@ -615,7 +615,7 @@ float Temperature::get_pid_output(int e) { SERIAL_ECHOPAIR(MSG_PID_DEBUG_CTERM, cTerm[HOTEND_INDEX]); #endif SERIAL_EOL; - #endif //PID_DEBUG + #endif // PID_DEBUG #else /* PID off */ pid_output = (current_temperature[HOTEND_INDEX] < target_temperature[HOTEND_INDEX]) ? PID_MAX : 0; @@ -662,11 +662,11 @@ float Temperature::get_pid_output(int e) { SERIAL_ECHO(iTerm_bed); SERIAL_ECHOPGM(" dTerm "); SERIAL_ECHOLN(dTerm_bed); - #endif //PID_BED_DEBUG + #endif // PID_BED_DEBUG return pid_output; } -#endif //PIDTEMPBED +#endif // PIDTEMPBED /** * Manage heating activities for extruder hot-ends and a heated bed @@ -818,7 +818,7 @@ void Temperature::manage_heater() { WRITE_HEATER_BED(LOW); } #endif - #endif //TEMP_SENSOR_BED != 0 + #endif // TEMP_SENSOR_BED != 0 } #define PGM_RD_W(x) (short)pgm_read_word(&x) @@ -1188,7 +1188,7 @@ void Temperature::init() { bed_minttemp_raw -= OVERSAMPLENR; #endif } - #endif //BED_MINTEMP + #endif // BED_MINTEMP #ifdef BED_MAXTEMP while (analog2tempBed(bed_maxttemp_raw) > BED_MAXTEMP) { #if HEATER_BED_RAW_LO_TEMP < HEATER_BED_RAW_HI_TEMP @@ -1197,7 +1197,7 @@ void Temperature::init() { bed_maxttemp_raw += OVERSAMPLENR; #endif } - #endif //BED_MAXTEMP + #endif // BED_MAXTEMP #if ENABLED(PROBING_HEATERS_OFF) paused = false; @@ -1454,7 +1454,7 @@ void Temperature::disable_all_heaters() { return (int)max6675_temp; } -#endif //HEATER_0_USES_MAX6675 +#endif // HEATER_0_USES_MAX6675 /** * Get raw temperatures @@ -2056,7 +2056,7 @@ void Temperature::isr() { babystepsTodo[axis]++; //fewer to do next time } } - #endif //BABYSTEPPING + #endif // BABYSTEPPING #if ENABLED(PINS_DEBUGGING) extern bool endstop_monitor_flag; diff --git a/Marlin/twibus.cpp b/Marlin/twibus.cpp index c59e79dc9..d4822f1d2 100644 --- a/Marlin/twibus.cpp +++ b/Marlin/twibus.cpp @@ -201,4 +201,4 @@ void TWIBus::flush() { #endif -#endif //EXPERIMENTAL_I2CBUS +#endif // EXPERIMENTAL_I2CBUS diff --git a/Marlin/twibus.h b/Marlin/twibus.h index 3b606571c..b93cd1c4c 100644 --- a/Marlin/twibus.h +++ b/Marlin/twibus.h @@ -239,4 +239,4 @@ class TWIBus { #endif }; -#endif //TWIBUS_H +#endif // TWIBUS_H diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 83cd04527..60771a5f5 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -291,7 +291,7 @@ uint16_t max_display_update_time = 0; _MENU_ITEM_PART_2(type, ## __VA_ARGS__); \ } while(0) - #else // !ENCODER_RATE_MULTIPLIER + #else // !ENCODER_RATE_MULTIPLIER #define ENCODER_RATE_MULTIPLY(F) NOOP #endif // !ENCODER_RATE_MULTIPLIER @@ -301,10 +301,10 @@ uint16_t max_display_update_time = 0; #if ENABLED(ENCODER_RATE_MULTIPLIER) #define MENU_MULTIPLIER_ITEM_EDIT(type, label, ...) MENU_MULTIPLIER_ITEM(setting_edit_ ## type, label, PSTR(label), ## __VA_ARGS__) #define MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(type, label, ...) MENU_MULTIPLIER_ITEM(setting_edit_callback_ ## type, label, PSTR(label), ## __VA_ARGS__) - #else //!ENCODER_RATE_MULTIPLIER + #else // !ENCODER_RATE_MULTIPLIER #define MENU_MULTIPLIER_ITEM_EDIT(type, label, ...) MENU_ITEM(setting_edit_ ## type, label, PSTR(label), ## __VA_ARGS__) #define MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(type, label, ...) MENU_ITEM(setting_edit_callback_ ## type, label, PSTR(label), ## __VA_ARGS__) - #endif //!ENCODER_RATE_MULTIPLIER + #endif // !ENCODER_RATE_MULTIPLIER /** * START_SCREEN_OR_MENU generates init code for a screen or menu @@ -568,10 +568,10 @@ void lcd_status_screen() { } #else expire_status_ms = 0; - #endif //SDSUPPORT + #endif // SDSUPPORT } #endif - #endif //LCD_PROGRESS_BAR + #endif // LCD_PROGRESS_BAR lcd_implementation_status_screen(); @@ -614,7 +614,7 @@ void lcd_status_screen() { feedrate_percentage = constrain(feedrate_percentage, 10, 999); - #endif //ULTIPANEL + #endif // ULTIPANEL } /** @@ -848,7 +848,7 @@ void kill_screen(const char* lcd_msg) { MENU_ITEM(gcode, MSG_INIT_SDCARD, PSTR("M21")); // Manually initialize the SD-card via user interface #endif } - #endif //SDSUPPORT + #endif // SDSUPPORT #if ENABLED(LCD_INFO_MENU) MENU_ITEM(submenu, MSG_INFO_MENU, lcd_info_menu); @@ -1061,7 +1061,7 @@ void kill_screen(const char* lcd_msg) { // #if HOTENDS == 1 MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(int3, MSG_NOZZLE, &thermalManager.target_temperature[0], 0, HEATER_0_MAXTEMP - 15, watch_temp_callback_E0); - #else //HOTENDS > 1 + #else // HOTENDS > 1 MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(int3, MSG_NOZZLE MSG_N1, &thermalManager.target_temperature[0], 0, HEATER_0_MAXTEMP - 15, watch_temp_callback_E0); MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(int3, MSG_NOZZLE MSG_N2, &thermalManager.target_temperature[1], 0, HEATER_1_MAXTEMP - 15, watch_temp_callback_E1); #if HOTENDS > 2 @@ -2191,7 +2191,7 @@ void kill_screen(const char* lcd_msg) { enqueue_and_echo_command(cmd); } - #endif //PID_AUTOTUNE_MENU + #endif // PID_AUTOTUNE_MENU #if ENABLED(PIDTEMP) @@ -2360,7 +2360,7 @@ void kill_screen(const char* lcd_msg) { PID_MENU_ITEMS("", 0); #endif // !PID_PARAMS_PER_HOTEND || HOTENDS == 1 - #endif //PIDTEMP + #endif // PIDTEMP // // Preheat Material 1 conf @@ -2724,7 +2724,7 @@ void kill_screen(const char* lcd_msg) { END_MENU(); } - #endif //SDSUPPORT + #endif // SDSUPPORT #if ENABLED(LCD_INFO_MENU) @@ -3285,7 +3285,7 @@ void kill_screen(const char* lcd_msg) { lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; } - #endif //SDSUPPORT + #endif // SDSUPPORT void menu_action_setting_edit_bool(const char* pstr, bool* ptr) {UNUSED(pstr); *ptr ^= true; lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; } void menu_action_setting_edit_callback_bool(const char* pstr, bool* ptr, screenFunc_t callback) { @@ -3483,7 +3483,7 @@ void lcd_update() { ); } - #endif //SDSUPPORT && SD_DETECT_PIN + #endif // SDSUPPORT && SD_DETECT_PIN const millis_t ms = millis(); if (ELAPSED(ms, next_lcd_update_ms) @@ -3533,12 +3533,12 @@ void lcd_update() { 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 //ENCODER_RATE_MULTIPLIER_DEBUG + #endif // ENCODER_RATE_MULTIPLIER_DEBUG } lastEncoderMovementMillis = ms; } // encoderRateMultiplierEnabled - #endif //ENCODER_RATE_MULTIPLIER + #endif // ENCODER_RATE_MULTIPLIER encoderPosition += (encoderDiff * encoderMultiplier) / ENCODER_PULSES_PER_STEP; encoderDiff = 0; @@ -3829,7 +3829,7 @@ void lcd_reset_alert_level() { lcd_status_message_level = 0; } #endif #else GET_BUTTON_STATES(buttons); - #endif //!NEWPANEL + #endif // !NEWPANEL } // next_button_update_ms diff --git a/Marlin/ultralcd.h b/Marlin/ultralcd.h index 0b32c09b6..fbc5e1c4a 100644 --- a/Marlin/ultralcd.h +++ b/Marlin/ultralcd.h @@ -148,7 +148,7 @@ #define LCD_CLICKED false #endif -#else //no LCD +#else // no LCD inline void lcd_update() {} inline void lcd_init() {} inline bool lcd_hasstatus() { return false; } diff --git a/Marlin/ultralcd_impl_DOGM.h b/Marlin/ultralcd_impl_DOGM.h index 0db02992b..9c36573c5 100644 --- a/Marlin/ultralcd_impl_DOGM.h +++ b/Marlin/ultralcd_impl_DOGM.h @@ -874,4 +874,4 @@ static void lcd_implementation_status_screen() { #endif // ULTIPANEL -#endif //__ULTRALCD_IMPL_DOGM_H +#endif // __ULTRALCD_IMPL_DOGM_H diff --git a/Marlin/ultralcd_impl_HD44780.h b/Marlin/ultralcd_impl_HD44780.h index 0e92079d6..0cb0d524f 100644 --- a/Marlin/ultralcd_impl_HD44780.h +++ b/Marlin/ultralcd_impl_HD44780.h @@ -101,7 +101,7 @@ extern volatile uint8_t buttons; //an extended version of the last checked butt #define LCD_CLICKED ((buttons & B_MI) || (buttons & B_ST)) #endif -#endif //ULTIPANEL +#endif // ULTIPANEL //////////////////////////////////// // Create LCD class instance and chipset-specific information @@ -675,7 +675,7 @@ static void lcd_implementation_status_screen() { LCD_TEMP(thermalManager.degBed(), thermalManager.degTargetBed(), LCD_STR_BEDTEMP[0]); #endif - #endif // HOTENDS > 1 || TEMP_SENSOR_BED != 0 + #endif // HOTENDS > 1 || TEMP_SENSOR_BED != 0 #endif // LCD_WIDTH >= 20 diff --git a/Marlin/ultralcd_st7920_u8glib_rrd.h b/Marlin/ultralcd_st7920_u8glib_rrd.h index 5cc36907f..edefbc93d 100644 --- a/Marlin/ultralcd_st7920_u8glib_rrd.h +++ b/Marlin/ultralcd_st7920_u8glib_rrd.h @@ -186,5 +186,5 @@ class U8GLIB_ST7920_128X64_RRD : public U8GLIB { #pragma GCC reset_options -#endif //U8GLIB_ST7920 -#endif //ULCDST7920_H +#endif // U8GLIB_ST7920 +#endif // ULCDST7920_H diff --git a/Marlin/watchdog.cpp b/Marlin/watchdog.cpp index ce8e832b6..fe20b89e9 100644 --- a/Marlin/watchdog.cpp +++ b/Marlin/watchdog.cpp @@ -51,6 +51,6 @@ void watchdog_init() { kill(PSTR("ERR:Please Reset")); //kill blocks //16 characters so it fits on a 16x2 display while (1); //wait for user or serial reset } -#endif //WATCHDOG_RESET_MANUAL +#endif // WATCHDOG_RESET_MANUAL -#endif //USE_WATCHDOG +#endif // USE_WATCHDOG From 11104f177b4613982268d162f0e868a1850951f1 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 9 May 2017 12:36:37 -0500 Subject: [PATCH 041/189] Apply const in BABYSTEPPING --- Marlin/temperature.cpp | 11 +++++------ 1 file changed, 5 insertions(+), 6 deletions(-) diff --git a/Marlin/temperature.cpp b/Marlin/temperature.cpp index 8193d3c96..94c1e4a58 100644 --- a/Marlin/temperature.cpp +++ b/Marlin/temperature.cpp @@ -2045,15 +2045,14 @@ void Temperature::isr() { #if ENABLED(BABYSTEPPING) LOOP_XYZ(axis) { - int curTodo = babystepsTodo[axis]; //get rid of volatile for performance - + const int curTodo = babystepsTodo[axis]; // get rid of volatile for performance if (curTodo > 0) { - stepper.babystep((AxisEnum)axis,/*fwd*/true); - babystepsTodo[axis]--; //fewer to do next time + stepper.babystep((AxisEnum)axis, /*fwd*/true); + babystepsTodo[axis]--; } else if (curTodo < 0) { - stepper.babystep((AxisEnum)axis,/*fwd*/false); - babystepsTodo[axis]++; //fewer to do next time + stepper.babystep((AxisEnum)axis, /*fwd*/false); + babystepsTodo[axis]++; } } #endif // BABYSTEPPING From 3b0127cf8e24daf31f0a07a2c1154cc8d3595aa8 Mon Sep 17 00:00:00 2001 From: Brian Date: Tue, 9 May 2017 21:45:44 -0400 Subject: [PATCH 042/189] Fix compiler complaint related to M100 --- Marlin/M100_Free_Mem_Chk.cpp | 13 ++++++------- 1 file changed, 6 insertions(+), 7 deletions(-) diff --git a/Marlin/M100_Free_Mem_Chk.cpp b/Marlin/M100_Free_Mem_Chk.cpp index 047f4225d..6b5edebff 100644 --- a/Marlin/M100_Free_Mem_Chk.cpp +++ b/Marlin/M100_Free_Mem_Chk.cpp @@ -153,15 +153,14 @@ void M100_dump_routine(const char * const title, const char *start, const char * * Return the number of free bytes in the memory pool, * with other vital statistics defining the pool. */ -void free_memory_pool_report(char * const ptr, const uint16_t size) { - int16_t max_cnt = -1; - uint16_t block_cnt = 0; +void free_memory_pool_report(char * const ptr, const int16_t size) { + int16_t max_cnt = -1, block_cnt = 0; char *max_addr = NULL; // Find the longest block of test bytes in the buffer - for (uint16_t i = 0; i < size; i++) { + for (int16_t i = 0; i < size; i++) { char *addr = ptr + i; if (*addr == TEST_BYTE) { - const uint16_t j = count_test_bytes(addr); + const int16_t j = count_test_bytes(addr); if (j > 8) { SERIAL_ECHOPAIR("Found ", j); SERIAL_ECHOLNPAIR(" bytes free at ", hex_address(addr)); @@ -225,8 +224,8 @@ void init_free_memory(char *ptr, int16_t size) { SERIAL_ECHO(size); SERIAL_ECHOLNPGM(" bytes of memory initialized.\n"); - for (uint16_t i = 0; i < size; i++) { - if ((char)ptr[i] != TEST_BYTE) { + for (int16_t i = 0; i < size; i++) { + if (ptr[i] != TEST_BYTE) { SERIAL_ECHOPAIR("? address : ", hex_address(ptr + i)); SERIAL_ECHOLNPAIR("=", hex_byte(ptr[i])); SERIAL_EOL; From f1cccd65c29558c1fcf2ef8758b6a68860fd23c0 Mon Sep 17 00:00:00 2001 From: Brian Date: Wed, 10 May 2017 07:11:13 -0400 Subject: [PATCH 043/189] platformio.ini env_default=xxxxx has to match one of the labels in the env:xxxxx, otherwise nothing happens when you `pio run` --- platformio.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/platformio.ini b/platformio.ini index 4182e53fc..c82fe4869 100644 --- a/platformio.ini +++ b/platformio.ini @@ -16,7 +16,7 @@ src_dir = Marlin envs_dir = .pioenvs lib_dir = .piolib libdeps_dir = .piolibdeps -env_default = mega2560 +env_default = megaatmega2560 [common] lib_deps = U8glib@1.19.1 From 66db6c3acc83afeaea87cd39dfccd0af87cacf90 Mon Sep 17 00:00:00 2001 From: Tannoo Date: Sun, 7 May 2017 21:38:03 -0600 Subject: [PATCH 044/189] UBL Menu System 1.1 /** * UBL System submenu * * Prepare * - Unified Bed Leveling * - Activate UBL * - Deactivate UBL * - Mesh Storage * Memory Slot: * Load Bed Mesh * Save Bed Mesh * - Output Map * Map Type: * Output Bed Mesh Host / Output Bed Mesh CSV * - UBL Tools * - Build Mesh * Build PLA Mesh * Build ABS Mesh * - Build Custom Mesh * Hotend Temp: * Bed Temp: * Build Custom Mesh * Info Screen * - Build Cold Mesh * - Fill-in Mesh * Fill-in Mesh * Smart Fill-in * Manual Fill-in * Info Screen * Continue Bed Mesh * Invalidate All * Invalidate Closest * - Validate Mesh * PLA Mesh Validation * ABS Mesh Validation * - Custom Mesh Validation * Hotend Temp: * Bed Temp: * Validate Mesh * Info Screen * - Edit Mesh * Fine Tune All * Fine Tune Closest * - Adjust Mesh Height * Height Amount: * Adjust Mesh Height * Info Screen * - Mesh Leveling * 3-Point Mesh Leveling * - Grid Mesh Leveling * Side points: * Level Mesh * Info Screen * - Output UBL Info */ --- Marlin/language_en.h | 143 +++++++++++++++++- Marlin/ubl_G29.cpp | 32 ++-- Marlin/ultralcd.cpp | 350 ++++++++++++++++++++++++++++++++++++++++++- 3 files changed, 512 insertions(+), 13 deletions(-) diff --git a/Marlin/language_en.h b/Marlin/language_en.h index 78d674c71..7dd2edf0a 100644 --- a/Marlin/language_en.h +++ b/Marlin/language_en.h @@ -153,6 +153,145 @@ #ifndef MSG_LEVEL_BED #define MSG_LEVEL_BED _UxGT("Level bed") #endif + +#if ENABLED(AUTO_BED_LEVELING_UBL) + #ifndef MSG_UBL_UNHOMED + #define MSG_UBL_UNHOMED _UxGT("Home XYZ first") + #endif + #ifndef MSG_UBL_TOOLS + #define MSG_UBL_TOOLS _UxGT("UBL Tools") + #endif + #ifndef MSG_UBL_LEVEL_BED + #define MSG_UBL_LEVEL_BED _UxGT("Unified Bed Leveling") + #endif + #ifndef MSG_UBL_ACTIVATE_MESH + #define MSG_UBL_ACTIVATE_MESH _UxGT("Activate UBL") + #endif + #ifndef MSG_UBL_DEACTIVATE_MESH + #define MSG_UBL_DEACTIVATE_MESH _UxGT("Deactivate UBL") + #endif + #ifndef MSG_UBL_CUSTOM_BED_TEMP + #define MSG_UBL_CUSTOM_BED_TEMP _UxGT("Bed Temp") + #endif + #ifndef MSG_UBL_SET_BED_TEMP + #define MSG_UBL_SET_BED_TEMP _UxGT("Bed Temp") + #endif + #ifndef MSG_UBL_CUSTOM_HOTEND_TEMP + #define MSG_UBL_CUSTOM_HOTEND_TEMP _UxGT("Hotend Temp") + #endif + #ifndef MSG_UBL_SET_HOTEND_TEMP + #define MSG_UBL_SET_HOTEND_TEMP _UxGT("Hotend Temp") + #endif + #ifndef MSG_UBL_EDIT_CUSTOM_MESH + #define MSG_UBL_EDIT_CUSTOM_MESH _UxGT("Edit Custom Mesh") + #endif + #ifndef MSG_UBL_BUILD_CUSTOM_MESH + #define MSG_UBL_BUILD_CUSTOM_MESH _UxGT("Build Custom Mesh") + #endif + #ifndef MSG_UBL_BUILD_MESH_MENU + #define MSG_UBL_BUILD_MESH_MENU _UxGT("Build Mesh") + #endif + #ifndef MSG_UBL_BUILD_PLA_MESH + #define MSG_UBL_BUILD_PLA_MESH _UxGT("Build PLA Mesh") + #endif + #ifndef MSG_UBL_BUILD_ABS_MESH + #define MSG_UBL_BUILD_ABS_MESH _UxGT("Build ABS Mesh") + #endif + #ifndef MSG_UBL_BUILD_COLD_MESH + #define MSG_UBL_BUILD_COLD_MESH _UxGT("Build Cold Mesh") + #endif + #ifndef MSG_UBL_MESH_HEIGHT_ADJUST + #define MSG_UBL_MESH_HEIGHT_ADJUST _UxGT("Adjust Mesh Height") + #endif + #ifndef MSG_UBL_MESH_HEIGHT_AMOUNT + #define MSG_UBL_MESH_HEIGHT_AMOUNT _UxGT("Height Amount") + #endif + #ifndef MSG_UBL_VALIDATE_MESH_MENU + #define MSG_UBL_VALIDATE_MESH_MENU _UxGT("Validate Mesh") + #endif + #ifndef MSG_UBL_VALIDATE_PLA_MESH + #define MSG_UBL_VALIDATE_PLA_MESH _UxGT("Validate PLA Mesh") + #endif + #ifndef MSG_UBL_VALIDATE_ABS_MESH + #define MSG_UBL_VALIDATE_ABS_MESH _UxGT("Validate ABS Mesh") + #endif + #ifndef MSG_UBL_VALIDATE_CUSTOM_MESH + #define MSG_UBL_VALIDATE_CUSTOM_MESH _UxGT("Validate Custom Mesh") + #endif + #ifndef MSG_UBL_CONTINUE_MESH + #define MSG_UBL_CONTINUE_MESH _UxGT("Continue Bed Mesh") + #endif + #ifndef MSG_UBL_MESH_LEVELING + #define MSG_UBL_MESH_LEVELING _UxGT("Mesh Leveling") + #endif + #ifndef MSG_UBL_3POINT_MESH_LEVELING + #define MSG_UBL_3POINT_MESH_LEVELING _UxGT("3-Point Leveling") + #endif + #ifndef MSG_UBL_GRID_MESH_LEVELING + #define MSG_UBL_GRID_MESH_LEVELING _UxGT("Grid Mesh Leveling") + #endif + #ifndef MSG_UBL_MESH_LEVEL + #define MSG_UBL_MESH_LEVEL _UxGT("Level Mesh") + #endif + #ifndef MSG_UBL_SIDE_POINTS + #define MSG_UBL_SIDE_POINTS _UxGT("Side Points") + #endif + #ifndef MSG_UBL_MAP_TYPE + #define MSG_UBL_MAP_TYPE _UxGT("Map Type") + #endif + #ifndef MSG_UBL_OUTPUT_MAP + #define MSG_UBL_OUTPUT_MAP _UxGT("Output Mesh Map") + #endif + #ifndef MSG_UBL_OUTPUT_MAP_HOST + #define MSG_UBL_OUTPUT_MAP_HOST _UxGT("Output for Host") + #endif + #ifndef MSG_UBL_OUTPUT_MAP_CSV + #define MSG_UBL_OUTPUT_MAP_CSV _UxGT("Output for CSV") + #endif + #ifndef MSG_UBL_INFO_UBL + #define MSG_UBL_INFO_UBL _UxGT("Output UBL Info") + #endif + #ifndef MSG_UBL_EDIT_MESH_MENU + #define MSG_UBL_EDIT_MESH_MENU _UxGT("Edit Mesh") + #endif + #ifndef MSG_UBL_FILLIN_AMOUNT + #define MSG_UBL_FILLIN_AMOUNT _UxGT("Fill-in Amount") + #endif + #ifndef MSG_UBL_MANUAL_FILLIN + #define MSG_UBL_MANUAL_FILLIN _UxGT("Manual Fill-in") + #endif + #ifndef MSG_UBL_SMART_FILLIN + #define MSG_UBL_SMART_FILLIN _UxGT("Smart Fill-in") + #endif + #ifndef MSG_UBL_FILLIN_MESH + #define MSG_UBL_FILLIN_MESH _UxGT("Fill-in Mesh") + #endif + #ifndef MSG_UBL_INVALIDATE_ALL + #define MSG_UBL_INVALIDATE_ALL _UxGT("Invalidate All") + #endif + #ifndef MSG_UBL_INVALIDATE_CLOSEST + #define MSG_UBL_INVALIDATE_CLOSEST _UxGT("Invalidate Closest") + #endif + #ifndef MSG_UBL_FINE_TUNE_ALL + #define MSG_UBL_FINE_TUNE_ALL _UxGT("Fine Tune All") + #endif + #ifndef MSG_UBL_FINE_TUNE_CLOSEST + #define MSG_UBL_FINE_TUNE_CLOSEST _UxGT("Fine Tune Closest") + #endif + #ifndef MSG_UBL_STORAGE_MESH_MENU + #define MSG_UBL_STORAGE_MESH_MENU _UxGT("Mesh Storage") + #endif + #ifndef MSG_UBL_STORAGE_SLOT + #define MSG_UBL_STORAGE_SLOT _UxGT("Memory Slot") + #endif + #ifndef MSG_UBL_LOAD_MESH + #define MSG_UBL_LOAD_MESH _UxGT("Load Bed Mesh") + #endif + #ifndef MSG_UBL_SAVE_MESH + #define MSG_UBL_SAVE_MESH _UxGT("Save Bed Mesh") + #endif +#endif // AUTO_BED_LEVELING_UBL + #ifndef MSG_MOVING #define MSG_MOVING _UxGT("Moving...") #endif @@ -324,6 +463,9 @@ #ifndef MSG_RESTORE_FAILSAFE #define MSG_RESTORE_FAILSAFE _UxGT("Restore failsafe") #endif +#ifndef MSG_INIT_EEPROM + #define MSG_INIT_EEPROM _UxGT("Initalize Memory") +#endif #ifndef MSG_REFRESH #define MSG_REFRESH _UxGT("Refresh") #endif @@ -590,7 +732,6 @@ #ifndef MSG_INFO_PSU #define MSG_INFO_PSU _UxGT("Power Supply") #endif - #ifndef MSG_DRIVE_STRENGTH #define MSG_DRIVE_STRENGTH _UxGT("Drive Strength") #endif diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 7a174f702..6e794a3b0 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -55,12 +55,16 @@ extern float probe_pt(float x, float y, bool, int); extern bool set_probe_deployed(bool); void smart_fill_mesh(); + float measure_business_card_thickness(float &in_height); + void manually_probe_remaining_mesh(const float &lx, const float &ly, float &z_clearance, const float &card_thickness, const bool do_ubl_mesh_map); bool ProbeStay = true; - #define SIZE_OF_LITTLE_RAISE 0 + #define SIZE_OF_LITTLE_RAISE 1 #define BIG_RAISE_NOT_NEEDED 0 - extern void lcd_quick_feedback(); + extern void lcd_status_screen(); + typedef void (*screenFunc_t)(); + extern void lcd_goto_screen(screenFunc_t screen, const uint32_t encoder = 0); /** * G29: Unified Bed Leveling by Roxy @@ -444,7 +448,7 @@ y_pos = current_position[Y_AXIS]; } - const float height = code_seen('H') && code_has_value() ? code_value_float() : Z_CLEARANCE_BETWEEN_PROBES; + float height = code_seen('H') && code_has_value() ? code_value_float() : Z_CLEARANCE_BETWEEN_PROBES; if (code_seen('B')) { card_thickness = code_has_value() ? code_value_float() : measure_business_card_thickness(height); @@ -876,7 +880,7 @@ SERIAL_PROTOCOLLNPGM(" and take a measurement."); } - float measure_business_card_thickness(const float &in_height) { + float measure_business_card_thickness(float &in_height) { ubl.has_control_of_lcd_panel = true; ubl.save_ubl_active_state_and_disable(); // Disable bed level correction for probing @@ -886,6 +890,8 @@ stepper.synchronize(); SERIAL_PROTOCOLPGM("Place shim under nozzle."); + LCD_MESSAGEPGM("Place shim & measure"); + lcd_goto_screen(lcd_status_screen); say_and_take_a_measurement(); const float z1 = use_encoder_wheel_to_measure_point(); @@ -893,29 +899,33 @@ stepper.synchronize(); SERIAL_PROTOCOLPGM("Remove shim."); + LCD_MESSAGEPGM("Remove & measure"); + say_and_take_a_measurement(); const float z2 = use_encoder_wheel_to_measure_point(); - do_blocking_move_to_z(current_position[Z_AXIS] + SIZE_OF_LITTLE_RAISE); + do_blocking_move_to_z(current_position[Z_AXIS] + Z_CLEARANCE_BETWEEN_PROBES); if (g29_verbose_level > 1) { SERIAL_PROTOCOLPGM("Business Card is: "); SERIAL_PROTOCOL_F(abs(z1 - z2), 6); SERIAL_PROTOCOLLNPGM("mm thick."); } + in_height = current_position[Z_AXIS]; // do manual probing at lower height ubl.has_control_of_lcd_panel = false; ubl.restore_ubl_active_state_and_leave(); return abs(z1 - z2); } - void manually_probe_remaining_mesh(const float &lx, const float &ly, const float &z_clearance, const float &card_thickness, const bool do_ubl_mesh_map) { + void manually_probe_remaining_mesh(const float &lx, const float &ly, float &z_clearance, const float &card_thickness, const bool do_ubl_mesh_map) { ubl.has_control_of_lcd_panel = true; ubl.save_ubl_active_state_and_disable(); // we don't do bed level correction because we want the raw data when we probe do_blocking_move_to_z(z_clearance); do_blocking_move_to_xy(lx, ly); + lcd_goto_screen(lcd_status_screen); float last_x = -9999.99, last_y = -9999.99; mesh_index_pair location; do { @@ -943,6 +953,7 @@ do_blocking_move_to_z(current_position[Z_AXIS] + SIZE_OF_LITTLE_RAISE); else do_blocking_move_to_z(z_clearance); + LCD_MESSAGEPGM("Moving to next"); do_blocking_move_to_xy(xProbe, yProbe); @@ -953,6 +964,8 @@ ubl.has_control_of_lcd_panel = true; if (do_ubl_mesh_map) ubl.display_map(map_type); // show user where we're probing + if (code_seen('B')) {LCD_MESSAGEPGM("Place shim & measure");} + else {LCD_MESSAGEPGM("Measure");} while (ubl_lcd_clicked()) delay(50); // wait for user to release encoder wheel delay(50); // debounce @@ -1024,6 +1037,7 @@ repeat_flag = code_seen('R'); if (repeat_flag) { repetition_cnt = code_has_value() ? code_value_int() : (GRID_MAX_POINTS_X) * (GRID_MAX_POINTS_Y); + repetition_cnt = min(repetition_cnt, (GRID_MAX_POINTS_X) * (GRID_MAX_POINTS_Y)); if (repetition_cnt < 1) { SERIAL_PROTOCOLLNPGM("?(R)epetition count invalid (1+).\n"); return UBL_ERR; @@ -1056,7 +1070,6 @@ SERIAL_PROTOCOLLNPGM("Both X & Y locations must be specified.\n"); err_flag = true; } - if (!WITHIN(RAW_X_POSITION(x_pos), X_MIN_POS, X_MAX_POS)) { SERIAL_PROTOCOLLNPGM("Invalid X location specified.\n"); err_flag = true; @@ -1422,8 +1435,7 @@ do_blocking_move_to_xy(lx, ly); do { location = find_closest_mesh_point_of_type(SET_IN_BITMAP, lx, ly, USE_NOZZLE_AS_REFERENCE, not_done, false); - // It doesn't matter if the probe can't reach this - // location. This is a manual edit of the Mesh Point. + if (location.x_index < 0 && location.y_index < 0) continue; // abort if we can't find any more points. bit_clear(not_done, location.x_index, location.y_index); // Mark this location as 'adjusted' so we will find a @@ -1612,7 +1624,7 @@ SERIAL_ECHOPGM("Could not complete LSF!"); return; } - + if (g29_verbose_level > 3) { SERIAL_ECHOPGM("LSF Results A="); SERIAL_PROTOCOL_F(lsf_results.A, 7); diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 60771a5f5..29eb269bd 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -1674,6 +1674,348 @@ void kill_screen(const char* lcd_msg) { END_MENU(); } + #if ENABLED(AUTO_BED_LEVELING_UBL) + + void _lcd_ubl_level_bed(); + + int UBL_STORAGE_SLOT = 0; + int CUSTOM_BED_TEMP = 50; + int CUSTOM_HOTEND_TEMP = 190; + int SIDE_POINTS = 3; + int UBL_FILLIN_AMOUNT = 5; + int UBL_HEIGHT_AMOUNT; + int map_type; + + char UBL_LCD_GCODE [30]; + + /** + * UBL Build Custom Mesh Command + */ + void _lcd_ubl_build_custom_mesh() { + enqueue_and_echo_command("G28"); + #if (WATCH_THE_BED) + sprintf_P(UBL_LCD_GCODE, PSTR("M190 S%i"), CUSTOM_BED_TEMP); + enqueue_and_echo_command(UBL_LCD_GCODE); + #endif + sprintf_P(UBL_LCD_GCODE, PSTR("M109 S%i"), CUSTOM_HOTEND_TEMP); + enqueue_and_echo_command(UBL_LCD_GCODE); + enqueue_and_echo_command("G29 P1"); + } + + /** + * UBL Custom Mesh submenu + */ + void _lcd_ubl_custom_mesh() { + START_MENU(); + MENU_BACK(MSG_UBL_BUILD_MESH_MENU); + MENU_ITEM_EDIT(int3, MSG_UBL_CUSTOM_HOTEND_TEMP, &CUSTOM_HOTEND_TEMP, EXTRUDE_MINTEMP, (HEATER_0_MAXTEMP - 10)); + #if (WATCH_THE_BED) + MENU_ITEM_EDIT(int3, MSG_UBL_CUSTOM_BED_TEMP, &CUSTOM_BED_TEMP, BED_MINTEMP, (BED_MAXTEMP - 5)); + #endif + MENU_ITEM(function, MSG_UBL_BUILD_CUSTOM_MESH, _lcd_ubl_build_custom_mesh); + END_MENU(); + } + + /** + * UBL Adjust Mesh Height Command + */ + void _lcd_ubl_adjust_height_cmd() { + if (UBL_HEIGHT_AMOUNT < 0) { + // Convert to positive for the `sprintf_P` string. + UBL_HEIGHT_AMOUNT = (UBL_HEIGHT_AMOUNT - (UBL_HEIGHT_AMOUNT * 2)); // Convert to positive + sprintf_P(UBL_LCD_GCODE, PSTR("G29 N Z-.%i"), UBL_HEIGHT_AMOUNT); + // Convert back to negative to preserve the user setting. + UBL_HEIGHT_AMOUNT = (UBL_HEIGHT_AMOUNT - (UBL_HEIGHT_AMOUNT * 2)); // Convert back to negative + } + else { + sprintf_P(UBL_LCD_GCODE, PSTR("G29 N Z.%i"), UBL_HEIGHT_AMOUNT); + } + enqueue_and_echo_command(UBL_LCD_GCODE); + } + + /** + * UBL Adjust Mesh Height submenu + */ + void _lcd_ubl_height_adjust_menu() { + START_MENU(); + MENU_BACK(MSG_UBL_EDIT_MESH_MENU); + MENU_ITEM_EDIT(int3, MSG_UBL_MESH_HEIGHT_AMOUNT, &UBL_HEIGHT_AMOUNT, -9, 9); + MENU_ITEM(function, MSG_UBL_MESH_HEIGHT_ADJUST, _lcd_ubl_adjust_height_cmd); + MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); + END_MENU(); + } + + /** + * UBL Edit Mesh submenu + */ + void _lcd_ubl_edit_mesh() { + START_MENU(); + MENU_BACK(MSG_UBL_TOOLS); + MENU_BACK(MSG_UBL_LEVEL_BED); + MENU_ITEM(gcode, MSG_UBL_FINE_TUNE_ALL, PSTR("G29 P4 R O")); + MENU_ITEM(gcode, MSG_UBL_FINE_TUNE_CLOSEST, PSTR("G29 P4 O")); + MENU_ITEM(submenu, MSG_UBL_MESH_HEIGHT_ADJUST, _lcd_ubl_height_adjust_menu); + MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); + END_MENU(); + } + + /** + * UBL Validate Custom Mesh Command + */ + void _lcd_ubl_validate_custom_mesh() { + enqueue_and_echo_command("G28"); + #if (WATCH_THE_BED) + sprintf_P(UBL_LCD_GCODE, PSTR("G26 C B%i H%i P"), CUSTOM_BED_TEMP, CUSTOM_HOTEND_TEMP); + #else + sprintf_P(UBL_LCD_GCODE, PSTR("G26 C B0 H%i P"), CUSTOM_HOTEND_TEMP); + #endif + enqueue_and_echo_command(UBL_LCD_GCODE); + } + + /** + * UBL Validate Mesh submenu + */ + void _lcd_ubl_validate_mesh() { + START_MENU(); + MENU_BACK(MSG_UBL_TOOLS); + #if (WATCH_THE_BED) + MENU_ITEM(gcode, MSG_UBL_VALIDATE_PLA_MESH, PSTR("G28\nG26 C B" STRINGIFY(PREHEAT_1_TEMP_BED) + " H" STRINGIFY(PREHEAT_1_TEMP_HOTEND) " P")); + MENU_ITEM(gcode, MSG_UBL_VALIDATE_ABS_MESH, PSTR("G28\nG26 C B" STRINGIFY(PREHEAT_2_TEMP_BED) + " H" STRINGIFY(PREHEAT_2_TEMP_HOTEND) " P")); + #else + MENU_ITEM(gcode, MSG_UBL_VALIDATE_PLA_MESH, PSTR("G28\nG26 C B0 H" STRINGIFY(PREHEAT_1_TEMP_HOTEND) " P")); + MENU_ITEM(gcode, MSG_UBL_VALIDATE_ABS_MESH, PSTR("G28\nG26 C B0 H" STRINGIFY(PREHEAT_2_TEMP_HOTEND) " P")); + #endif + MENU_ITEM(function, MSG_UBL_VALIDATE_CUSTOM_MESH, _lcd_ubl_validate_custom_mesh); + MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); + END_MENU(); + } + + /** + * UBL Grid Leveling Command + */ + void _lcd_ubl_grid_level_cmd() { + sprintf_P(UBL_LCD_GCODE, PSTR("G29 J%i"), SIDE_POINTS); + enqueue_and_echo_command(UBL_LCD_GCODE); + } + + /** + * UBL Grid Leveling submenu + */ + void _lcd_ubl_grid_level() { + START_MENU(); + MENU_BACK(MSG_UBL_TOOLS); + MENU_ITEM_EDIT(int3, MSG_UBL_SIDE_POINTS, &SIDE_POINTS, 2, 6); + MENU_ITEM(function, MSG_UBL_MESH_LEVEL, _lcd_ubl_grid_level_cmd); + END_MENU(); + } + + /** + * UBL Mesh Leveling submenu + */ + void _lcd_ubl_mesh_leveling() { + START_MENU(); + MENU_BACK(MSG_UBL_TOOLS); + MENU_ITEM(gcode, MSG_UBL_3POINT_MESH_LEVELING, PSTR("G29 T")); + MENU_ITEM(submenu, MSG_UBL_GRID_MESH_LEVELING, _lcd_ubl_grid_level); + MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); + END_MENU(); + } + + /** + * UBL Fill-in Amount Mesh Command + */ + void _lcd_ubl_fillin_amount_cmd() { + sprintf_P(UBL_LCD_GCODE, PSTR("G29 P3 R C.%i N"), UBL_FILLIN_AMOUNT); + enqueue_and_echo_command(UBL_LCD_GCODE); + } + + /** + * UBL Smart Fill-in Command + */ + void _lcd_ubl_smart_fillin_cmd() { + sprintf_P(UBL_LCD_GCODE, PSTR("G29 P3 N O%i"), map_type); + enqueue_and_echo_command(UBL_LCD_GCODE); + } + + /** + * UBL Fill-in Mesh submenu + */ + void _lcd_ubl_fillin_menu() { + START_MENU(); + MENU_BACK(MSG_UBL_BUILD_MESH_MENU); + MENU_ITEM_EDIT(int3, MSG_UBL_FILLIN_AMOUNT, &UBL_FILLIN_AMOUNT, 0, 9); + MENU_ITEM(function, MSG_UBL_FILLIN_MESH, _lcd_ubl_fillin_amount_cmd); + MENU_ITEM(function, MSG_UBL_SMART_FILLIN, _lcd_ubl_smart_fillin_cmd); + MENU_ITEM(gcode, MSG_UBL_MANUAL_FILLIN, PSTR("G29 P2 B O")); + MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); + END_MENU(); + } + + void _lcd_ubl_invalidate() { + ubl.invalidate(); + SERIAL_PROTOCOLLNPGM("Mesh invalidated."); + } + + /** + * UBL Build Mesh submenu + */ + void _lcd_ubl_build_mesh() { + int GRID_NUM_POINTS = GRID_MAX_POINTS_X * GRID_MAX_POINTS_Y ; + START_MENU(); + MENU_BACK(MSG_UBL_TOOLS); + #if (WATCH_THE_BED) + MENU_ITEM(gcode, MSG_UBL_BUILD_PLA_MESH, PSTR("G28\nM190 S" STRINGIFY(PREHEAT_1_TEMP_BED) + "\nM109 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) "\nG29 P1\nM104 S0\nM140 S0")); + MENU_ITEM(gcode, MSG_UBL_BUILD_ABS_MESH, PSTR("G28\nM190 S" STRINGIFY(PREHEAT_1_TEMP_BED) + "\nM109 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) "\nG29 P1\nM104 S0\nM140 S0")); + #else + MENU_ITEM(gcode, MSG_UBL_BUILD_PLA_MESH, PSTR("G28\nM109 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) + "\nG29 P1\nM104 S0")); + MENU_ITEM(gcode, MSG_UBL_BUILD_ABS_MESH, PSTR("G28\nM109 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) + "\nG29 P1\nM104 S0")); + #endif + MENU_ITEM(submenu, MSG_UBL_BUILD_CUSTOM_MESH, _lcd_ubl_custom_mesh); + MENU_ITEM(gcode, MSG_UBL_BUILD_COLD_MESH, PSTR("G28\nG29 P1")); + MENU_ITEM(submenu, MSG_UBL_FILLIN_MESH, _lcd_ubl_fillin_menu); + MENU_ITEM(gcode, MSG_UBL_CONTINUE_MESH, PSTR("G29 P1 C")); + MENU_ITEM(function, MSG_UBL_INVALIDATE_ALL, _lcd_ubl_invalidate); + MENU_ITEM(gcode, MSG_UBL_INVALIDATE_CLOSEST, PSTR("G29 I")); + MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); + END_MENU(); + } + + /** + * UBL Load Mesh Command + */ + void _lcd_ubl_load_mesh_cmd() { + sprintf_P(UBL_LCD_GCODE, PSTR("G29 N L%i"), UBL_STORAGE_SLOT); + enqueue_and_echo_command(UBL_LCD_GCODE); + } + + /** + * UBL Save Mesh Command + */ + void _lcd_ubl_save_mesh_cmd() { + sprintf_P(UBL_LCD_GCODE, PSTR("G29 N S%i"), UBL_STORAGE_SLOT); + enqueue_and_echo_command(UBL_LCD_GCODE); + } + + /** + * UBL Mesh Storage submenu + */ + void _lcd_ubl_storage_mesh() { + START_MENU(); + MENU_BACK(MSG_UBL_LEVEL_BED); + MENU_ITEM_EDIT(int3, MSG_UBL_STORAGE_SLOT, &UBL_STORAGE_SLOT, 0, 9); + MENU_ITEM(function, MSG_UBL_LOAD_MESH, _lcd_ubl_load_mesh_cmd); + MENU_ITEM(function, MSG_UBL_SAVE_MESH, _lcd_ubl_save_mesh_cmd); + END_MENU(); + } + + /** + * UBL Output map Command + */ + void _lcd_ubl_output_map_cmd() { + sprintf_P(UBL_LCD_GCODE, PSTR("G29 N O%i"), map_type); + enqueue_and_echo_command(UBL_LCD_GCODE); + } + + /** + * UBL Output map submenu + */ + void _lcd_ubl_output_map() { + START_MENU(); + MENU_BACK(MSG_UBL_LEVEL_BED); + MENU_ITEM_EDIT(int3, MSG_UBL_MAP_TYPE, &map_type, 0, 1); + if (map_type == 0) MENU_ITEM(function, MSG_UBL_OUTPUT_MAP_HOST, _lcd_ubl_output_map_cmd); + if (map_type == 1) MENU_ITEM(function, MSG_UBL_OUTPUT_MAP_CSV, _lcd_ubl_output_map_cmd); + END_MENU(); + } + + /** + * UBL Tools submenu + */ + void _lcd_ubl_tools_menu() { + START_MENU(); + MENU_BACK(MSG_UBL_LEVEL_BED); + MENU_ITEM(submenu, MSG_UBL_BUILD_MESH_MENU, _lcd_ubl_build_mesh); + MENU_ITEM(submenu, MSG_UBL_VALIDATE_MESH_MENU, _lcd_ubl_validate_mesh); + MENU_ITEM(submenu, MSG_UBL_EDIT_MESH_MENU, _lcd_ubl_edit_mesh); + MENU_ITEM(submenu, MSG_UBL_MESH_LEVELING, _lcd_ubl_mesh_leveling); + END_MENU(); + } + + /** + * UBL System submenu + * + * Prepare + * - Unified Bed Leveling + * - Activate UBL + * - Deactivate UBL + * - Mesh Storage + * Memory Slot: + * Load Bed Mesh + * Save Bed Mesh + * - Output Map + * Map Type: + * Output Bed Mesh Host / Output Bed Mesh CSV + * - UBL Tools + * - Build Mesh + * Build PLA Mesh + * Build ABS Mesh + * - Build Custom Mesh + * Hotend Temp: + * Bed Temp: + * Build Custom Mesh + * Info Screen + * - Build Cold Mesh + * - Fill-in Mesh + * Fill-in Mesh + * Smart Fill-in + * Manual Fill-in + * Info Screen + * Continue Bed Mesh + * Invalidate All + * Invalidate Closest + * - Validate Mesh + * PLA Mesh Validation + * ABS Mesh Validation + * - Custom Mesh Validation + * Hotend Temp: + * Bed Temp: + * Validate Mesh + * Info Screen + * - Edit Mesh + * Fine Tune All + * Fine Tune Closest + * - Adjust Mesh Height + * Height Amount: + * Adjust Mesh Height + * Info Screen + * - Mesh Leveling + * 3-Point Mesh Leveling + * - Grid Mesh Leveling + * Side points: + * Level Mesh + * Info Screen + * - Output UBL Info + */ + + void _lcd_ubl_level_bed() { + START_MENU(); + MENU_BACK(MSG_PREPARE); + MENU_ITEM(gcode, MSG_UBL_ACTIVATE_MESH, PSTR("G29 A N")); + MENU_ITEM(gcode, MSG_UBL_DEACTIVATE_MESH, PSTR("G29 D N")); + MENU_ITEM(submenu, MSG_UBL_STORAGE_MESH_MENU, _lcd_ubl_storage_mesh); + MENU_ITEM(submenu, MSG_UBL_OUTPUT_MAP, _lcd_ubl_output_map); + MENU_ITEM(submenu, MSG_UBL_TOOLS, _lcd_ubl_tools_menu); + MENU_ITEM(gcode, MSG_UBL_INFO_UBL, PSTR("G29 W N")); + END_MENU(); + } + #endif + #endif // LCD_BED_LEVELING || HAS_ABL /** @@ -1716,7 +2058,11 @@ void kill_screen(const char* lcd_msg) { #if ENABLED(PROBE_MANUALLY) if (!g29_in_progress) #endif - MENU_ITEM(submenu, MSG_LEVEL_BED, lcd_level_bed); + #if ENABLED(AUTO_BED_LEVELING_UBL) + MENU_ITEM(submenu, MSG_UBL_LEVEL_BED, _lcd_ubl_level_bed); + #else + MENU_ITEM(submenu, MSG_LEVEL_BED, lcd_level_bed); + #endif #endif @@ -2158,7 +2504,7 @@ void kill_screen(const char* lcd_msg) { #endif MENU_ITEM(function, MSG_RESTORE_FAILSAFE, lcd_factory_settings); - END_MENU(); + END_MENU(); } /** From 4da14b14f4fe511c9655181704bb27d7efc9079c Mon Sep 17 00:00:00 2001 From: Brian Date: Wed, 10 May 2017 13:37:35 -0400 Subject: [PATCH 045/189] UBL Cleanup/Bugfix - Fix bug in ubl_line_to_destination - Improve/fix output of some ubl.h functions --- Marlin/ubl.h | 13 ++++++++----- Marlin/ubl_motion.cpp | 10 ++++------ 2 files changed, 12 insertions(+), 11 deletions(-) diff --git a/Marlin/ubl.h b/Marlin/ubl.h index 73f9b1c0e..a6516ba8a 100644 --- a/Marlin/ubl.h +++ b/Marlin/ubl.h @@ -160,7 +160,8 @@ unified_bed_leveling(); FORCE_INLINE void set_z(const int8_t px, const int8_t py, const float &z) { z_values[px][py] = z; } - int8_t get_cell_index_x(const float &x) { + + int8_t get_cell_index_x(const float &x) { const int8_t cx = (x - (UBL_MESH_MIN_X)) * (1.0 / (MESH_X_DIST)); return constrain(cx, 0, (GRID_MAX_POINTS_X) - 1); // -1 is appropriate if we want all movement to the X_MAX } // position. But with this defined this way, it is possible @@ -210,7 +211,8 @@ */ inline float z_correction_for_x_on_horizontal_mesh_line(const float &lx0, const int x1_i, const int yi) { if (!WITHIN(x1_i, 0, GRID_MAX_POINTS_X - 1) || !WITHIN(yi, 0, GRID_MAX_POINTS_Y - 1)) { - SERIAL_ECHOPAIR("? in z_correction_for_x_on_horizontal_mesh_line(lx0=", lx0); + serialprintPGM( !WITHIN(x1_i, 0, GRID_MAX_POINTS_X - 1) ? PSTR("x1l_i") : PSTR("yi") ); + SERIAL_ECHOPAIR(" out of bounds in z_correction_for_x_on_horizontal_mesh_line(lx0=", lx0); SERIAL_ECHOPAIR(",x1_i=", x1_i); SERIAL_ECHOPAIR(",yi=", yi); SERIAL_CHAR(')'); @@ -229,9 +231,10 @@ // inline float z_correction_for_y_on_vertical_mesh_line(const float &ly0, const int xi, const int y1_i) { if (!WITHIN(xi, 0, GRID_MAX_POINTS_X - 1) || !WITHIN(y1_i, 0, GRID_MAX_POINTS_Y - 1)) { - SERIAL_ECHOPAIR("? in get_z_correction_along_vertical_mesh_line_at_specific_x(ly0=", ly0); - SERIAL_ECHOPAIR(", x1_i=", xi); - SERIAL_ECHOPAIR(", yi=", y1_i); + serialprintPGM( !WITHIN(xi, 0, GRID_MAX_POINTS_X - 1) ? PSTR("xi") : PSTR("yl_i") ); + SERIAL_ECHOPAIR(" out of bounds in z_correction_for_y_on_vertical_mesh_line(ly0=", ly0); + SERIAL_ECHOPAIR(", xi=", xi); + SERIAL_ECHOPAIR(", y1_i=", y1_i); SERIAL_CHAR(')'); SERIAL_EOL; return NAN; diff --git a/Marlin/ubl_motion.cpp b/Marlin/ubl_motion.cpp index 5fbf141ab..bdc8de15a 100644 --- a/Marlin/ubl_motion.cpp +++ b/Marlin/ubl_motion.cpp @@ -231,8 +231,8 @@ const float m = dy / dx, c = start[Y_AXIS] - m * start[X_AXIS]; - const bool inf_normalized_flag = isinf(e_normalized_dist), - inf_m_flag = isinf(m); + const bool inf_normalized_flag = (isinf(e_normalized_dist) != 0), + inf_m_flag = (isinf(m) != 0); /** * This block handles vertical lines. These are lines that stay within the same * X Cell column. They do not need to be perfectly vertical. They just can @@ -403,9 +403,7 @@ // as a vertical line move above.) if (left_flag == (x > next_mesh_line_x)) { // Check if we hit the Y line first - // // Yes! Crossing a Y Mesh Line next - // float z0 = ubl.z_correction_for_x_on_horizontal_mesh_line(x, current_xi - left_flag, current_yi + dyi); z0 *= ubl.fade_scaling_factor_for_z(end[Z_AXIS]); @@ -433,9 +431,7 @@ yi_cnt--; } else { - // // Yes! Crossing a X Mesh Line next - // float z0 = ubl.z_correction_for_y_on_vertical_mesh_line(y, current_xi + dxi, current_yi - down_flag); z0 *= ubl.fade_scaling_factor_for_z(end[Z_AXIS]); @@ -463,6 +459,8 @@ current_xi += dxi; xi_cnt--; } + + if (xi_cnt < 0 || yi_cnt < 0) break; // we've gone too far, so exit the loop and move on to FINAL_MOVE } if (ubl.g26_debug_flag) From 9c5957fc774f384b9db8f97fc1e97f3fcc7aefef Mon Sep 17 00:00:00 2001 From: Brian Date: Wed, 10 May 2017 15:19:06 -0400 Subject: [PATCH 046/189] G26: Add 0.5mm Z-bump between circles to minimize pattern scraping --- Marlin/G26_Mesh_Validation_Tool.cpp | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/Marlin/G26_Mesh_Validation_Tool.cpp b/Marlin/G26_Mesh_Validation_Tool.cpp index 3d93baa91..33f759077 100644 --- a/Marlin/G26_Mesh_Validation_Tool.cpp +++ b/Marlin/G26_Mesh_Validation_Tool.cpp @@ -605,13 +605,19 @@ return print_line_from_here_to_there(ex, ey, ez, sx, sy, sz); } - // Decide whether to retract. + // Decide whether to retract & bump if (dist_start > 2.0) { retract_filament(destination); //if (ubl.g26_debug_flag) SERIAL_ECHOLNPGM(" filament retracted."); + + //if (ubl.g26_debug_flag) SERIAL_ECHOLNPGM(" Z bumping by 0.500 to minimize scraping."); + //todo: parameterize the bump height with a define + move_to(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS]+0.500, 0.0); // Z bump to minimize scraping + move_to(sx, sy, sz+0.500, 0.0); // Get to the starting point with no extrusion while bumped } - move_to(sx, sy, sz, 0.0); // Get to the starting point with no extrusion + + move_to(sx, sy, sz, 0.0); // Get to the starting point with no extrusion / un-Z bump const float e_pos_delta = line_length * g26_e_axis_feedrate * extrusion_multiplier; From f7a201b0d0292d0bfd9647bd6cdb26c4bb35fd4d Mon Sep 17 00:00:00 2001 From: Brian Date: Wed, 10 May 2017 15:51:44 -0400 Subject: [PATCH 047/189] G26: Add 'Repeat' Option - Allows for specifying number of points to print/validate, using 'R' code like with G29 P4 Rx - Moved the code for Random to 'M' so we could be consistent with G29 P4 - G26 instructions indenting/cleanup --- Marlin/G26_Mesh_Validation_Tool.cpp | 88 +++++++++++++++++------------ 1 file changed, 52 insertions(+), 36 deletions(-) diff --git a/Marlin/G26_Mesh_Validation_Tool.cpp b/Marlin/G26_Mesh_Validation_Tool.cpp index 3d93baa91..95e038d4e 100644 --- a/Marlin/G26_Mesh_Validation_Tool.cpp +++ b/Marlin/G26_Mesh_Validation_Tool.cpp @@ -66,54 +66,58 @@ * the user can specify the X and Y position of interest with command parameters. This allows the user to * focus on a particular area of the Mesh where attention is needed. * - * B # Bed Set the Bed Temperature. If not specified, a default of 60 C. will be assumed. + * B # Bed Set the Bed Temperature. If not specified, a default of 60 C. will be assumed. * - * C Current When searching for Mesh Intersection points to draw, use the current nozzle location - * as the base for any distance comparison. + * C Current When searching for Mesh Intersection points to draw, use the current nozzle location + as the base for any distance comparison. * - * D Disable Disable the Unified Bed Leveling System. In the normal case the user is invoking this - * command to see how well a Mesh as been adjusted to match a print surface. In order to do - * this the Unified Bed Leveling System is turned on by the G26 command. The D parameter - * alters the command's normal behaviour and disables the Unified Bed Leveling System even if - * it is on. + * D Disable Disable the Unified Bed Leveling System. In the normal case the user is invoking this + * command to see how well a Mesh as been adjusted to match a print surface. In order to do + * this the Unified Bed Leveling System is turned on by the G26 command. The D parameter + * alters the command's normal behaviour and disables the Unified Bed Leveling System even if + * it is on. * - * H # Hotend Set the Nozzle Temperature. If not specified, a default of 205 C. will be assumed. + * H # Hotend Set the Nozzle Temperature. If not specified, a default of 205 C. will be assumed. * - * F # Filament Used to specify the diameter of the filament being used. If not specified - * 1.75mm filament is assumed. If you are not getting acceptable results by using the - * 'correct' numbers, you can scale this number up or down a little bit to change the amount - * of filament that is being extruded during the printing of the various lines on the bed. + * F # Filament Used to specify the diameter of the filament being used. If not specified + * 1.75mm filament is assumed. If you are not getting acceptable results by using the + * 'correct' numbers, you can scale this number up or down a little bit to change the amount + * of filament that is being extruded during the printing of the various lines on the bed. * - * K Keep-On Keep the heaters turned on at the end of the command. + * K Keep-On Keep the heaters turned on at the end of the command. * - * L # Layer Layer height. (Height of nozzle above bed) If not specified .20mm will be used. + * L # Layer Layer height. (Height of nozzle above bed) If not specified .20mm will be used. * * Q # Multiplier Retraction Multiplier. Normally not needed. Retraction defaults to 1.0mm and - * un-retraction is at 1.2mm These numbers will be scaled by the specified amount + * un-retraction is at 1.2mm These numbers will be scaled by the specified amount * - * N # Nozzle Used to control the size of nozzle diameter. If not specified, a .4mm nozzle is assumed. - * 'n' can be used instead if your host program does not appreciate you using 'N'. + * M # Random Randomize the order that the circles are drawn on the bed. The search for the closest + * undrawn cicle is still done. But the distance to the location for each circle has a + * random number of the size specified added to it. Specifying R50 will give an interesting + * deviation from the normal behaviour on a 10 x 10 Mesh. + + * N # Nozzle Used to control the size of nozzle diameter. If not specified, a .4mm nozzle is assumed. + * 'n' can be used instead if your host program does not appreciate you using 'N'. * - * O # Ooooze How much your nozzle will Ooooze filament while getting in position to print. This - * is over kill, but using this parameter will let you get the very first 'cicle' perfect - * so you have a trophy to peel off of the bed and hang up to show how perfectly you have your - * Mesh calibrated. If not specified, a filament length of .3mm is assumed. + * O # Ooooze How much your nozzle will Ooooze filament while getting in position to print. This + * is over kill, but using this parameter will let you get the very first 'cicle' perfect + * so you have a trophy to peel off of the bed and hang up to show how perfectly you have your + * Mesh calibrated. If not specified, a filament length of .3mm is assumed. * - * P # Prime Prime the nozzle with specified length of filament. If this parameter is not - * given, no prime action will take place. If the parameter specifies an amount, that much - * will be purged before continuing. If no amount is specified the command will start - * purging filament until the user provides an LCD Click and then it will continue with - * printing the Mesh. You can carefully remove the spent filament with a needle nose - * pliers while holding the LCD Click wheel in a depressed state. + * P # Prime Prime the nozzle with specified length of filament. If this parameter is not + * given, no prime action will take place. If the parameter specifies an amount, that much + * will be purged before continuing. If no amount is specified the command will start + * purging filament until the user provides an LCD Click and then it will continue with + * printing the Mesh. You can carefully remove the spent filament with a needle nose + * pliers while holding the LCD Click wheel in a depressed state. * - * R # Random Randomize the order that the circles are drawn on the bed. The search for the closest - * undrawn cicle is still done. But the distance to the location for each circle has a - * random number of the size specified added to it. Specifying R50 will give an interesting - * deviation from the normal behaviour on a 10 x 10 Mesh. + * R # Repeat Prints the number of patterns given as a parameter, starting at the current location. + * If a parameter isn't given, every point will be printed unless G26 is interrupted. + * This works the same way that the UBL G29 P4 R parameter works. * - * X # X coordinate Specify the starting location of the drawing activity. + * X # X Coord. Specify the starting location of the drawing activity. * - * Y # Y coordinate Specify the starting location of the drawing activity. + * Y # Y Coord. Specify the starting location of the drawing activity. */ // External references @@ -176,6 +180,8 @@ static bool keep_heaters_on = false; + static int16_t g26_repeats; + /** * G26: Mesh Validation Pattern generation. * @@ -359,7 +365,7 @@ //debug_current_and_destination(PSTR("Done with current circle.")); - } while (location.x_index >= 0 && location.y_index >= 0); + } while (location.x_index >= 0 && location.y_index >= 0 && g26_repeats--); LEAVE: lcd_reset_alert_level(); @@ -722,11 +728,21 @@ } } - if (code_seen('R')) { + if (code_seen('M')) { randomSeed(millis()); random_deviation = code_has_value() ? code_value_float() : 50.0; } + if (code_seen('R')) { + g26_repeats = code_has_value() ? code_value_int() - 1 : 999; + + if (g26_repeats <= 0) { + SERIAL_PROTOCOLLNPGM("?(R)epeat value not plausible; must be greater than 0."); + return UBL_ERR; + } + } + + x_pos = current_position[X_AXIS]; y_pos = current_position[Y_AXIS]; From 26047421913b533af4f23a71909f28bc22abb146 Mon Sep 17 00:00:00 2001 From: Brian Date: Mon, 8 May 2017 18:23:17 -0400 Subject: [PATCH 048/189] Add proportional font adjustment ratio - update example configs --- Marlin/Configuration_adv.h | 10 ++++++++++ .../Cartesio/Configuration_adv.h | 10 ++++++++++ .../example_configurations/Felix/Configuration_adv.h | 10 ++++++++++ .../FolgerTech-i3-2020/Configuration_adv.h | 10 ++++++++++ .../Hephestos/Configuration_adv.h | 10 ++++++++++ .../Hephestos_2/Configuration_adv.h | 10 ++++++++++ .../example_configurations/K8200/Configuration_adv.h | 10 ++++++++++ .../example_configurations/K8400/Configuration_adv.h | 10 ++++++++++ .../RigidBot/Configuration_adv.h | 10 ++++++++++ .../example_configurations/SCARA/Configuration_adv.h | 10 ++++++++++ Marlin/example_configurations/TAZ4/Configuration_adv.h | 10 ++++++++++ .../TinyBoy2/Configuration_adv.h | 10 ++++++++++ .../example_configurations/WITBOX/Configuration_adv.h | 10 ++++++++++ .../delta/FLSUN/auto_calibrate/Configuration_adv.h | 10 ++++++++++ .../delta/FLSUN/kossel_mini/Configuration_adv.h | 10 ++++++++++ .../delta/generic/Configuration_adv.h | 10 ++++++++++ .../delta/kossel_mini/Configuration_adv.h | 10 ++++++++++ .../delta/kossel_pro/Configuration_adv.h | 10 ++++++++++ .../delta/kossel_xl/Configuration_adv.h | 10 ++++++++++ .../gCreate_gMax1.5+/Configuration_adv.h | 10 ++++++++++ .../example_configurations/makibox/Configuration_adv.h | 10 ++++++++++ .../tvrrug/Round2/Configuration_adv.h | 10 ++++++++++ .../example_configurations/wt150/Configuration_adv.h | 10 ++++++++++ Marlin/serial.cpp | 2 +- Marlin/ubl.cpp | 6 +++--- 25 files changed, 234 insertions(+), 4 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index d3ee48a85..b51219dbc 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1165,4 +1165,14 @@ */ //#define NO_WORKSPACE_OFFSETS +/** + * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number + * of spaces to be output by the ratio set below. This allows for better alignment of output for commands + * like G29 O, which renders a mesh/grid. + * + * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust + * accordingly for your client and font. + */ +#define PROPORTIONAL_FONT_RATIO 1.0 + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/Cartesio/Configuration_adv.h b/Marlin/example_configurations/Cartesio/Configuration_adv.h index f6f8c4020..c26dfb816 100644 --- a/Marlin/example_configurations/Cartesio/Configuration_adv.h +++ b/Marlin/example_configurations/Cartesio/Configuration_adv.h @@ -1158,4 +1158,14 @@ */ //#define NO_WORKSPACE_OFFSETS +/** + * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number + * of spaces to be output by the ratio set below. This allows for better alignment of output for commands + * like G29 O, which renders a mesh/grid. + * + * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust + * accordingly for your client and font. + */ +#define PROPORTIONAL_FONT_RATIO 1.0 + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/Felix/Configuration_adv.h b/Marlin/example_configurations/Felix/Configuration_adv.h index 4a334780f..176fd2ab2 100644 --- a/Marlin/example_configurations/Felix/Configuration_adv.h +++ b/Marlin/example_configurations/Felix/Configuration_adv.h @@ -1158,4 +1158,14 @@ */ //#define NO_WORKSPACE_OFFSETS +/** + * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number + * of spaces to be output by the ratio set below. This allows for better alignment of output for commands + * like G29 O, which renders a mesh/grid. + * + * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust + * accordingly for your client and font. + */ +#define PROPORTIONAL_FONT_RATIO 1.0 + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h index 7867bddc7..b818e90f1 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h @@ -1165,4 +1165,14 @@ */ //#define NO_WORKSPACE_OFFSETS +/** + * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number + * of spaces to be output by the ratio set below. This allows for better alignment of output for commands + * like G29 O, which renders a mesh/grid. + * + * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust + * accordingly for your client and font. + */ +#define PROPORTIONAL_FONT_RATIO 1.0 + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/Hephestos/Configuration_adv.h b/Marlin/example_configurations/Hephestos/Configuration_adv.h index ab322752b..798d74177 100644 --- a/Marlin/example_configurations/Hephestos/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos/Configuration_adv.h @@ -1158,4 +1158,14 @@ */ //#define NO_WORKSPACE_OFFSETS +/** + * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number + * of spaces to be output by the ratio set below. This allows for better alignment of output for commands + * like G29 O, which renders a mesh/grid. + * + * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust + * accordingly for your client and font. + */ +#define PROPORTIONAL_FONT_RATIO 1.0 + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h index b8ab84e48..a0c063576 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h @@ -1142,4 +1142,14 @@ */ //#define NO_WORKSPACE_OFFSETS +/** + * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number + * of spaces to be output by the ratio set below. This allows for better alignment of output for commands + * like G29 O, which renders a mesh/grid. + * + * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust + * accordingly for your client and font. + */ +#define PROPORTIONAL_FONT_RATIO 1.0 + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/K8200/Configuration_adv.h b/Marlin/example_configurations/K8200/Configuration_adv.h index 32c9114ca..7f5268d93 100644 --- a/Marlin/example_configurations/K8200/Configuration_adv.h +++ b/Marlin/example_configurations/K8200/Configuration_adv.h @@ -1171,4 +1171,14 @@ */ //#define NO_WORKSPACE_OFFSETS +/** + * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number + * of spaces to be output by the ratio set below. This allows for better alignment of output for commands + * like G29 O, which renders a mesh/grid. + * + * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust + * accordingly for your client and font. + */ +#define PROPORTIONAL_FONT_RATIO 1.0 + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/K8400/Configuration_adv.h b/Marlin/example_configurations/K8400/Configuration_adv.h index 7ffc9e04b..9ef3258f1 100644 --- a/Marlin/example_configurations/K8400/Configuration_adv.h +++ b/Marlin/example_configurations/K8400/Configuration_adv.h @@ -1158,4 +1158,14 @@ */ //#define NO_WORKSPACE_OFFSETS +/** + * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number + * of spaces to be output by the ratio set below. This allows for better alignment of output for commands + * like G29 O, which renders a mesh/grid. + * + * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust + * accordingly for your client and font. + */ +#define PROPORTIONAL_FONT_RATIO 1.0 + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/RigidBot/Configuration_adv.h b/Marlin/example_configurations/RigidBot/Configuration_adv.h index f259c0e42..3d6483b26 100644 --- a/Marlin/example_configurations/RigidBot/Configuration_adv.h +++ b/Marlin/example_configurations/RigidBot/Configuration_adv.h @@ -1158,4 +1158,14 @@ */ //#define NO_WORKSPACE_OFFSETS +/** + * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number + * of spaces to be output by the ratio set below. This allows for better alignment of output for commands + * like G29 O, which renders a mesh/grid. + * + * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust + * accordingly for your client and font. + */ +#define PROPORTIONAL_FONT_RATIO 1.0 + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/SCARA/Configuration_adv.h b/Marlin/example_configurations/SCARA/Configuration_adv.h index a7ad075e5..9f6d22b2d 100644 --- a/Marlin/example_configurations/SCARA/Configuration_adv.h +++ b/Marlin/example_configurations/SCARA/Configuration_adv.h @@ -1158,4 +1158,14 @@ */ //#define NO_WORKSPACE_OFFSETS +/** + * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number + * of spaces to be output by the ratio set below. This allows for better alignment of output for commands + * like G29 O, which renders a mesh/grid. + * + * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust + * accordingly for your client and font. + */ +#define PROPORTIONAL_FONT_RATIO 1.0 + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/TAZ4/Configuration_adv.h b/Marlin/example_configurations/TAZ4/Configuration_adv.h index 23e2226ff..8c510aab9 100644 --- a/Marlin/example_configurations/TAZ4/Configuration_adv.h +++ b/Marlin/example_configurations/TAZ4/Configuration_adv.h @@ -1158,4 +1158,14 @@ */ //#define NO_WORKSPACE_OFFSETS +/** + * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number + * of spaces to be output by the ratio set below. This allows for better alignment of output for commands + * like G29 O, which renders a mesh/grid. + * + * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust + * accordingly for your client and font. + */ +#define PROPORTIONAL_FONT_RATIO 1.0 + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h index 94e357943..ee78175bc 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h @@ -1161,4 +1161,14 @@ */ //#define NO_WORKSPACE_OFFSETS +/** + * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number + * of spaces to be output by the ratio set below. This allows for better alignment of output for commands + * like G29 O, which renders a mesh/grid. + * + * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust + * accordingly for your client and font. + */ +#define PROPORTIONAL_FONT_RATIO 1.0 + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/WITBOX/Configuration_adv.h b/Marlin/example_configurations/WITBOX/Configuration_adv.h index ab322752b..798d74177 100644 --- a/Marlin/example_configurations/WITBOX/Configuration_adv.h +++ b/Marlin/example_configurations/WITBOX/Configuration_adv.h @@ -1158,4 +1158,14 @@ */ //#define NO_WORKSPACE_OFFSETS +/** + * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number + * of spaces to be output by the ratio set below. This allows for better alignment of output for commands + * like G29 O, which renders a mesh/grid. + * + * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust + * accordingly for your client and font. + */ +#define PROPORTIONAL_FONT_RATIO 1.0 + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h index 6fbc87f5f..010a1989d 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h @@ -1163,4 +1163,14 @@ */ //#define NO_WORKSPACE_OFFSETS +/** + * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number + * of spaces to be output by the ratio set below. This allows for better alignment of output for commands + * like G29 O, which renders a mesh/grid. + * + * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust + * accordingly for your client and font. + */ +#define PROPORTIONAL_FONT_RATIO 1.0 + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h index ef7804587..b3f183a31 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h @@ -1162,4 +1162,14 @@ */ //#define NO_WORKSPACE_OFFSETS +/** + * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number + * of spaces to be output by the ratio set below. This allows for better alignment of output for commands + * like G29 O, which renders a mesh/grid. + * + * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust + * accordingly for your client and font. + */ +#define PROPORTIONAL_FONT_RATIO 1.0 + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/delta/generic/Configuration_adv.h b/Marlin/example_configurations/delta/generic/Configuration_adv.h index 057f30d71..deb74b6d6 100644 --- a/Marlin/example_configurations/delta/generic/Configuration_adv.h +++ b/Marlin/example_configurations/delta/generic/Configuration_adv.h @@ -1160,4 +1160,14 @@ */ //#define NO_WORKSPACE_OFFSETS +/** + * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number + * of spaces to be output by the ratio set below. This allows for better alignment of output for commands + * like G29 O, which renders a mesh/grid. + * + * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust + * accordingly for your client and font. + */ +#define PROPORTIONAL_FONT_RATIO 1.0 + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h index 057f30d71..deb74b6d6 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h @@ -1160,4 +1160,14 @@ */ //#define NO_WORKSPACE_OFFSETS +/** + * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number + * of spaces to be output by the ratio set below. This allows for better alignment of output for commands + * like G29 O, which renders a mesh/grid. + * + * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust + * accordingly for your client and font. + */ +#define PROPORTIONAL_FONT_RATIO 1.0 + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h index 1b0cb7c48..8bb8f312a 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h @@ -1165,4 +1165,14 @@ */ //#define NO_WORKSPACE_OFFSETS +/** + * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number + * of spaces to be output by the ratio set below. This allows for better alignment of output for commands + * like G29 O, which renders a mesh/grid. + * + * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust + * accordingly for your client and font. + */ +#define PROPORTIONAL_FONT_RATIO 1.0 + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h index f705314f4..aad4304e5 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h @@ -1160,4 +1160,14 @@ */ //#define NO_WORKSPACE_OFFSETS +/** + * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number + * of spaces to be output by the ratio set below. This allows for better alignment of output for commands + * like G29 O, which renders a mesh/grid. + * + * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust + * accordingly for your client and font. + */ +#define PROPORTIONAL_FONT_RATIO 1.0 + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h index cf186a11e..3f38210b5 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h @@ -1165,4 +1165,14 @@ */ #define NO_WORKSPACE_OFFSETS +/** + * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number + * of spaces to be output by the ratio set below. This allows for better alignment of output for commands + * like G29 O, which renders a mesh/grid. + * + * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust + * accordingly for your client and font. + */ +#define PROPORTIONAL_FONT_RATIO 1.0 + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/makibox/Configuration_adv.h b/Marlin/example_configurations/makibox/Configuration_adv.h index 9e1738a78..c8c38d60f 100644 --- a/Marlin/example_configurations/makibox/Configuration_adv.h +++ b/Marlin/example_configurations/makibox/Configuration_adv.h @@ -1158,4 +1158,14 @@ */ //#define NO_WORKSPACE_OFFSETS +/** + * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number + * of spaces to be output by the ratio set below. This allows for better alignment of output for commands + * like G29 O, which renders a mesh/grid. + * + * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust + * accordingly for your client and font. + */ +#define PROPORTIONAL_FONT_RATIO 1.0 + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h index 76593f954..daf9e0d7d 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h @@ -1158,4 +1158,14 @@ */ //#define NO_WORKSPACE_OFFSETS +/** + * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number + * of spaces to be output by the ratio set below. This allows for better alignment of output for commands + * like G29 O, which renders a mesh/grid. + * + * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust + * accordingly for your client and font. + */ +#define PROPORTIONAL_FONT_RATIO 1.0 + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/wt150/Configuration_adv.h b/Marlin/example_configurations/wt150/Configuration_adv.h index cbad1319d..81d5028b2 100644 --- a/Marlin/example_configurations/wt150/Configuration_adv.h +++ b/Marlin/example_configurations/wt150/Configuration_adv.h @@ -1161,4 +1161,14 @@ */ //#define NO_WORKSPACE_OFFSETS +/** + * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number + * of spaces to be output by the ratio set below. This allows for better alignment of output for commands + * like G29 O, which renders a mesh/grid. + * + * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust + * accordingly for your client and font. + */ +#define PROPORTIONAL_FONT_RATIO 1.0 + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/serial.cpp b/Marlin/serial.cpp index 797c6107a..232a85c30 100644 --- a/Marlin/serial.cpp +++ b/Marlin/serial.cpp @@ -33,4 +33,4 @@ void serial_echopair_P(const char* s_P, float v) { serialprintPGM(s_P); void serial_echopair_P(const char* s_P, double v) { serialprintPGM(s_P); SERIAL_ECHO(v); } void serial_echopair_P(const char* s_P, unsigned long v) { serialprintPGM(s_P); SERIAL_ECHO(v); } -void serial_spaces(uint8_t count) { while (count--) MYSERIAL.write(' '); } +void serial_spaces(uint8_t count) { count *= (PROPORTIONAL_FONT_RATIO); while (count--) MYSERIAL.write(' '); } diff --git a/Marlin/ubl.cpp b/Marlin/ubl.cpp index 0f0c928e2..29e935a65 100644 --- a/Marlin/ubl.cpp +++ b/Marlin/ubl.cpp @@ -136,7 +136,7 @@ void unified_bed_leveling::display_map(const int map_type) { const bool map0 = map_type == 0; - constexpr uint8_t spaces = 11 * (GRID_MAX_POINTS_X - 2); + constexpr uint8_t spaces = 9 * (GRID_MAX_POINTS_X - 2); if (map0) { SERIAL_PROTOCOLLNPGM("\nBed Topography Report:\n"); @@ -145,7 +145,7 @@ serial_echo_xy(GRID_MAX_POINTS_X - 1, GRID_MAX_POINTS_Y - 1); SERIAL_EOL; serial_echo_xy(UBL_MESH_MIN_X, UBL_MESH_MAX_Y); - SERIAL_ECHO_SP(spaces - 3); + SERIAL_ECHO_SP(spaces); serial_echo_xy(UBL_MESH_MAX_X, UBL_MESH_MAX_Y); SERIAL_EOL; } @@ -190,7 +190,7 @@ if (map0) { serial_echo_xy(UBL_MESH_MIN_X, UBL_MESH_MIN_Y); - SERIAL_ECHO_SP(spaces + 1); + SERIAL_ECHO_SP(spaces + 4); serial_echo_xy(UBL_MESH_MAX_X, UBL_MESH_MIN_Y); SERIAL_EOL; serial_echo_xy(0, 0); From 60a4ca1182e6b57e0c649bdfd2d184434faf6287 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 10 May 2017 17:43:39 -0500 Subject: [PATCH 049/189] Better mfpub --- buildroot/share/git/mfpub | 53 ++++++++++++++++++++++----------------- 1 file changed, 30 insertions(+), 23 deletions(-) diff --git a/buildroot/share/git/mfpub b/buildroot/share/git/mfpub index aa76498c0..190e47ae8 100755 --- a/buildroot/share/git/mfpub +++ b/buildroot/share/git/mfpub @@ -22,23 +22,21 @@ if [[ $ORG != "MarlinFirmware" || $REPO != "MarlinDocumentation" ]]; then exit fi +# Check out the named branch (or stay in current) +git checkout $BRANCH + if [[ $BRANCH == "gh-pages" ]]; then echo "Can't build from 'gh-pages.' Only the Jekyll branches (based on 'master')." - bundle exec jekyll serve --watch exit fi if [[ $BRANCH != "master" ]]; then + echo "Stashing any changes to files..." echo "Don't forget to update and push 'master'!" # GOJF Card git stash fi -# Check out the named branch (or stay in current) -git checkout $BRANCH - -echo "Generating MarlinDocumentation..." - COMMIT=$( git log --format="%H" -n 1 ) # Clean out changes and other junk in the branch @@ -48,28 +46,31 @@ git clean -d -f # Push 'master' to the fork and make a proper PR... if [[ $BRANCH == "master" ]]; then - if [[ $FORK == "MarlinFirmware" ]]; then + # Allow working directly with the main fork + echo -n "Pushing to origin/master... " + git push -f origin - # Allow working directly with the main fork - git push -f upstream - - else + echo -n "Pushing to upstream/master... " + git push -f upstream - if [ -z "$(git branch -vv | grep ^\* | grep \\[origin)" ]; then firstpush; fi +else + if [ -z "$(git branch -vv | grep ^\* | grep \\[origin)" ]; then + firstpush + else + echo -n "Pushing to origin/$BRANCH... " git push -f origin + fi - TOOL=$(which gnome-open xdg-open open | awk '{ print $1 }') - URL="https://github.com/$ORG/$REPO/compare/$TARG...$FORK:$BRANCH?expand=1" - - if [ -z "$TOOL" ]; then - echo "Can't find a tool to open the URL:" - echo $URL - else - echo "Opening a New PR Form..." - "$TOOL" "$URL" - fi + TOOL=$(which gnome-open xdg-open open | awk '{ print $1 }') + URL="https://github.com/$ORG/$REPO/compare/$TARG...$FORK:$BRANCH?expand=1" + if [ -z "$TOOL" ]; then + echo "Can't find a tool to open the URL:" + echo $URL + else + echo "Opening a New PR Form..." + "$TOOL" "$URL" fi fi @@ -78,6 +79,8 @@ fi # mv ./_plugins/jekyll-press.rb-disabled ./_plugins/jekyll-press.rb # bundle install +echo "Generating MarlinDocumentation..." + # build the site statically and proof it bundle exec jekyll build --profile --trace --no-watch bundle exec htmlproofer ./_site --only-4xx --allow-hash-href --check-favicon --check-html --url-swap ".*marlinfw.org/:/" @@ -90,7 +93,7 @@ rsync -av _site/ ${TMPFOLDER}/ git reset --hard git clean -d -f -# Sync built-site with gh-pages +# Copy built-site into the gh-pages branch git checkout gh-pages rsync -av ${TMPFOLDER}/ ./ @@ -104,3 +107,7 @@ rm -rf ${TMPFOLDER} # Go back to the branch we started from git checkout $BRANCH + +if [[ $BRANCH != "master" ]]; then + git stash pop +fi From 539e0c2f31f7a98f09e7bd42721d322315125409 Mon Sep 17 00:00:00 2001 From: Pablo Ventura Date: Wed, 10 May 2017 13:07:58 -0300 Subject: [PATCH 050/189] "M80 S" to report the state of the PSU pin --- Marlin/Marlin_main.cpp | 30 ++++++++++++++++++++---------- Marlin/ultralcd.cpp | 4 ++-- 2 files changed, 22 insertions(+), 12 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 4047adb52..4f227afb8 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -559,8 +559,8 @@ static uint8_t target_extruder; #endif // FWRETRACT -#if ENABLED(ULTIPANEL) && HAS_POWER_SWITCH - bool powersupply = +#if HAS_POWER_SWITCH + bool powersupply_on = #if ENABLED(PS_DEFAULT_OFF) false #else @@ -7093,10 +7093,18 @@ inline void gcode_M140() { #if HAS_POWER_SWITCH /** - * M80: Turn on Power Supply + * M80 : Turn on the Power Supply + * M80 S : Report the current state and exit */ inline void gcode_M80() { - OUT_WRITE(PS_ON_PIN, PS_ON_AWAKE); //GND + + // S: Report the current power supply state and exit + if (code_seen('S')) { + serialprintPGM(powersupply_on ? PSTR("PS:1\n") : PSTR("PS:0\n")); + return; + } + + OUT_WRITE(PS_ON_PIN, PS_ON_AWAKE); // GND /** * If you have a switch on suicide pin, this is useful @@ -7112,8 +7120,9 @@ inline void gcode_M140() { tmc2130_init(); // Settings only stick when the driver has power #endif + powersupply_on = true; + #if ENABLED(ULTIPANEL) - powersupply = true; LCD_MESSAGEPGM(WELCOME_MSG); #endif } @@ -7128,25 +7137,26 @@ inline void gcode_M140() { inline void gcode_M81() { thermalManager.disable_all_heaters(); stepper.finish_and_disable(); + #if FAN_COUNT > 0 for (uint8_t i = 0; i < FAN_COUNT; i++) fanSpeeds[i] = 0; - #if ENABLED(PROBING_FANS_OFF) fans_paused = false; ZERO(paused_fanSpeeds); #endif #endif + safe_delay(1000); // Wait 1 second before switching off + #if HAS_SUICIDE stepper.synchronize(); suicide(); #elif HAS_POWER_SWITCH OUT_WRITE(PS_ON_PIN, PS_ON_ASLEEP); + powersupply_on = false; #endif + #if ENABLED(ULTIPANEL) - #if HAS_POWER_SWITCH - powersupply = false; - #endif LCD_MESSAGEPGM(MACHINE_NAME " " MSG_OFF "."); #endif } @@ -10119,7 +10129,7 @@ void process_next_command() { gcode_M81(); break; - case 82: // M83: Set E axis normal mode (same as other axes) + case 82: // M82: Set E axis normal mode (same as other axes) gcode_M82(); break; case 83: // M83: Set E axis relative mode diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 29eb269bd..f563c09cc 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -98,7 +98,7 @@ uint16_t max_display_update_time = 0; typedef void (*screenFunc_t)(); #if HAS_POWER_SWITCH - extern bool powersupply; + extern bool powersupply_on; #endif #if ENABLED(AUTO_BED_LEVELING_UBL) @@ -2129,7 +2129,7 @@ void kill_screen(const char* lcd_msg) { // Switch power on/off // #if HAS_POWER_SWITCH - if (powersupply) + if (powersupply_on) MENU_ITEM(gcode, MSG_SWITCH_PS_OFF, PSTR("M81")); else MENU_ITEM(gcode, MSG_SWITCH_PS_ON, PSTR("M80")); From b63e82f309b19df5da4b11ce0c6cedf3cd3775f0 Mon Sep 17 00:00:00 2001 From: Roxy-3D Date: Wed, 10 May 2017 18:54:10 -0500 Subject: [PATCH 051/189] M421 Mesh Point Offset and misc. UBL clean up (#6685) * M421 Mesh Point Offset and misc. UBL clean up Allow M421 to accept an offset as well as absolute value for a specified mesh point. And misc. UBL clean up to reduce redundent code. * Better error checking for M421 * Fix M421 Y index bug I just noticed.... We've had a Y index bug for who knows how long? --- Marlin/Marlin_main.cpp | 34 +++++++++----- Marlin/configuration_store.cpp | 27 +----------- Marlin/language.h | 2 +- Marlin/ubl.h | 1 - Marlin/ubl_G29.cpp | 81 +++++++++++++++------------------- 5 files changed, 62 insertions(+), 83 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 4047adb52..b1754079f 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -8473,17 +8473,26 @@ void quickstop_stepper() { * M421: Set a single Mesh Bed Leveling Z coordinate * * M421 I J Z + * or + * M421 I J Q */ inline void gcode_M421() { int8_t px = 0, py = 0; float z = 0; - bool hasI, hasJ, hasZ; + bool hasI, hasJ, hasZ, hasQ; if ((hasI = code_seen('I'))) px = code_value_linear_units(); if ((hasJ = code_seen('J'))) py = code_value_linear_units(); if ((hasZ = code_seen('Z'))) z = code_value_linear_units(); + if ((hasQ = code_seen('Q'))) z = code_value_linear_units(); - if (hasI && hasJ && hasZ) { - if (WITHIN(px, 0, GRID_MAX_POINTS_X - 1) && WITHIN(py, 0, GRID_MAX_POINTS_X - 1)) { + if (!hasI || !hasJ || (hasQ && hasZ) || (!hasQ && !hasZ)) { + SERIAL_ERROR_START; + SERIAL_ERRORLNPGM(MSG_ERR_M421_PARAMETERS); + return; + } + + if (WITHIN(px, 0, GRID_MAX_POINTS_X - 1) && WITHIN(py, 0, GRID_MAX_POINTS_Y - 1)) { + if (hasZ) { // doing an absolute mesh value #if ENABLED(AUTO_BED_LEVELING_UBL) ubl.z_values[px][py] = z; #else @@ -8492,18 +8501,23 @@ void quickstop_stepper() { bed_level_virt_interpolate(); #endif #endif - } - else { - SERIAL_ERROR_START; - SERIAL_ERRORLNPGM(MSG_ERR_MESH_XY); + } + else { // doing an offset of a mesh value + #if ENABLED(AUTO_BED_LEVELING_UBL) + ubl.z_values[px][py] += z; + #else + z_values[px][py] += z; + #if ENABLED(ABL_BILINEAR_SUBDIVISION) + bed_level_virt_interpolate(); + #endif + #endif } } - else { + else { // bad indexes were specified for the mesh point SERIAL_ERROR_START; - SERIAL_ERRORLNPGM(MSG_ERR_M421_PARAMETERS); + SERIAL_ERRORLNPGM(MSG_ERR_MESH_XY); } } - #endif #if HAS_M206_COMMAND diff --git a/Marlin/configuration_store.cpp b/Marlin/configuration_store.cpp index 997922550..fe815af2c 100644 --- a/Marlin/configuration_store.cpp +++ b/Marlin/configuration_store.cpp @@ -1459,33 +1459,8 @@ void MarlinSettings::reset() { SERIAL_EOL; if (!forReplay) { - SERIAL_ECHOPGM("\nUBL is "); - ubl.state.active ? SERIAL_CHAR('A') : SERIAL_ECHOPGM("Ina"); - SERIAL_ECHOLNPAIR("ctive\n\nActive Mesh Slot: ", ubl.state.eeprom_storage_slot); + ubl.g29_what_command(); - SERIAL_ECHOPGM("z_offset: "); - SERIAL_ECHO_F(ubl.state.z_offset, 6); - SERIAL_EOL; - - SERIAL_ECHOPAIR("EEPROM can hold ", (int)((UBL_LAST_EEPROM_INDEX - ubl.eeprom_start) / sizeof(ubl.z_values))); - SERIAL_ECHOLNPGM(" meshes.\n"); - - SERIAL_ECHOLNPAIR("GRID_MAX_POINTS_X ", GRID_MAX_POINTS_X); - SERIAL_ECHOLNPAIR("GRID_MAX_POINTS_Y ", GRID_MAX_POINTS_Y); - - SERIAL_ECHOPGM("UBL_MESH_MIN_X " STRINGIFY(UBL_MESH_MIN_X)); - SERIAL_ECHOLNPAIR("=", UBL_MESH_MIN_X ); - SERIAL_ECHOPGM("UBL_MESH_MIN_Y " STRINGIFY(UBL_MESH_MIN_Y)); - SERIAL_ECHOLNPAIR("=", UBL_MESH_MIN_Y ); - - SERIAL_ECHOPGM("UBL_MESH_MAX_X " STRINGIFY(UBL_MESH_MAX_X)); - SERIAL_ECHOLNPAIR("=", UBL_MESH_MAX_X); - SERIAL_ECHOPGM("UBL_MESH_MAX_Y " STRINGIFY(UBL_MESH_MAX_Y)); - SERIAL_ECHOLNPAIR("=", UBL_MESH_MAX_Y); - - SERIAL_ECHOLNPAIR("MESH_X_DIST ", MESH_X_DIST); - SERIAL_ECHOLNPAIR("MESH_Y_DIST ", MESH_Y_DIST); - SERIAL_EOL; } #elif HAS_ABL diff --git a/Marlin/language.h b/Marlin/language.h index 1294eb6b6..914c0363d 100644 --- a/Marlin/language.h +++ b/Marlin/language.h @@ -155,7 +155,7 @@ #define MSG_FILAMENT_RUNOUT_SENSOR "filament: " #define MSG_ERR_MATERIAL_INDEX "M145 S out of range (0-1)" #define MSG_ERR_M355_NONE "No case light" -#define MSG_ERR_M421_PARAMETERS "M421 required parameters missing" +#define MSG_ERR_M421_PARAMETERS "M421 incorrect parameter usage" #define MSG_ERR_MESH_XY "Mesh point cannot be resolved" #define MSG_ERR_ARC_ARGS "G2/G3 bad parameters" #define MSG_ERR_PROTECTED_PIN "Protected Pin" diff --git a/Marlin/ubl.h b/Marlin/ubl.h index a6516ba8a..b33b5d21f 100644 --- a/Marlin/ubl.h +++ b/Marlin/ubl.h @@ -63,7 +63,6 @@ void shift_mesh_height(); void fine_tune_mesh(const float&, const float&, const bool); bool g29_parameter_parsing(); - void g29_what_command(); void g29_eeprom_dump(); void g29_compare_current_mesh_to_stored_mesh(); diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 6e794a3b0..cee20f174 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -520,8 +520,8 @@ // Much of the 'What?' command can be eliminated. But until we are fully debugged, it is // good to have the extra information. Soon... we prune this to just a few items // - if (code_seen('W')) g29_what_command(); - + if (code_seen('W')) ubl.g29_what_command(); + // // When we are fully debugged, the EEPROM dump command will get deleted also. But // right now, it is good to have the extra information. Soon... we prune this. @@ -1181,7 +1181,7 @@ * Much of the 'What?' command can be eliminated. But until we are fully debugged, it is * good to have the extra information. Soon... we prune this to just a few items */ - void g29_what_command() { + void unified_bed_leveling::g29_what_command() { const uint16_t k = E2END - ubl.eeprom_start; say_ubl_name(); @@ -1205,82 +1205,73 @@ SERIAL_PROTOCOLLNPAIR("UBL object count: ", (int)ubl_cnt); #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - SERIAL_PROTOCOLLNPAIR("planner.z_fade_height : ", planner.z_fade_height); + SERIAL_PROTOCOL("planner.z_fade_height : "); + SERIAL_PROTOCOL_F(planner.z_fade_height, 4); + SERIAL_EOL; #endif SERIAL_PROTOCOLPGM("zprobe_zoffset: "); SERIAL_PROTOCOL_F(zprobe_zoffset, 7); SERIAL_EOL; - SERIAL_PROTOCOLPGM("z_offset: "); - SERIAL_PROTOCOL_F(ubl.state.z_offset, 7); - SERIAL_EOL; + SERIAL_PROTOCOLLNPAIR("ubl.eeprom_start=", hex_address((void*)ubl.eeprom_start)); + + SERIAL_ECHOLNPAIR("GRID_MAX_POINTS_X ", GRID_MAX_POINTS_X); + SERIAL_ECHOLNPAIR("GRID_MAX_POINTS_Y ", GRID_MAX_POINTS_Y); safe_delay(25); - SERIAL_PROTOCOLLNPAIR("ubl.eeprom_start=", hex_address((void*)ubl.eeprom_start)); + SERIAL_ECHOLNPAIR("MESH_X_DIST ", MESH_X_DIST); + SERIAL_ECHOLNPAIR("MESH_Y_DIST ", MESH_Y_DIST); + safe_delay(25); SERIAL_PROTOCOLPGM("X-Axis Mesh Points at: "); for (uint8_t i = 0; i < GRID_MAX_POINTS_X; i++) { - SERIAL_PROTOCOL_F(LOGICAL_X_POSITION(pgm_read_float(&ubl.mesh_index_to_xpos[i])), 1); + SERIAL_PROTOCOL_F(LOGICAL_X_POSITION(pgm_read_float(&ubl.mesh_index_to_xpos[i])), 3); SERIAL_PROTOCOLPGM(" "); - safe_delay(50); + safe_delay(25); } SERIAL_EOL; SERIAL_PROTOCOLPGM("Y-Axis Mesh Points at: "); for (uint8_t i = 0; i < GRID_MAX_POINTS_Y; i++) { - SERIAL_PROTOCOL_F(LOGICAL_Y_POSITION(pgm_read_float(&ubl.mesh_index_to_ypos[i])), 1); + SERIAL_PROTOCOL_F(LOGICAL_Y_POSITION(pgm_read_float(&ubl.mesh_index_to_ypos[i])), 3); SERIAL_PROTOCOLPGM(" "); - safe_delay(50); + safe_delay(25); } SERIAL_EOL; - #if HAS_KILL - SERIAL_PROTOCOLPAIR("Kill pin on :", KILL_PIN); - SERIAL_PROTOCOLLNPAIR(" state:", READ(KILL_PIN)); - #endif - SERIAL_EOL; - safe_delay(50); - - SERIAL_PROTOCOLLNPAIR("ubl_state_at_invocation :", ubl_state_at_invocation); - SERIAL_EOL; - SERIAL_PROTOCOLLNPAIR("ubl_state_recursion_chk :", ubl_state_recursion_chk); - SERIAL_EOL; - safe_delay(50); SERIAL_PROTOCOLLNPAIR("Free EEPROM space starts at: ", hex_address((void*)ubl.eeprom_start)); + SERIAL_PROTOCOLLNPAIR("end of EEPROM: ", hex_address((void*)E2END)); + safe_delay(25); - SERIAL_PROTOCOLLNPAIR("end of EEPROM : ", hex_address((void*)E2END)); - safe_delay(50); - - SERIAL_PROTOCOLLNPAIR("sizeof(ubl) : ", (int)sizeof(ubl)); + SERIAL_PROTOCOLPAIR("sizeof(ubl.state) : ", (int)sizeof(ubl.state)); SERIAL_EOL; SERIAL_PROTOCOLLNPAIR("z_value[][] size: ", (int)sizeof(ubl.z_values)); SERIAL_EOL; - safe_delay(50); + safe_delay(25); SERIAL_PROTOCOLLNPAIR("EEPROM free for UBL: ", hex_address((void*)k)); - safe_delay(50); + safe_delay(25); SERIAL_PROTOCOLPAIR("EEPROM can hold ", k / sizeof(ubl.z_values)); SERIAL_PROTOCOLLNPGM(" meshes.\n"); - safe_delay(50); - - SERIAL_PROTOCOLPAIR("sizeof(ubl.state) : ", (int)sizeof(ubl.state)); + safe_delay(25); SERIAL_PROTOCOLPAIR("\nGRID_MAX_POINTS_X ", GRID_MAX_POINTS_X); SERIAL_PROTOCOLPAIR("\nGRID_MAX_POINTS_Y ", GRID_MAX_POINTS_Y); - safe_delay(50); - SERIAL_PROTOCOLPAIR("\nUBL_MESH_MIN_X ", UBL_MESH_MIN_X); - SERIAL_PROTOCOLPAIR("\nUBL_MESH_MIN_Y ", UBL_MESH_MIN_Y); - safe_delay(50); - SERIAL_PROTOCOLPAIR("\nUBL_MESH_MAX_X ", UBL_MESH_MAX_X); - SERIAL_PROTOCOLPAIR("\nUBL_MESH_MAX_Y ", UBL_MESH_MAX_Y); - safe_delay(50); - SERIAL_PROTOCOLPGM("\nMESH_X_DIST "); - SERIAL_PROTOCOL_F(MESH_X_DIST, 6); - SERIAL_PROTOCOLPGM("\nMESH_Y_DIST "); - SERIAL_PROTOCOL_F(MESH_Y_DIST, 6); + safe_delay(25); SERIAL_EOL; - safe_delay(50); + + SERIAL_ECHOPGM("UBL_MESH_MIN_X " STRINGIFY(UBL_MESH_MIN_X)); + SERIAL_ECHOLNPAIR("=", UBL_MESH_MIN_X ); + SERIAL_ECHOPGM("UBL_MESH_MIN_Y " STRINGIFY(UBL_MESH_MIN_Y)); + SERIAL_ECHOLNPAIR("=", UBL_MESH_MIN_Y ); + safe_delay(25); + + SERIAL_ECHOPGM("UBL_MESH_MAX_X " STRINGIFY(UBL_MESH_MAX_X)); + SERIAL_ECHOLNPAIR("=", UBL_MESH_MAX_X); + SERIAL_ECHOPGM("UBL_MESH_MAX_Y " STRINGIFY(UBL_MESH_MAX_Y)); + SERIAL_ECHOLNPAIR("=", UBL_MESH_MAX_Y); + safe_delay(25); if (!ubl.sanity_check()) { say_ubl_name(); From ae676490c9b145b05ee1e85fbacb5d335b734385 Mon Sep 17 00:00:00 2001 From: Brian Date: Thu, 11 May 2017 12:10:38 -0400 Subject: [PATCH 052/189] M421: Add 'adjust closest point' capability - Split M421 into separate versions for bilinear and ubl - Fix minor issue in G26 --- Marlin/G26_Mesh_Validation_Tool.cpp | 4 +- Marlin/Marlin_main.cpp | 72 ++++++++++++++++++++++------- Marlin/ubl.h | 3 ++ Marlin/ubl_G29.cpp | 3 -- 4 files changed, 61 insertions(+), 21 deletions(-) diff --git a/Marlin/G26_Mesh_Validation_Tool.cpp b/Marlin/G26_Mesh_Validation_Tool.cpp index 56a2e4950..896eb4b8b 100644 --- a/Marlin/G26_Mesh_Validation_Tool.cpp +++ b/Marlin/G26_Mesh_Validation_Tool.cpp @@ -740,12 +740,14 @@ } if (code_seen('R')) { - g26_repeats = code_has_value() ? code_value_int() - 1 : 999; + g26_repeats = code_has_value() ? code_value_int() : 999; if (g26_repeats <= 0) { SERIAL_PROTOCOLLNPGM("?(R)epeat value not plausible; must be greater than 0."); return UBL_ERR; } + + g26_repeats--; } diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 63ae0a083..7eb417db7 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -8477,7 +8477,7 @@ void quickstop_stepper() { } } -#elif ENABLED(AUTO_BED_LEVELING_BILINEAR) || ENABLED(AUTO_BED_LEVELING_UBL) +#elif ENABLED(AUTO_BED_LEVELING_BILINEAR) /** * M421: Set a single Mesh Bed Leveling Z coordinate @@ -8490,8 +8490,8 @@ void quickstop_stepper() { int8_t px = 0, py = 0; float z = 0; bool hasI, hasJ, hasZ, hasQ; - if ((hasI = code_seen('I'))) px = code_value_linear_units(); - if ((hasJ = code_seen('J'))) py = code_value_linear_units(); + if ((hasI = code_seen('I'))) px = code_value_int(); + if ((hasJ = code_seen('J'))) py = code_value_int(); if ((hasZ = code_seen('Z'))) z = code_value_linear_units(); if ((hasQ = code_seen('Q'))) z = code_value_linear_units(); @@ -8503,23 +8503,15 @@ void quickstop_stepper() { if (WITHIN(px, 0, GRID_MAX_POINTS_X - 1) && WITHIN(py, 0, GRID_MAX_POINTS_Y - 1)) { if (hasZ) { // doing an absolute mesh value - #if ENABLED(AUTO_BED_LEVELING_UBL) - ubl.z_values[px][py] = z; - #else - z_values[px][py] = z; - #if ENABLED(ABL_BILINEAR_SUBDIVISION) - bed_level_virt_interpolate(); - #endif + z_values[px][py] = z; + #if ENABLED(ABL_BILINEAR_SUBDIVISION) + bed_level_virt_interpolate(); #endif } else { // doing an offset of a mesh value - #if ENABLED(AUTO_BED_LEVELING_UBL) - ubl.z_values[px][py] += z; - #else - z_values[px][py] += z; - #if ENABLED(ABL_BILINEAR_SUBDIVISION) - bed_level_virt_interpolate(); - #endif + z_values[px][py] += z; + #if ENABLED(ABL_BILINEAR_SUBDIVISION) + bed_level_virt_interpolate(); #endif } } @@ -8528,6 +8520,52 @@ void quickstop_stepper() { SERIAL_ERRORLNPGM(MSG_ERR_MESH_XY); } } + +#elif ENABLED(AUTO_BED_LEVELING_UBL) + + /** + * M421: Set a single Mesh Bed Leveling Z coordinate + * + * M421 I J Z + * or + * M421 I J Q + */ + + //todo: change multiple points simultaneously? + + inline void gcode_M421() { + int8_t px = 0, py = 0; + float z = 0; + bool hasI, hasJ, hasZ, hasQ, hasC; + if ((hasI = code_seen('I'))) px = code_value_int(); + if ((hasJ = code_seen('J'))) py = code_value_int(); + if ((hasZ = code_seen('Z'))) z = code_value_linear_units(); + if ((hasQ = code_seen('Q'))) z = code_value_linear_units(); + hasC = code_seen('C'); + + if ( (!(hasI && hasJ) && !hasC) || (hasQ && hasZ) || (!hasQ && !hasZ)) { + SERIAL_ERROR_START; + SERIAL_ERRORLNPGM(MSG_ERR_M421_PARAMETERS); + return; + } + + if (hasC) { // get closest position + const mesh_index_pair location = find_closest_mesh_point_of_type(REAL, current_position[X_AXIS], current_position[Y_AXIS], USE_NOZZLE_AS_REFERENCE, NULL, false); + px = location.x_index; + py = location.y_index; + } + + if (WITHIN(px, 0, GRID_MAX_POINTS_X - 1) && WITHIN(py, 0, GRID_MAX_POINTS_Y - 1)) { + if (hasZ) // doing an absolute mesh value + ubl.z_values[px][py] = z; + else // doing an offset of a mesh value + ubl.z_values[px][py] += z; + } + else { // bad indexes were specified for the mesh point + SERIAL_ERROR_START; + SERIAL_ERRORLNPGM(MSG_ERR_MESH_XY); + } + } #endif #if HAS_M206_COMMAND diff --git a/Marlin/ubl.h b/Marlin/ubl.h index b33b5d21f..4ae4c0504 100644 --- a/Marlin/ubl.h +++ b/Marlin/ubl.h @@ -35,6 +35,9 @@ #define UBL_OK false #define UBL_ERR true + #define USE_NOZZLE_AS_REFERENCE 0 + #define USE_PROBE_AS_REFERENCE 1 + typedef struct { int8_t x_index, y_index; float distance; // When populated, the distance from the search location diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index cee20f174..82efb2fa0 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -311,9 +311,6 @@ * we now have the functionality and features of all three systems combined. */ - #define USE_NOZZLE_AS_REFERENCE 0 - #define USE_PROBE_AS_REFERENCE 1 - // The simple parameter flags and values are 'static' so parameter parsing can be in a support routine. static int g29_verbose_level, phase_value, repetition_cnt, storage_slot = 0, map_type, grid_size; From 5a5dba6fc8f367ef7d9e3adf43c7d8fe9ae6a6db Mon Sep 17 00:00:00 2001 From: Brian Date: Thu, 11 May 2017 18:09:31 -0400 Subject: [PATCH 053/189] UBL: Minor improvement to G29 P2 - allow H code value to override probing height - minor cleanups --- Marlin/ubl_G29.cpp | 45 +++++++++++++++++++++++---------------------- 1 file changed, 23 insertions(+), 22 deletions(-) diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index cee20f174..43fc4c6d9 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -448,7 +448,7 @@ y_pos = current_position[Y_AXIS]; } - float height = code_seen('H') && code_has_value() ? code_value_float() : Z_CLEARANCE_BETWEEN_PROBES; + float height = Z_CLEARANCE_BETWEEN_PROBES; if (code_seen('B')) { card_thickness = code_has_value() ? code_value_float() : measure_business_card_thickness(height); @@ -458,9 +458,11 @@ return; } } + + if (code_seen('H') && code_has_value()) height = code_value_float(); + manually_probe_remaining_mesh(x_pos, y_pos, height, card_thickness, code_seen('O') || code_seen('M')); SERIAL_PROTOCOLLNPGM("G29 P2 finished."); - } break; case 3: { @@ -887,9 +889,9 @@ do_blocking_move_to_z(in_height); do_blocking_move_to_xy(0.5 * (UBL_MESH_MAX_X - (UBL_MESH_MIN_X)), 0.5 * (UBL_MESH_MAX_Y - (UBL_MESH_MIN_Y))); //, min(planner.max_feedrate_mm_s[X_AXIS], planner.max_feedrate_mm_s[Y_AXIS]) / 2.0); - stepper.synchronize(); - SERIAL_PROTOCOLPGM("Place shim under nozzle."); + + SERIAL_PROTOCOLPGM("Place shim under nozzle"); LCD_MESSAGEPGM("Place shim & measure"); lcd_goto_screen(lcd_status_screen); say_and_take_a_measurement(); @@ -898,35 +900,39 @@ do_blocking_move_to_z(current_position[Z_AXIS] + SIZE_OF_LITTLE_RAISE); stepper.synchronize(); - SERIAL_PROTOCOLPGM("Remove shim."); - LCD_MESSAGEPGM("Remove & measure"); - + SERIAL_PROTOCOLPGM("Remove shim"); + LCD_MESSAGEPGM("Remove & measure bed"); say_and_take_a_measurement(); const float z2 = use_encoder_wheel_to_measure_point(); + do_blocking_move_to_z(current_position[Z_AXIS] + Z_CLEARANCE_BETWEEN_PROBES); + const float thickness = abs(z1 - z2); + if (g29_verbose_level > 1) { - SERIAL_PROTOCOLPGM("Business Card is: "); - SERIAL_PROTOCOL_F(abs(z1 - z2), 6); + SERIAL_PROTOCOLPGM("Business Card is "); + SERIAL_PROTOCOL_F(thickness, 4); SERIAL_PROTOCOLLNPGM("mm thick."); } + in_height = current_position[Z_AXIS]; // do manual probing at lower height + ubl.has_control_of_lcd_panel = false; ubl.restore_ubl_active_state_and_leave(); - return abs(z1 - z2); + + return thickness; } void manually_probe_remaining_mesh(const float &lx, const float &ly, float &z_clearance, const float &card_thickness, const bool do_ubl_mesh_map) { ubl.has_control_of_lcd_panel = true; ubl.save_ubl_active_state_and_disable(); // we don't do bed level correction because we want the raw data when we probe - do_blocking_move_to_z(z_clearance); + do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); do_blocking_move_to_xy(lx, ly); lcd_goto_screen(lcd_status_screen); - float last_x = -9999.99, last_y = -9999.99; mesh_index_pair location; do { location = find_closest_mesh_point_of_type(INVALID, lx, ly, USE_NOZZLE_AS_REFERENCE, NULL, false); @@ -945,25 +951,20 @@ } const float xProbe = LOGICAL_X_POSITION(rawx), - yProbe = LOGICAL_Y_POSITION(rawy), - dx = xProbe - last_x, - dy = yProbe - last_y; + yProbe = LOGICAL_Y_POSITION(rawy); + + do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); - if (HYPOT(dx, dy) < BIG_RAISE_NOT_NEEDED) - do_blocking_move_to_z(current_position[Z_AXIS] + SIZE_OF_LITTLE_RAISE); - else - do_blocking_move_to_z(z_clearance); LCD_MESSAGEPGM("Moving to next"); do_blocking_move_to_xy(xProbe, yProbe); - - last_x = xProbe; - last_y = yProbe; + do_blocking_move_to_z(z_clearance); KEEPALIVE_STATE(PAUSED_FOR_USER); ubl.has_control_of_lcd_panel = true; if (do_ubl_mesh_map) ubl.display_map(map_type); // show user where we're probing + if (code_seen('B')) {LCD_MESSAGEPGM("Place shim & measure");} else {LCD_MESSAGEPGM("Measure");} From 91841d75c9a473e15932bd4589d64ee59efe947e Mon Sep 17 00:00:00 2001 From: oldmcg Date: Thu, 11 May 2017 22:33:47 -0500 Subject: [PATCH 054/189] UBL_DELTA (#6695) UBL on Delta's.... Should be close! Should not affect any Cartesian printer. --- Marlin/Conditionals_post.h | 36 +++- Marlin/G26_Mesh_Validation_Tool.cpp | 114 ++++++------- Marlin/Marlin.h | 67 +++++++- Marlin/Marlin_main.cpp | 105 +++++------- Marlin/SanityCheck.h | 57 ++++--- Marlin/planner.cpp | 45 +++++ Marlin/ubl.cpp | 2 +- Marlin/ubl.h | 12 +- Marlin/ubl_G29.cpp | 102 ++++++----- Marlin/ubl_motion.cpp | 256 ++++++++++++++++++++++++++-- 10 files changed, 589 insertions(+), 207 deletions(-) diff --git a/Marlin/Conditionals_post.h b/Marlin/Conditionals_post.h index 3edc8dfe8..2a1f4e0b8 100644 --- a/Marlin/Conditionals_post.h +++ b/Marlin/Conditionals_post.h @@ -730,11 +730,16 @@ /** * Set granular options based on the specific type of leveling */ + + #if ENABLED(AUTO_BED_LEVELING_UBL) && ENABLED(DELTA) + #define UBL_DELTA + #endif + #define ABL_PLANAR (ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_3POINT)) #define ABL_GRID (ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)) #define HAS_ABL (ABL_PLANAR || ABL_GRID || ENABLED(AUTO_BED_LEVELING_UBL)) #define HAS_LEVELING (HAS_ABL || ENABLED(MESH_BED_LEVELING)) - #define PLANNER_LEVELING (ABL_PLANAR || ABL_GRID || ENABLED(MESH_BED_LEVELING)) + #define PLANNER_LEVELING (ABL_PLANAR || ABL_GRID || ENABLED(MESH_BED_LEVELING) || ENABLED(UBL_DELTA)) #define HAS_PROBING_PROCEDURE (HAS_ABL || ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST)) #if HAS_PROBING_PROCEDURE #define PROBE_BED_WIDTH abs(RIGHT_PROBE_BED_POSITION - (LEFT_PROBE_BED_POSITION)) @@ -779,12 +784,13 @@ #define MANUAL_PROBE_HEIGHT Z_HOMING_HEIGHT #endif - #if IS_KINEMATIC - // Check for this in the code instead - #define MIN_PROBE_X X_MIN_POS - #define MAX_PROBE_X X_MAX_POS - #define MIN_PROBE_Y Y_MIN_POS - #define MAX_PROBE_Y Y_MAX_POS + #if ENABLED(DELTA) + // These will be further constrained in code, but UBL_PROBE_PT values + // cannot be compile-time verified within the radius. + #define MIN_PROBE_X (-DELTA_PRINTABLE_RADIUS) + #define MAX_PROBE_X ( DELTA_PRINTABLE_RADIUS) + #define MIN_PROBE_Y (-DELTA_PRINTABLE_RADIUS) + #define MAX_PROBE_Y ( DELTA_PRINTABLE_RADIUS) #else // Boundaries for probing based on set limits #define MIN_PROBE_X (max(X_MIN_POS, X_MIN_POS + X_PROBE_OFFSET_FROM_EXTRUDER)) @@ -814,4 +820,20 @@ #define LCD_TIMEOUT_TO_STATUS 15000 #endif + /** + * DELTA_SEGMENT_MIN_LENGTH for UBL_DELTA + */ + + #if ENABLED(UBL_DELTA) + #ifndef DELTA_SEGMENT_MIN_LENGTH + #if IS_SCARA + #define DELTA_SEGMENT_MIN_LENGTH 0.25 // SCARA minimum segment size is 0.25mm + #elif ENABLED(DELTA) + #define DELTA_SEGMENT_MIN_LENGTH 0.10 // mm (still subject to DELTA_SEGMENTS_PER_SECOND) + #else // CARTESIAN + #define DELTA_SEGMENT_MIN_LENGTH 1.00 // mm (similar to G2/G3 arc segmentation) + #endif + #endif + #endif + #endif // CONDITIONALS_POST_H diff --git a/Marlin/G26_Mesh_Validation_Tool.cpp b/Marlin/G26_Mesh_Validation_Tool.cpp index 896eb4b8b..6b862358d 100644 --- a/Marlin/G26_Mesh_Validation_Tool.cpp +++ b/Marlin/G26_Mesh_Validation_Tool.cpp @@ -122,7 +122,7 @@ // External references - extern float feedrate; + extern float feedrate_mm_s; // must set before calling prepare_move_to_destination extern Planner planner; #if ENABLED(ULTRA_LCD) extern char lcd_status_message[]; @@ -130,6 +130,7 @@ extern float destination[XYZE]; void set_destination_to_current(); void set_current_to_destination(); + void prepare_move_to_destination(); float code_value_float(); float code_value_linear_units(); float code_value_axis_units(const AxisEnum axis); @@ -137,9 +138,6 @@ bool code_has_value(); void lcd_init(); void lcd_setstatuspgm(const char* const message, const uint8_t level); - bool prepare_move_to_destination_cartesian(); - void line_to_destination(); - void line_to_destination(float); void sync_plan_position_e(); void chirp_at_user(); @@ -182,6 +180,13 @@ static int16_t g26_repeats; + void G26_line_to_destination(const float &feed_rate) { + const float save_feedrate = feedrate_mm_s; + feedrate_mm_s = feed_rate; // use specified feed rate + prepare_move_to_destination(); // will ultimately call ubl_line_to_destination_cartesian or ubl_prepare_linear_move_to for UBL_DELTA + feedrate_mm_s = save_feedrate; // restore global feed rate + } + /** * G26: Mesh Validation Pattern generation. * @@ -271,21 +276,10 @@ const float circle_x = pgm_read_float(&ubl.mesh_index_to_xpos[location.x_index]), circle_y = pgm_read_float(&ubl.mesh_index_to_ypos[location.y_index]); - // Let's do a couple of quick sanity checks. We can pull this code out later if we never see it catch a problem - #ifdef DELTA - if (HYPOT2(circle_x, circle_y) > sq(DELTA_PRINTABLE_RADIUS)) { - SERIAL_ERROR_START; - SERIAL_ERRORLNPGM("Attempt to print outside of DELTA_PRINTABLE_RADIUS."); - goto LEAVE; - } - #endif + // If this mesh location is outside the printable_radius, skip it. - // TODO: Change this to use `position_is_reachable` - if (!WITHIN(circle_x, X_MIN_POS, X_MAX_POS) || !WITHIN(circle_y, Y_MIN_POS, Y_MAX_POS)) { - SERIAL_ERROR_START; - SERIAL_ERRORLNPGM("Attempt to print off the bed."); - goto LEAVE; - } + if ( ! position_is_reachable_raw_xy( circle_x, circle_y )) + continue; xi = location.x_index; // Just to shrink the next few lines and make them easier to understand yi = location.y_index; @@ -333,9 +327,11 @@ y = circle_y + sin_table[tmp_div_30], xe = circle_x + cos_table[tmp_div_30 + 1], ye = circle_y + sin_table[tmp_div_30 + 1]; - #ifdef DELTA - if (HYPOT2(x, y) > sq(DELTA_PRINTABLE_RADIUS)) // Check to make sure this part of - continue; // the 'circle' is on the bed. If + #if IS_KINEMATIC + // Check to make sure this segment is entirely on the bed, skip if not. + if (( ! position_is_reachable_raw_xy( x , y )) || + ( ! position_is_reachable_raw_xy( xe, ye ))) + continue; #else // not, we need to skip x = constrain(x, X_MIN_POS + 1, X_MAX_POS - 1); // This keeps us from bumping the endstops y = constrain(y, Y_MIN_POS + 1, Y_MAX_POS - 1); @@ -463,18 +459,22 @@ sy = ey = constrain(pgm_read_float(&ubl.mesh_index_to_ypos[j]), Y_MIN_POS + 1, Y_MAX_POS - 1); ex = constrain(ex, X_MIN_POS + 1, X_MAX_POS - 1); - if (ubl.g26_debug_flag) { - SERIAL_ECHOPAIR(" Connecting with horizontal line (sx=", sx); - SERIAL_ECHOPAIR(", sy=", sy); - SERIAL_ECHOPAIR(") -> (ex=", ex); - SERIAL_ECHOPAIR(", ey=", ey); - SERIAL_CHAR(')'); - SERIAL_EOL; - //debug_current_and_destination(PSTR("Connecting horizontal line.")); - } + if (( position_is_reachable_raw_xy( sx, sy )) && + ( position_is_reachable_raw_xy( ex, ey ))) { - print_line_from_here_to_there(LOGICAL_X_POSITION(sx), LOGICAL_Y_POSITION(sy), layer_height, LOGICAL_X_POSITION(ex), LOGICAL_Y_POSITION(ey), layer_height); - bit_set(horizontal_mesh_line_flags, i, j); // Mark it as done so we don't do it again + if (ubl.g26_debug_flag) { + SERIAL_ECHOPAIR(" Connecting with horizontal line (sx=", sx); + SERIAL_ECHOPAIR(", sy=", sy); + SERIAL_ECHOPAIR(") -> (ex=", ex); + SERIAL_ECHOPAIR(", ey=", ey); + SERIAL_CHAR(')'); + SERIAL_EOL; + //debug_current_and_destination(PSTR("Connecting horizontal line.")); + } + + print_line_from_here_to_there(LOGICAL_X_POSITION(sx), LOGICAL_Y_POSITION(sy), layer_height, LOGICAL_X_POSITION(ex), LOGICAL_Y_POSITION(ey), layer_height); + } + bit_set(horizontal_mesh_line_flags, i, j); // Mark it as done so we don't do it again, even if we skipped it } } @@ -494,17 +494,21 @@ sy = constrain(sy, Y_MIN_POS + 1, Y_MAX_POS - 1); ey = constrain(ey, Y_MIN_POS + 1, Y_MAX_POS - 1); - if (ubl.g26_debug_flag) { - SERIAL_ECHOPAIR(" Connecting with vertical line (sx=", sx); - SERIAL_ECHOPAIR(", sy=", sy); - SERIAL_ECHOPAIR(") -> (ex=", ex); - SERIAL_ECHOPAIR(", ey=", ey); - SERIAL_CHAR(')'); - SERIAL_EOL; - debug_current_and_destination(PSTR("Connecting vertical line.")); + if (( position_is_reachable_raw_xy( sx, sy )) && + ( position_is_reachable_raw_xy( ex, ey ))) { + + if (ubl.g26_debug_flag) { + SERIAL_ECHOPAIR(" Connecting with vertical line (sx=", sx); + SERIAL_ECHOPAIR(", sy=", sy); + SERIAL_ECHOPAIR(") -> (ex=", ex); + SERIAL_ECHOPAIR(", ey=", ey); + SERIAL_CHAR(')'); + SERIAL_EOL; + debug_current_and_destination(PSTR("Connecting vertical line.")); + } + print_line_from_here_to_there(LOGICAL_X_POSITION(sx), LOGICAL_Y_POSITION(sy), layer_height, LOGICAL_X_POSITION(ex), LOGICAL_Y_POSITION(ey), layer_height); } - print_line_from_here_to_there(LOGICAL_X_POSITION(sx), LOGICAL_Y_POSITION(sy), layer_height, LOGICAL_X_POSITION(ex), LOGICAL_Y_POSITION(ey), layer_height); - bit_set(vertical_mesh_line_flags, i, j); // Mark it as done so we don't do it again + bit_set(vertical_mesh_line_flags, i, j); // Mark it as done so we don't do it again, even if skipped } } } @@ -532,7 +536,7 @@ destination[Z_AXIS] = z; // We know the last_z==z or we wouldn't be in this block of code. destination[E_AXIS] = current_position[E_AXIS]; - ubl_line_to_destination(feed_value, 0); + G26_line_to_destination(feed_value); stepper.synchronize(); set_destination_to_current(); @@ -552,7 +556,7 @@ //if (ubl.g26_debug_flag) debug_current_and_destination(PSTR(" in move_to() doing last move")); - ubl_line_to_destination(feed_value, 0); + G26_line_to_destination(feed_value); //if (ubl.g26_debug_flag) debug_current_and_destination(PSTR(" in move_to() after last move")); @@ -755,20 +759,16 @@ y_pos = current_position[Y_AXIS]; if (code_seen('X')) { - x_pos = code_value_axis_units(X_AXIS); - if (!WITHIN(x_pos, X_MIN_POS, X_MAX_POS)) { - SERIAL_PROTOCOLLNPGM("?Specified X coordinate not plausible."); - return UBL_ERR; - } + x_pos = code_value_float(); } - else if (code_seen('Y')) { - y_pos = code_value_axis_units(Y_AXIS); - if (!WITHIN(y_pos, Y_MIN_POS, Y_MAX_POS)) { - SERIAL_PROTOCOLLNPGM("?Specified Y coordinate not plausible."); - return UBL_ERR; - } + y_pos = code_value_float(); + } + + if ( ! position_is_reachable_xy( x_pos, y_pos )) { + SERIAL_PROTOCOLLNPGM("?Specified X,Y coordinate out of bounds."); + return UBL_ERR; } /** @@ -864,7 +864,7 @@ Total_Prime += 0.25; if (Total_Prime >= EXTRUDE_MAXLENGTH) return UBL_ERR; #endif - ubl_line_to_destination(planner.max_feedrate_mm_s[E_AXIS] / 15.0, 0); + G26_line_to_destination(planner.max_feedrate_mm_s[E_AXIS] / 15.0); stepper.synchronize(); // Without this synchronize, the purge is more consistent, // but because the planner has a buffer, we won't be able @@ -893,7 +893,7 @@ #endif set_destination_to_current(); destination[E_AXIS] += prime_length; - ubl_line_to_destination(planner.max_feedrate_mm_s[E_AXIS] / 15.0, 0); + G26_line_to_destination(planner.max_feedrate_mm_s[E_AXIS] / 15.0); stepper.synchronize(); set_destination_to_current(); retract_filament(destination); diff --git a/Marlin/Marlin.h b/Marlin/Marlin.h index b10541b06..e74ad8ae0 100644 --- a/Marlin/Marlin.h +++ b/Marlin/Marlin.h @@ -429,4 +429,69 @@ void do_blocking_move_to_xy(const float &x, const float &y, const float &fr_mm_s bool axis_unhomed_error(const bool x, const bool y, const bool z); #endif -#endif // MARLIN_H +/** + * position_is_reachable family of functions + */ + +#if IS_KINEMATIC // (DELTA or SCARA) + + #if ENABLED(DELTA) + #define DELTA_PRINTABLE_RADIUS_SQUARED ((float)DELTA_PRINTABLE_RADIUS * (float)DELTA_PRINTABLE_RADIUS ) + #endif + + #if IS_SCARA + extern const float L1, L2; + #endif + + inline bool position_is_reachable_raw_xy( float raw_x, float raw_y ) { + #if ENABLED(DELTA) + return ( HYPOT2( raw_x, raw_y ) <= DELTA_PRINTABLE_RADIUS_SQUARED ); + #elif IS_SCARA + #if MIDDLE_DEAD_ZONE_R > 0 + const float R2 = HYPOT2(raw_x - SCARA_OFFSET_X, raw_y - SCARA_OFFSET_Y); + return R2 >= sq(float(MIDDLE_DEAD_ZONE_R)) && R2 <= sq(L1 + L2); + #else + return HYPOT2(raw_x - SCARA_OFFSET_X, raw_y - SCARA_OFFSET_Y) <= sq(L1 + L2); + #endif + #else // CARTESIAN + #error + #endif + } + + inline bool position_is_reachable_by_probe_raw_xy( float raw_x, float raw_y ) { + + // both the nozzle and the probe must be able to reach the point + + return ( position_is_reachable_raw_xy( raw_x, raw_y ) && + position_is_reachable_raw_xy( + raw_x - X_PROBE_OFFSET_FROM_EXTRUDER, + raw_y - Y_PROBE_OFFSET_FROM_EXTRUDER )); + } + +#else // CARTESIAN + + inline bool position_is_reachable_raw_xy( float raw_x, float raw_y ) { + // note to reviewer: this +/-0.0001 logic is copied from original postion_is_reachable + return WITHIN(raw_x, X_MIN_POS - 0.0001, X_MAX_POS + 0.0001) + && WITHIN(raw_y, Y_MIN_POS - 0.0001, Y_MAX_POS + 0.0001); + } + + inline bool position_is_reachable_by_probe_raw_xy( float raw_x, float raw_y ) { + // note to reviewer: this logic is copied from UBL_G29.cpp and does not contain the +/-0.0001 above + return WITHIN(raw_x, MIN_PROBE_X, MAX_PROBE_X) + && WITHIN(raw_y, MIN_PROBE_Y, MAX_PROBE_Y); + } + +#endif // CARTESIAN + +inline bool position_is_reachable_by_probe_xy( float target_x, float target_y ) { + return position_is_reachable_by_probe_raw_xy( + RAW_X_POSITION( target_x ), + RAW_Y_POSITION( target_y )); +} + +inline bool position_is_reachable_xy( float target_x, float target_y ) { + return position_is_reachable_raw_xy( RAW_X_POSITION( target_x ), RAW_Y_POSITION( target_y )); +} + +#endif //MARLIN_H diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 7eb417db7..983ae939e 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -401,7 +401,7 @@ float constexpr homing_feedrate_mm_s[] = { #endif MMM_TO_MMS(HOMING_FEEDRATE_Z), 0 }; -static float feedrate_mm_s = MMM_TO_MMS(1500.0), saved_feedrate_mm_s; +float feedrate_mm_s = MMM_TO_MMS(1500.0), saved_feedrate_mm_s; int feedrate_percentage = 100, saved_feedrate_percentage, flow_percentage[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(100); @@ -1677,6 +1677,8 @@ void do_blocking_move_to(const float &x, const float &y, const float &z, const f #if ENABLED(DELTA) + if ( ! position_is_reachable_xy( x, y )) return; + feedrate_mm_s = fr_mm_s ? fr_mm_s : XY_PROBE_FEEDRATE_MM_S; set_destination_to_current(); // sync destination at the start @@ -1731,6 +1733,8 @@ void do_blocking_move_to(const float &x, const float &y, const float &z, const f #elif IS_SCARA + if ( ! position_is_reachable_xy( x, y )) return; + set_destination_to_current(); // If Z needs to raise, do it before moving XY @@ -2351,6 +2355,8 @@ static void clean_up_after_endstop_or_probe_move() { } #endif + if ( ! position_is_reachable_by_probe_xy( x, y )) return NAN; + const float old_feedrate_mm_s = feedrate_mm_s; #if ENABLED(DELTA) @@ -2419,8 +2425,13 @@ static void clean_up_after_endstop_or_probe_move() { #elif ENABLED(AUTO_BED_LEVELING_UBL) + #if ENABLED(UBL_DELTA) + if (( ubl.state.active ) && ( ! enable )) { // leveling from on to off + planner.unapply_leveling(current_position); + } + #endif + ubl.state.active = enable; - //set_current_from_steppers_for_axis(Z_AXIS); #else @@ -3210,37 +3221,6 @@ void unknown_command_error() { #endif // HOST_KEEPALIVE_FEATURE -bool position_is_reachable(const float target[XYZ] - #if HAS_BED_PROBE - , bool by_probe=false - #endif -) { - float dx = RAW_X_POSITION(target[X_AXIS]), - dy = RAW_Y_POSITION(target[Y_AXIS]); - - #if HAS_BED_PROBE - if (by_probe) { - dx -= X_PROBE_OFFSET_FROM_EXTRUDER; - dy -= Y_PROBE_OFFSET_FROM_EXTRUDER; - } - #endif - - #if IS_SCARA - #if MIDDLE_DEAD_ZONE_R > 0 - const float R2 = HYPOT2(dx - SCARA_OFFSET_X, dy - SCARA_OFFSET_Y); - return R2 >= sq(float(MIDDLE_DEAD_ZONE_R)) && R2 <= sq(L1 + L2); - #else - return HYPOT2(dx - SCARA_OFFSET_X, dy - SCARA_OFFSET_Y) <= sq(L1 + L2); - #endif - #elif ENABLED(DELTA) - return HYPOT2(dx, dy) <= sq((float)(DELTA_PRINTABLE_RADIUS)); - #else - const float dz = RAW_Z_POSITION(target[Z_AXIS]); - return WITHIN(dx, X_MIN_POS - 0.0001, X_MAX_POS + 0.0001) - && WITHIN(dy, Y_MIN_POS - 0.0001, Y_MAX_POS + 0.0001) - && WITHIN(dz, Z_MIN_POS - 0.0001, Z_MAX_POS + 0.0001); - #endif -} /************************************************** ***************** GCode Handlers ***************** @@ -3676,18 +3656,12 @@ inline void gcode_G4() { destination[Y_AXIS] = LOGICAL_Y_POSITION(Z_SAFE_HOMING_Y_POINT); destination[Z_AXIS] = current_position[Z_AXIS]; // Z is already at the right height - if (position_is_reachable( - destination - #if HOMING_Z_WITH_PROBE - , true - #endif - ) - ) { + #if HOMING_Z_WITH_PROBE + destination[X_AXIS] -= X_PROBE_OFFSET_FROM_EXTRUDER; + destination[Y_AXIS] -= Y_PROBE_OFFSET_FROM_EXTRUDER; + #endif - #if HOMING_Z_WITH_PROBE - destination[X_AXIS] -= X_PROBE_OFFSET_FROM_EXTRUDER; - destination[Y_AXIS] -= Y_PROBE_OFFSET_FROM_EXTRUDER; - #endif + if ( position_is_reachable_xy( destination[X_AXIS], destination[Y_AXIS] )) { #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) DEBUG_POS("Z_SAFE_HOMING", destination); @@ -4612,8 +4586,7 @@ void home_all_axes() { gcode_G28(); } indexIntoAB[xCount][yCount] = abl_probe_index; #endif - float pos[XYZ] = { xProbe, yProbe, 0 }; - if (position_is_reachable(pos)) break; + if (position_is_reachable_xy( xProbe, yProbe )) break; ++abl_probe_index; } @@ -4724,8 +4697,7 @@ void home_all_axes() { gcode_G28(); } #if IS_KINEMATIC // Avoid probing outside the round or hexagonal area - const float pos[XYZ] = { xProbe, yProbe, 0 }; - if (!position_is_reachable(pos, true)) continue; + if (!position_is_reachable_by_probe_xy( xProbe, yProbe )) continue; #endif measured_z = faux ? 0.001 * random(-100, 101) : probe_pt(xProbe, yProbe, stow_probe_after_each, verbose_level); @@ -5028,10 +5000,9 @@ void home_all_axes() { gcode_G28(); } */ inline void gcode_G30() { const float xpos = code_seen('X') ? code_value_linear_units() : current_position[X_AXIS] + X_PROBE_OFFSET_FROM_EXTRUDER, - ypos = code_seen('Y') ? code_value_linear_units() : current_position[Y_AXIS] + Y_PROBE_OFFSET_FROM_EXTRUDER, - pos[XYZ] = { xpos, ypos, LOGICAL_Z_POSITION(0) }; + ypos = code_seen('Y') ? code_value_linear_units() : current_position[Y_AXIS] + Y_PROBE_OFFSET_FROM_EXTRUDER; - if (!position_is_reachable(pos, true)) return; + if (!position_is_reachable_by_probe_xy( xpos, ypos )) return; // Disable leveling so the planner won't mess with us #if HAS_LEVELING @@ -6222,22 +6193,19 @@ inline void gcode_M42() { bool stow_probe_after_each = code_seen('E'); float X_probe_location = code_seen('X') ? code_value_linear_units() : X_current + X_PROBE_OFFSET_FROM_EXTRUDER; + float Y_probe_location = code_seen('Y') ? code_value_linear_units() : Y_current + Y_PROBE_OFFSET_FROM_EXTRUDER; + #if DISABLED(DELTA) if (!WITHIN(X_probe_location, LOGICAL_X_POSITION(MIN_PROBE_X), LOGICAL_X_POSITION(MAX_PROBE_X))) { out_of_range_error(PSTR("X")); return; } - #endif - - float Y_probe_location = code_seen('Y') ? code_value_linear_units() : Y_current + Y_PROBE_OFFSET_FROM_EXTRUDER; - #if DISABLED(DELTA) if (!WITHIN(Y_probe_location, LOGICAL_Y_POSITION(MIN_PROBE_Y), LOGICAL_Y_POSITION(MAX_PROBE_Y))) { out_of_range_error(PSTR("Y")); return; } #else - float pos[XYZ] = { X_probe_location, Y_probe_location, 0 }; - if (!position_is_reachable(pos, true)) { + if (!position_is_reachable_by_probe_xy(X_probe_location, Y_probe_location)) { SERIAL_PROTOCOLLNPGM("? (X,Y) location outside of probeable radius."); return; } @@ -6335,7 +6303,7 @@ inline void gcode_M42() { #else // If we have gone out too far, we can do a simple fix and scale the numbers // back in closer to the origin. - while (HYPOT(X_current, Y_current) > DELTA_PROBEABLE_RADIUS) { + while ( ! position_is_reachable_by_probe_xy( X_current, Y_current )) { X_current *= 0.8; Y_current *= 0.8; if (verbose_level > 3) { @@ -11138,7 +11106,7 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) { #endif // AUTO_BED_LEVELING_BILINEAR -#if IS_KINEMATIC +#if IS_KINEMATIC && DISABLED(UBL_DELTA) /** * Prepare a linear move in a DELTA or SCARA setup. @@ -11157,6 +11125,9 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) { return false; } + // Fail if attempting move outside printable radius + if ( ! position_is_reachable_xy( ltarget[X_AXIS], ltarget[Y_AXIS] )) return true; + // Get the cartesian distances moved in XYZE float difference[XYZE]; LOOP_XYZE(i) difference[i] = ltarget[i] - current_position[i]; @@ -11245,7 +11216,7 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) { // For SCARA scale the feed rate from mm/s to degrees/s // With segments > 1 length is 1 segment, otherwise total length inverse_kinematics(ltarget); - ADJUST_DELTA(logical); + ADJUST_DELTA(ltarget); const float adiff = abs(delta[A_AXIS] - oldA), bdiff = abs(delta[B_AXIS] - oldB); planner.buffer_line(delta[A_AXIS], delta[B_AXIS], delta[C_AXIS], logical[E_AXIS], max(adiff, bdiff) * feed_factor, active_extruder); @@ -11278,7 +11249,7 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) { else #elif ENABLED(AUTO_BED_LEVELING_UBL) if (ubl.state.active) { - ubl_line_to_destination(MMS_SCALED(feedrate_mm_s), active_extruder); + ubl_line_to_destination_cartesian(MMS_SCALED(feedrate_mm_s), active_extruder); return true; } else @@ -11407,12 +11378,19 @@ void prepare_move_to_destination() { #endif #if IS_KINEMATIC - if (prepare_kinematic_move_to(destination)) return; + #if ENABLED(UBL_DELTA) + if (ubl_prepare_linear_move_to(destination,feedrate_mm_s)) return; + #else + if (prepare_kinematic_move_to(destination)) return; + #endif #else #if ENABLED(DUAL_X_CARRIAGE) if (prepare_move_to_destination_dualx()) return; + #elif ENABLED(UBL_DELTA) // will work for CARTESIAN too (smaller segments follow mesh more closely) + if (ubl_prepare_linear_move_to(destination,feedrate_mm_s)) return; + #else + if (prepare_move_to_destination_cartesian()) return; #endif - if (prepare_move_to_destination_cartesian()) return; #endif set_current_to_destination(); @@ -12427,3 +12405,4 @@ void loop() { endstops.report_state(); idle(); } + diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index a18d8d557..006bf6829 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -248,8 +248,9 @@ #if ENABLED(DELTA) #if DISABLED(USE_XMAX_PLUG) && DISABLED(USE_YMAX_PLUG) && DISABLED(USE_ZMAX_PLUG) #error "You probably want to use Max Endstops for DELTA!" - #elif ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - #error "DELTA is incompatible with ENABLE_LEVELING_FADE_HEIGHT. Please disable it." + #endif + #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) && DISABLED(UBL_DELTA) + #error "ENABLE_LEVELING_FADE_HEIGHT for DELTA requires UBL_DELTA and AUTO_BED_LEVELING_UBL." #endif #if ABL_GRID #if (GRID_MAX_POINTS_X & 1) == 0 || (GRID_MAX_POINTS_Y & 1) == 0 @@ -430,11 +431,20 @@ static_assert(1 >= 0 * Unified Bed Leveling */ #if ENABLED(AUTO_BED_LEVELING_UBL) - #if ENABLED(DELTA) - #error "AUTO_BED_LEVELING_UBL does not yet support DELTA printers." - #elif DISABLED(NEWPANEL) + #if IS_KINEMATIC + #if ENABLED(DELTA) + #if DISABLED(UBL_DELTA) + #error "AUTO_BED_LEVELING_UBL requires UBL_DELTA for DELTA printers." + #endif + #else // SCARA + #error "AUTO_BED_LEVELING_UBL not supported for SCARA printers." + #endif + #endif + #if DISABLED(NEWPANEL) #error "AUTO_BED_LEVELING_UBL requires an LCD controller." #endif +#elif ENABLED(UBL_DELTA) + #error "UBL_DELTA requires AUTO_BED_LEVELING_UBL." #endif /** @@ -593,11 +603,9 @@ static_assert(1 >= 0 /** * Delta and SCARA have limited bed leveling options */ - #if DISABLED(AUTO_BED_LEVELING_BILINEAR) - #if ENABLED(DELTA) - #error "Only AUTO_BED_LEVELING_BILINEAR is supported for DELTA bed leveling." - #elif ENABLED(SCARA) - #error "Only AUTO_BED_LEVELING_BILINEAR is supported for SCARA bed leveling." + #if IS_KINEMATIC + #if DISABLED(AUTO_BED_LEVELING_BILINEAR) && DISABLED(UBL_DELTA) + #error "Only AUTO_BED_LEVELING_BILINEAR or AUTO_BED_LEVELING_UBL with UBL_DELTA support DELTA and SCARA bed leveling." #endif #endif @@ -626,18 +634,23 @@ static_assert(1 >= 0 #error "AUTO_BED_LEVELING_UBL requires EEPROM_SETTINGS. Please update your configuration." #elif !WITHIN(GRID_MAX_POINTS_X, 3, 15) || !WITHIN(GRID_MAX_POINTS_Y, 3, 15) #error "GRID_MAX_POINTS_[XY] must be a whole number between 3 and 15." - #elif !WITHIN(UBL_PROBE_PT_1_X, MIN_PROBE_X, MAX_PROBE_X) - #error "The given UBL_PROBE_PT_1_X can't be reached by the Z probe." - #elif !WITHIN(UBL_PROBE_PT_2_X, MIN_PROBE_X, MAX_PROBE_X) - #error "The given UBL_PROBE_PT_2_X can't be reached by the Z probe." - #elif !WITHIN(UBL_PROBE_PT_3_X, MIN_PROBE_X, MAX_PROBE_X) - #error "The given UBL_PROBE_PT_3_X can't be reached by the Z probe." - #elif !WITHIN(UBL_PROBE_PT_1_Y, MIN_PROBE_Y, MAX_PROBE_Y) - #error "The given UBL_PROBE_PT_1_Y can't be reached by the Z probe." - #elif !WITHIN(UBL_PROBE_PT_2_Y, MIN_PROBE_Y, MAX_PROBE_Y) - #error "The given UBL_PROBE_PT_2_Y can't be reached by the Z probe." - #elif !WITHIN(UBL_PROBE_PT_3_Y, MIN_PROBE_Y, MAX_PROBE_Y) - #error "The given UBL_PROBE_PT_3_Y can't be reached by the Z probe." + #endif + #if IS_CARTESIAN + #if !WITHIN(GRID_MAX_POINTS_X, 3, 15) || !WITHIN(GRID_MAX_POINTS_Y, 3, 15) + #error "GRID_MAX_POINTS_[XY] must be a whole number between 3 and 15." + #elif !WITHIN(UBL_PROBE_PT_1_X, MIN_PROBE_X, MAX_PROBE_X) + #error "The given UBL_PROBE_PT_1_X can't be reached by the Z probe." + #elif !WITHIN(UBL_PROBE_PT_2_X, MIN_PROBE_X, MAX_PROBE_X) + #error "The given UBL_PROBE_PT_2_X can't be reached by the Z probe." + #elif !WITHIN(UBL_PROBE_PT_3_X, MIN_PROBE_X, MAX_PROBE_X) + #error "The given UBL_PROBE_PT_3_X can't be reached by the Z probe." + #elif !WITHIN(UBL_PROBE_PT_1_Y, MIN_PROBE_Y, MAX_PROBE_Y) + #error "The given UBL_PROBE_PT_1_Y can't be reached by the Z probe." + #elif !WITHIN(UBL_PROBE_PT_2_Y, MIN_PROBE_Y, MAX_PROBE_Y) + #error "The given UBL_PROBE_PT_2_Y can't be reached by the Z probe." + #elif !WITHIN(UBL_PROBE_PT_3_Y, MIN_PROBE_Y, MAX_PROBE_Y) + #error "The given UBL_PROBE_PT_3_Y can't be reached by the Z probe." + #endif #endif #else // AUTO_BED_LEVELING_3POINT #if !WITHIN(ABL_PROBE_PT_1_X, MIN_PROBE_X, MAX_PROBE_X) diff --git a/Marlin/planner.cpp b/Marlin/planner.cpp index af6808fa2..8c641fc26 100644 --- a/Marlin/planner.cpp +++ b/Marlin/planner.cpp @@ -63,6 +63,7 @@ #include "temperature.h" #include "ultralcd.h" #include "language.h" +#include "ubl.h" #include "Marlin.h" @@ -533,6 +534,17 @@ void Planner::check_axes_activity() { */ void Planner::apply_leveling(float &lx, float &ly, float &lz) { + #if ENABLED(AUTO_BED_LEVELING_UBL) && ENABLED(UBL_DELTA) // probably should also be enabled for UBL without UBL_DELTA + if (!ubl.state.active) return; + #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) + // if z_fade_height enabled (nonzero) and raw_z above it, no leveling required + if ((planner.z_fade_height) && (planner.z_fade_height <= RAW_Z_POSITION(lz))) return; + lz += ubl.state.z_offset + ( ubl.get_z_correction(lx,ly) * ubl.fade_scaling_factor_for_z(lz)); + #else // no fade + lz += ubl.state.z_offset + ubl.get_z_correction(lx,ly); + #endif // FADE + #endif // UBL + #if HAS_ABL if (!abl_enabled) return; #endif @@ -586,6 +598,39 @@ void Planner::check_axes_activity() { void Planner::unapply_leveling(float logical[XYZ]) { + #if ENABLED(AUTO_BED_LEVELING_UBL) && ENABLED(UBL_DELTA) + + if ( ubl.state.active ) { + + float z_leveled = RAW_Z_POSITION(logical[Z_AXIS]); + float z_ublmesh = ubl.get_z_correction(logical[X_AXIS],logical[Y_AXIS]); + float z_unlevel = z_leveled - ubl.state.z_offset - z_ublmesh; + + #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) + + // for L=leveled, U=unleveled, M=mesh, O=offset, H=fade_height, + // Given L==U+O+M(1-U/H) (faded mesh correction formula for U 0 ? UBL_MESH_MAX_X : UBL_MESH_MIN_X; - y_pos = Y_PROBE_OFFSET_FROM_EXTRUDER < 0 ? UBL_MESH_MAX_Y : UBL_MESH_MIN_Y; + #if IS_KINEMATIC + x_pos = X_HOME_POS; + y_pos = Y_HOME_POS; + #else // cartesian + x_pos = X_PROBE_OFFSET_FROM_EXTRUDER > 0 ? X_MAX_POS : X_MIN_POS; + y_pos = Y_PROBE_OFFSET_FROM_EXTRUDER < 0 ? Y_MAX_POS : Y_MIN_POS; + #endif } if (code_seen('C')) { @@ -457,6 +462,11 @@ } if (code_seen('H') && code_has_value()) height = code_value_float(); + + if ( !position_is_reachable_xy( x_pos, y_pos )) { + SERIAL_PROTOCOLLNPGM("(X,Y) outside printable radius."); + return; + } manually_probe_remaining_mesh(x_pos, y_pos, height, card_thickness, code_seen('O') || code_seen('M')); SERIAL_PROTOCOLLNPGM("G29 P2 finished."); @@ -470,17 +480,25 @@ * - Allow 'G29 P3' to choose a 'reasonable' constant. */ if (c_flag) { - while (repetition_cnt--) { - const mesh_index_pair location = find_closest_mesh_point_of_type(INVALID, x_pos, y_pos, USE_NOZZLE_AS_REFERENCE, NULL, false); - if (location.x_index < 0) break; // No more invalid Mesh Points to populate + + if ( repetition_cnt >= ( GRID_MAX_POINTS_X * GRID_MAX_POINTS_Y )) { + for ( uint8_t x = 0; x < GRID_MAX_POINTS_X; x++ ) { + for ( uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++ ) { + ubl.z_values[x][y] = ubl_constant; + } + } + } else { + while (repetition_cnt--) { // this only populates reachable mesh points near + const mesh_index_pair location = find_closest_mesh_point_of_type(INVALID, x_pos, y_pos, USE_NOZZLE_AS_REFERENCE, NULL, false); + if (location.x_index < 0) break; // No more reachable invalid Mesh Points to populate ubl.z_values[location.x_index][location.y_index] = ubl_constant; + } } - break; - } - else + } else { smart_fill_mesh(); // Do a 'Smart' fill using nearby known values - - } break; + } + break; + } case 4: // @@ -502,6 +520,12 @@ z2 = probe_pt(LOGICAL_X_POSITION(UBL_PROBE_PT_2_X), LOGICAL_Y_POSITION(UBL_PROBE_PT_2_Y), false, g29_verbose_level), z3 = probe_pt(LOGICAL_X_POSITION(UBL_PROBE_PT_3_X), LOGICAL_Y_POSITION(UBL_PROBE_PT_3_Y), true, g29_verbose_level); + if ( isnan(z1) || isnan(z2) || isnan(z3)) { // probe_pt will return NAN if unreachable + SERIAL_ERROR_START; + SERIAL_ERRORLNPGM("Attempt to probe off the bed."); + goto LEAVE; + } + // We need to adjust z1, z2, z3 by the Mesh Height at these points. Just because they are non-zero doesn't mean // the Mesh is tilted! (We need to compensate each probe point by what the Mesh says that location's height is) @@ -710,6 +734,8 @@ ubl.save_ubl_active_state_and_disable(); // we don't do bed level correction because we want the raw data when we probe DEPLOY_PROBE(); + uint16_t max_iterations = ( GRID_MAX_POINTS_X * GRID_MAX_POINTS_Y ); + do { if (ubl_lcd_clicked()) { SERIAL_PROTOCOLLNPGM("\nMesh only partially populated.\n"); @@ -723,27 +749,19 @@ } location = find_closest_mesh_point_of_type(INVALID, lx, ly, USE_PROBE_AS_REFERENCE, NULL, do_furthest); - if (location.x_index >= 0 && location.y_index >= 0) { + + if (location.x_index >= 0) { // mesh point found and is reachable by probe const float rawx = pgm_read_float(&ubl.mesh_index_to_xpos[location.x_index]), rawy = pgm_read_float(&ubl.mesh_index_to_ypos[location.y_index]); - // TODO: Change to use `position_is_reachable` (for SCARA-compatibility) - if (!WITHIN(rawx, MIN_PROBE_X, MAX_PROBE_X) || !WITHIN(rawy, MIN_PROBE_Y, MAX_PROBE_Y)) { - SERIAL_ERROR_START; - SERIAL_ERRORLNPGM("Attempt to probe off the bed."); - ubl.has_control_of_lcd_panel = false; - goto LEAVE; - } const float measured_z = probe_pt(LOGICAL_X_POSITION(rawx), LOGICAL_Y_POSITION(rawy), stow_probe, g29_verbose_level); ubl.z_values[location.x_index][location.y_index] = measured_z; } if (do_ubl_mesh_map) ubl.display_map(map_type); - } while (location.x_index >= 0 && location.y_index >= 0); - - LEAVE: + } while ((location.x_index >= 0) && (--max_iterations)); STOW_PROBE(); ubl.restore_ubl_active_state_and_leave(); @@ -939,17 +957,13 @@ const float rawx = pgm_read_float(&ubl.mesh_index_to_xpos[location.x_index]), rawy = pgm_read_float(&ubl.mesh_index_to_ypos[location.y_index]); - // TODO: Change to use `position_is_reachable` (for SCARA-compatibility) - if (!WITHIN(rawx, UBL_MESH_MIN_X, UBL_MESH_MAX_X) || !WITHIN(rawy, UBL_MESH_MIN_Y, UBL_MESH_MAX_Y)) { - SERIAL_ERROR_START; - SERIAL_ERRORLNPGM("Attempt to probe off the bed."); - ubl.has_control_of_lcd_panel = false; - goto LEAVE; - } - const float xProbe = LOGICAL_X_POSITION(rawx), yProbe = LOGICAL_Y_POSITION(rawy); + if ( ! position_is_reachable_raw_xy( rawx, rawy )) { // SHOULD NOT OCCUR (find_closest_mesh_point only returns reachable points) + break; + } + do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); LCD_MESSAGEPGM("Moving to next"); @@ -1361,13 +1375,17 @@ rawy = pgm_read_float(&ubl.mesh_index_to_ypos[j]); // If using the probe as the reference there are some unreachable locations. + // Also for round beds, there are grid points outside the bed that nozzle can't reach. // Prune them from the list and ignore them till the next Phase (manual nozzle probing). - if (probe_as_reference == USE_PROBE_AS_REFERENCE && - (!WITHIN(rawx, MIN_PROBE_X, MAX_PROBE_X) || !WITHIN(rawy, MIN_PROBE_Y, MAX_PROBE_Y)) - ) continue; + bool reachable = probe_as_reference ? + position_is_reachable_by_probe_raw_xy( rawx, rawy ) : + position_is_reachable_raw_xy( rawx, rawy ); - // Unreachable. Check if it's the closest location to the nozzle. + if ( ! reachable ) + continue; + + // Reachable. Check if it's the closest location to the nozzle. // Add in a weighting factor that considers the current location of the nozzle. const float mx = LOGICAL_X_POSITION(rawx), // Check if we can probe this mesh location @@ -1415,7 +1433,13 @@ uint16_t not_done[16]; int32_t round_off; + if ( ! position_is_reachable_xy( lx, ly )) { + SERIAL_PROTOCOLLNPGM("(X,Y) outside printable radius."); + return; + } + ubl.save_ubl_active_state_and_disable(); + memset(not_done, 0xFF, sizeof(not_done)); LCD_MESSAGEPGM("Fine Tuning Mesh"); @@ -1425,7 +1449,7 @@ do { location = find_closest_mesh_point_of_type(SET_IN_BITMAP, lx, ly, USE_NOZZLE_AS_REFERENCE, not_done, false); - if (location.x_index < 0 && location.y_index < 0) continue; // abort if we can't find any more points. + if (location.x_index < 0 ) break; // stop when we can't find any more reachable points. bit_clear(not_done, location.x_index, location.y_index); // Mark this location as 'adjusted' so we will find a // different location the next time through the loop @@ -1433,12 +1457,8 @@ const float rawx = pgm_read_float(&ubl.mesh_index_to_xpos[location.x_index]), rawy = pgm_read_float(&ubl.mesh_index_to_ypos[location.y_index]); - // TODO: Change to use `position_is_reachable` (for SCARA-compatibility) - if (!WITHIN(rawx, UBL_MESH_MIN_X, UBL_MESH_MAX_X) || !WITHIN(rawy, UBL_MESH_MIN_Y, UBL_MESH_MAX_Y)) { // In theory, we don't need this check. - SERIAL_ERROR_START; - SERIAL_ERRORLNPGM("Attempt to edit off the bed."); // This really can't happen, but do the check for now - ubl.has_control_of_lcd_panel = false; - goto FINE_TUNE_EXIT; + if ( ! position_is_reachable_raw_xy( rawx, rawy )) { // SHOULD NOT OCCUR because find_closest_mesh_point_of_type will only return reachable + break; } float new_z = ubl.z_values[location.x_index][location.y_index]; @@ -1494,7 +1514,7 @@ lcd_implementation_clear(); - } while (location.x_index >= 0 && location.y_index >= 0 && (--repetition_cnt>0)); + } while (( location.x_index >= 0 ) && (--repetition_cnt>0)); FINE_TUNE_EXIT: diff --git a/Marlin/ubl_motion.cpp b/Marlin/ubl_motion.cpp index bdc8de15a..aaca8d00d 100644 --- a/Marlin/ubl_motion.cpp +++ b/Marlin/ubl_motion.cpp @@ -26,11 +26,13 @@ #include "Marlin.h" #include "ubl.h" #include "planner.h" + #include "stepper.h" #include #include extern float destination[XYZE]; extern void set_current_to_destination(); + extern float delta_segments_per_second; static void debug_echo_axis(const AxisEnum axis) { if (current_position[axis] == destination[axis]) @@ -87,7 +89,7 @@ } - void ubl_line_to_destination(const float &feed_rate, uint8_t extruder) { + void ubl_line_to_destination_cartesian(const float &feed_rate, uint8_t extruder) { /** * Much of the nozzle movement will be within the same cell. So we will do as little computation * as possible to determine if this is the case. If this move is within the same cell, we will @@ -134,7 +136,7 @@ // Note: There is no Z Correction in this case. We are off the grid and don't know what // a reasonable correction would be. - planner.buffer_line(end[X_AXIS], end[Y_AXIS], end[Z_AXIS] + ubl.state.z_offset, end[E_AXIS], feed_rate, extruder); + planner._buffer_line(end[X_AXIS], end[Y_AXIS], end[Z_AXIS] + ubl.state.z_offset, end[E_AXIS], feed_rate, extruder); set_current_to_destination(); if (ubl.g26_debug_flag) @@ -178,7 +180,7 @@ */ if (isnan(z0)) z0 = 0.0; - planner.buffer_line(end[X_AXIS], end[Y_AXIS], end[Z_AXIS] + z0 + ubl.state.z_offset, end[E_AXIS], feed_rate, extruder); + planner._buffer_line(end[X_AXIS], end[Y_AXIS], end[Z_AXIS] + z0 + ubl.state.z_offset, end[E_AXIS], feed_rate, extruder); if (ubl.g26_debug_flag) debug_current_and_destination(PSTR("FINAL_MOVE in ubl_line_to_destination()")); @@ -270,7 +272,7 @@ * Without this check, it is possible for the algorithm to generate a zero length move in the case * where the line is heading down and it is starting right on a Mesh Line boundary. For how often that * happens, it might be best to remove the check and always 'schedule' the move because - * the planner.buffer_line() routine will filter it if that happens. + * the planner._buffer_line() routine will filter it if that happens. */ if (y != start[Y_AXIS]) { if (!inf_normalized_flag) { @@ -292,7 +294,7 @@ z_position = end[Z_AXIS]; } - planner.buffer_line(x, y, z_position + z0 + ubl.state.z_offset, e_position, feed_rate, extruder); + planner._buffer_line(x, y, z_position + z0 + ubl.state.z_offset, e_position, feed_rate, extruder); } //else printf("FIRST MOVE PRUNED "); } @@ -344,7 +346,7 @@ * Without this check, it is possible for the algorithm to generate a zero length move in the case * where the line is heading left and it is starting right on a Mesh Line boundary. For how often * that happens, it might be best to remove the check and always 'schedule' the move because - * the planner.buffer_line() routine will filter it if that happens. + * the planner._buffer_line() routine will filter it if that happens. */ if (x != start[X_AXIS]) { if (!inf_normalized_flag) { @@ -363,7 +365,7 @@ z_position = end[Z_AXIS]; } - planner.buffer_line(x, y, z_position + z0 + ubl.state.z_offset, e_position, feed_rate, extruder); + planner._buffer_line(x, y, z_position + z0 + ubl.state.z_offset, e_position, feed_rate, extruder); } //else printf("FIRST MOVE PRUNED "); } @@ -426,7 +428,7 @@ e_position = end[E_AXIS]; z_position = end[Z_AXIS]; } - planner.buffer_line(x, next_mesh_line_y, z_position + z0 + ubl.state.z_offset, e_position, feed_rate, extruder); + planner._buffer_line(x, next_mesh_line_y, z_position + z0 + ubl.state.z_offset, e_position, feed_rate, extruder); current_yi += dyi; yi_cnt--; } @@ -455,7 +457,7 @@ z_position = end[Z_AXIS]; } - planner.buffer_line(next_mesh_line_x, y, z_position + z0 + ubl.state.z_offset, e_position, feed_rate, extruder); + planner._buffer_line(next_mesh_line_x, y, z_position + z0 + ubl.state.z_offset, e_position, feed_rate, extruder); current_xi += dxi; xi_cnt--; } @@ -472,4 +474,238 @@ set_current_to_destination(); } -#endif + + #ifdef UBL_DELTA + + #define COPY_XYZE( target, source ) { \ + target[X_AXIS] = source[X_AXIS]; \ + target[Y_AXIS] = source[Y_AXIS]; \ + target[Z_AXIS] = source[Z_AXIS]; \ + target[E_AXIS] = source[E_AXIS]; \ + } + + #if IS_SCARA // scale the feed rate from mm/s to degrees/s + static float scara_feed_factor; + static float scara_oldA; + static float scara_oldB; + #endif + + // We don't want additional apply_leveling() performed by regular buffer_line or buffer_line_kinematic, + // so we call _buffer_line directly here. Per-segmented leveling performed first. + + static inline void ubl_buffer_line_segment(const float ltarget[XYZE], const float &fr_mm_s, const uint8_t extruder) { + + #if IS_KINEMATIC + + inverse_kinematics(ltarget); // this writes delta[ABC] from ltarget[XYZ] but does not modify ltarget + float feedrate = fr_mm_s; + + #if IS_SCARA // scale the feed rate from mm/s to degrees/s + float adiff = abs(delta[A_AXIS] - scara_oldA); + float bdiff = abs(delta[B_AXIS] - scara_oldB); + scara_oldA = delta[A_AXIS]; + scara_oldB = delta[B_AXIS]; + feedrate = max(adiff, bdiff) * scara_feed_factor; + #endif + + planner._buffer_line( delta[A_AXIS], delta[B_AXIS], delta[C_AXIS], ltarget[E_AXIS], feedrate, extruder ); + + #else // cartesian + + planner._buffer_line( ltarget[X_AXIS], ltarget[Y_AXIS], ltarget[Z_AXIS], ltarget[E_AXIS], fr_mm_s, extruder ); + + #endif + } + + /** + * Prepare a linear move for DELTA/SCARA/CARTESIAN with UBL and FADE semantics. + * This calls planner._buffer_line multiple times for small incremental moves. + * Returns true if the caller did NOT update current_position, otherwise false. + */ + + static bool ubl_prepare_linear_move_to(const float ltarget[XYZE], const float &feedrate) { + + if ( ! position_is_reachable_xy( ltarget[X_AXIS], ltarget[Y_AXIS] )) // fail if moving outside reachable boundary + return true; // did not move, so current_position still accurate + + const float difference[XYZE] = { // cartesian distances moved in XYZE + ltarget[X_AXIS] - current_position[X_AXIS], + ltarget[Y_AXIS] - current_position[Y_AXIS], + ltarget[Z_AXIS] - current_position[Z_AXIS], + ltarget[E_AXIS] - current_position[E_AXIS] + }; + + float cartesian_xy_mm = sqrtf( sq(difference[X_AXIS]) + sq(difference[Y_AXIS]) ); // total horizontal xy distance + + #if IS_KINEMATIC + float seconds = cartesian_xy_mm / feedrate; // seconds to move xy distance at requested rate + uint16_t segments = lroundf( delta_segments_per_second * seconds ); // preferred number of segments for distance @ feedrate + uint16_t seglimit = lroundf( cartesian_xy_mm * (1.0/(DELTA_SEGMENT_MIN_LENGTH))); // number of segments at minimum segment length + NOMORE( segments, seglimit ); // limit to minimum segment length (fewer segments) + #else + uint16_t segments = lroundf( cartesian_xy_mm * (1.0/(DELTA_SEGMENT_MIN_LENGTH))); // cartesian fixed segment length + #endif + + NOLESS( segments, 1 ); // must have at least one segment + float inv_segments = 1.0 / segments; // divide once, multiply thereafter + + #if IS_SCARA // scale the feed rate from mm/s to degrees/s + scara_feed_factor = cartesian_xy_mm * inv_segments * feedrate; + scara_oldA = stepper.get_axis_position_degrees(A_AXIS); + scara_oldB = stepper.get_axis_position_degrees(B_AXIS); + #endif + + const float segment_distance[XYZE] = { // length for each segment + difference[X_AXIS] * inv_segments, + difference[Y_AXIS] * inv_segments, + difference[Z_AXIS] * inv_segments, + difference[E_AXIS] * inv_segments + }; + + // Note that E segment distance could vary slightly as z mesh height + // changes for each segment, but small enough to ignore. + + bool above_fade_height = false; + #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) + if (( planner.z_fade_height != 0 ) && + ( planner.z_fade_height < RAW_Z_POSITION(ltarget[Z_AXIS]) )) { + above_fade_height = true; + } + #endif + + // Only compute leveling per segment if ubl active and target below z_fade_height. + + if (( ! ubl.state.active ) || ( above_fade_height )) { // no mesh leveling + + const float z_offset = ubl.state.active ? ubl.state.z_offset : 0.0; + + float seg_dest[XYZE]; // per-segment destination, + COPY_XYZE( seg_dest, current_position ); // starting from current position + + while (--segments) { + LOOP_XYZE(i) seg_dest[i] += segment_distance[i]; + float ztemp = seg_dest[Z_AXIS]; + seg_dest[Z_AXIS] += z_offset; + ubl_buffer_line_segment( seg_dest, feedrate, active_extruder ); + seg_dest[Z_AXIS] = ztemp; + } + + // Since repeated adding segment_distance accumulates small errors, final move to exact destination. + COPY_XYZE( seg_dest, ltarget ); + seg_dest[Z_AXIS] += z_offset; + ubl_buffer_line_segment( seg_dest, feedrate, active_extruder ); + return false; // moved but did not set_current_to_destination(); + } + + // Otherwise perform per-segment leveling + + #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) + float fade_scaling_factor = ubl.fade_scaling_factor_for_z(ltarget[Z_AXIS]); + #endif + + float seg_dest[XYZE]; // per-segment destination, initialize to first segment + LOOP_XYZE(i) seg_dest[i] = current_position[i] + segment_distance[i]; + + const float& dx_seg = segment_distance[X_AXIS]; // alias for clarity + const float& dy_seg = segment_distance[Y_AXIS]; + + float rx = RAW_X_POSITION(seg_dest[X_AXIS]); // assume raw vs logical coordinates shifted but not scaled. + float ry = RAW_Y_POSITION(seg_dest[Y_AXIS]); + + do { // for each mesh cell encountered during the move + + // Compute mesh cell invariants that remain constant for all segments within cell. + // Note for cell index, if point is outside the mesh grid (in MESH_INSET perimeter) + // the bilinear interpolation from the adjacent cell within the mesh will still work. + // Inner loop will exit each time (because out of cell bounds) but will come back + // in top of loop and again re-find same adjacent cell and use it, just less efficient + // for mesh inset area. + + int8_t cell_xi = (rx - (UBL_MESH_MIN_X)) * (1.0 / (MESH_X_DIST)); + cell_xi = constrain( cell_xi, 0, (GRID_MAX_POINTS_X) - 1 ); + + int8_t cell_yi = (ry - (UBL_MESH_MIN_Y)) * (1.0 / (MESH_X_DIST)); + cell_yi = constrain( cell_yi, 0, (GRID_MAX_POINTS_Y) - 1 ); + + // float x0 = (UBL_MESH_MIN_X) + ((MESH_X_DIST) * cell_xi ); // lower left cell corner + // float y0 = (UBL_MESH_MIN_Y) + ((MESH_Y_DIST) * cell_yi ); // lower left cell corner + // float x1 = x0 + MESH_X_DIST; // upper right cell corner + // float y1 = y0 + MESH_Y_DIST; // upper right cell corner + + float x0 = pgm_read_float(&(ubl.mesh_index_to_xpos[cell_xi ])); // 64 byte table lookup avoids mul+add + float y0 = pgm_read_float(&(ubl.mesh_index_to_ypos[cell_yi ])); // 64 byte table lookup avoids mul+add + float x1 = pgm_read_float(&(ubl.mesh_index_to_xpos[cell_xi+1])); // 64 byte table lookup avoids mul+add + float y1 = pgm_read_float(&(ubl.mesh_index_to_ypos[cell_yi+1])); // 64 byte table lookup avoids mul+add + + float cx = rx - x0; // cell-relative x + float cy = ry - y0; // cell-relative y + + float z_x0y0 = ubl.z_values[cell_xi ][cell_yi ]; // z at lower left corner + float z_x1y0 = ubl.z_values[cell_xi+1][cell_yi ]; // z at upper left corner + float z_x0y1 = ubl.z_values[cell_xi ][cell_yi+1]; // z at lower right corner + float z_x1y1 = ubl.z_values[cell_xi+1][cell_yi+1]; // z at upper right corner + + if ( isnan( z_x0y0 )) z_x0y0 = 0; // ideally activating ubl.state.active (G29 A) + if ( isnan( z_x1y0 )) z_x1y0 = 0; // should refuse if any invalid mesh points + if ( isnan( z_x0y1 )) z_x0y1 = 0; // in order to avoid isnan tests per cell, + if ( isnan( z_x1y1 )) z_x1y1 = 0; // thus guessing zero for undefined points + + float z_xmy0 = (z_x1y0 - z_x0y0) * (1.0/MESH_X_DIST); // z slope per x along y0 (lower left to lower right) + float z_xmy1 = (z_x1y1 - z_x0y1) * (1.0/MESH_X_DIST); // z slope per x along y1 (upper left to upper right) + + float z_cxy0 = z_x0y0 + z_xmy0 * cx; // z height along y0 at cx + float z_cxy1 = z_x0y1 + z_xmy1 * cx; // z height along y1 at cx + float z_cxyd = z_cxy1 - z_cxy0; // z height difference along cx from y0 to y1 + + float z_cxym = z_cxyd * (1.0/MESH_Y_DIST); // z slope per y along cx from y0 to y1 + float z_cxcy = z_cxy0 + z_cxym * cy; // z height along cx at cy + + // As subsequent segments step through this cell, the z_cxy0 intercept will change + // and the z_cxym slope will change, both as a function of cx within the cell, and + // each change by a constant for fixed segment lengths. + + float z_sxy0 = z_xmy0 * dx_seg; // per-segment adjustment to z_cxy0 + float z_sxym = ( z_xmy1 - z_xmy0 ) * (1.0/MESH_Y_DIST) * dx_seg; // per-segment adjustment to z_cxym + + do { // for all segments within this mesh cell + + z_cxcy += ubl.state.z_offset; + + if ( --segments == 0 ) { // this is last segment, use ltarget for exact + COPY_XYZE( seg_dest, ltarget ); + seg_dest[Z_AXIS] += z_cxcy; + ubl_buffer_line_segment( seg_dest, feedrate, active_extruder ); + return false; // did not set_current_to_destination() + } + + float z_orig = seg_dest[Z_AXIS]; // remember the pre-leveled segment z value + seg_dest[Z_AXIS] = z_orig + z_cxcy; // adjust segment z height per mesh leveling + ubl_buffer_line_segment( seg_dest, feedrate, active_extruder ); + seg_dest[Z_AXIS] = z_orig; // restore pre-leveled z before incrementing + + LOOP_XYZE(i) seg_dest[i] += segment_distance[i]; // adjust seg_dest for next segment + + cx += dx_seg; + cy += dy_seg; + + if ( !WITHIN(cx,0,MESH_X_DIST) || !WITHIN(cy,0,MESH_Y_DIST)) { // done within this cell, break to next + rx = RAW_X_POSITION(seg_dest[X_AXIS]); + ry = RAW_Y_POSITION(seg_dest[Y_AXIS]); + break; + } + + // Next segment still within same mesh cell, adjust the per-segment + // slope and intercept and compute next z height. + + z_cxy0 += z_sxy0; // adjust z_cxy0 by per-segment z_sxy0 + z_cxym += z_sxym; // adjust z_cxym by per-segment z_sxym + z_cxcy = z_cxy0 + z_cxym * cy; // recompute z_cxcy from adjusted slope and intercept + + } while (true); // per-segment loop exits by break after last segment within cell, or by return on final segment + } while (true); // per-cell loop + } // end of function + + #endif // UBL_DELTA + +#endif // AUTO_BED_LEVELING_UBL + From b0ba5cae7385cc4b594c35f20229dc0a90bbe72d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 10 May 2017 20:28:35 -0500 Subject: [PATCH 055/189] Fix a spelling boo --- Marlin/G26_Mesh_Validation_Tool.cpp | 2 +- Marlin/ubl_G29.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/G26_Mesh_Validation_Tool.cpp b/Marlin/G26_Mesh_Validation_Tool.cpp index 6b862358d..49a29daa9 100644 --- a/Marlin/G26_Mesh_Validation_Tool.cpp +++ b/Marlin/G26_Mesh_Validation_Tool.cpp @@ -100,7 +100,7 @@ * 'n' can be used instead if your host program does not appreciate you using 'N'. * * O # Ooooze How much your nozzle will Ooooze filament while getting in position to print. This - * is over kill, but using this parameter will let you get the very first 'cicle' perfect + * is over kill, but using this parameter will let you get the very first 'circle' perfect * so you have a trophy to peel off of the bed and hang up to show how perfectly you have your * Mesh calibrated. If not specified, a filament length of .3mm is assumed. * diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 9efec6235..281182166 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -209,7 +209,7 @@ * Mesh Validation Pattern phase. Please note that you are populating your mesh with unverified * numbers. You should use some scrutiny and caution. * - * P4 Phase 4 Fine tune the Mesh. The Delta Mesh Compensation System assume the existance of + * P4 Phase 4 Fine tune the Mesh. The Delta Mesh Compensation System assume the existence of * an LCD Panel. It is possible to fine tune the mesh without the use of an LCD Panel. * (More work and details on doing this later!) * The System will search for the closest Mesh Point to the nozzle. It will move the From ee50dfaaf353d162d13203992dfbc0d164608a6d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 10 May 2017 23:02:52 -0500 Subject: [PATCH 056/189] Adjust G26 arguments --- Marlin/G26_Mesh_Validation_Tool.cpp | 53 +++++++++-------------------- 1 file changed, 17 insertions(+), 36 deletions(-) diff --git a/Marlin/G26_Mesh_Validation_Tool.cpp b/Marlin/G26_Mesh_Validation_Tool.cpp index 49a29daa9..4f231c2ae 100644 --- a/Marlin/G26_Mesh_Validation_Tool.cpp +++ b/Marlin/G26_Mesh_Validation_Tool.cpp @@ -152,7 +152,7 @@ bool turn_on_heaters(); bool prime_nozzle(); - static uint16_t circle_flags[16], horizontal_mesh_line_flags[16], vertical_mesh_line_flags[16], continue_with_closest = 0; + static uint16_t circle_flags[16], horizontal_mesh_line_flags[16], vertical_mesh_line_flags[16]; float g26_e_axis_feedrate = 0.020, random_deviation = 0.0, layer_height = LAYER_HEIGHT; @@ -176,7 +176,7 @@ static int8_t prime_flag = 0; - static bool keep_heaters_on = false; + static bool continue_with_closest, keep_heaters_on; static int16_t g26_repeats; @@ -361,7 +361,7 @@ //debug_current_and_destination(PSTR("Done with current circle.")); - } while (location.x_index >= 0 && location.y_index >= 0 && g26_repeats--); + } while (--g26_repeats && location.x_index >= 0 && location.y_index >= 0); LEAVE: lcd_reset_alert_level(); @@ -623,8 +623,8 @@ //if (ubl.g26_debug_flag) SERIAL_ECHOLNPGM(" Z bumping by 0.500 to minimize scraping."); //todo: parameterize the bump height with a define - move_to(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS]+0.500, 0.0); // Z bump to minimize scraping - move_to(sx, sy, sz+0.500, 0.0); // Get to the starting point with no extrusion while bumped + move_to(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS] + 0.500, 0.0); // Z bump to minimize scraping + move_to(sx, sy, sz + 0.500, 0.0); // Get to the starting point with no extrusion while bumped } move_to(sx, sy, sz, 0.0); // Get to the starting point with no extrusion / un-Z bump @@ -655,9 +655,11 @@ prime_length = PRIME_LENGTH; bed_temp = BED_TEMP; hotend_temp = HOTEND_TEMP; - ooze_amount = OOZE_AMOUNT; prime_flag = 0; - keep_heaters_on = false; + + ooze_amount = code_seen('O') && code_has_value() ? code_value_linear_units() : OOZE_AMOUNT; + keep_heaters_on = code_seen('K') && code_value_bool(); + continue_with_closest = code_seen('C') && code_value_bool(); if (code_seen('B')) { bed_temp = code_value_temp_abs(); @@ -667,8 +669,6 @@ } } - if (code_seen('C')) continue_with_closest++; - if (code_seen('L')) { layer_height = code_value_linear_units(); if (!WITHIN(layer_height, 0.0, 2.0)) { @@ -699,11 +699,6 @@ } } - if (code_seen('K')) keep_heaters_on++; - - if (code_seen('O') && code_has_value()) - ooze_amount = code_value_linear_units(); - if (code_seen('P')) { if (!code_has_value()) prime_flag = -1; @@ -740,33 +735,19 @@ if (code_seen('M')) { randomSeed(millis()); + // This setting will persist for the next G26 random_deviation = code_has_value() ? code_value_float() : 50.0; } - if (code_seen('R')) { - g26_repeats = code_has_value() ? code_value_int() : 999; - - if (g26_repeats <= 0) { - SERIAL_PROTOCOLLNPGM("?(R)epeat value not plausible; must be greater than 0."); - return UBL_ERR; - } - - g26_repeats--; - } - - - x_pos = current_position[X_AXIS]; - y_pos = current_position[Y_AXIS]; - - if (code_seen('X')) { - x_pos = code_value_float(); - } - - if (code_seen('Y')) { - y_pos = code_value_float(); + g26_repeats = code_seen('R') ? (code_has_value() ? code_value_int() : 999) : 1; + if (g26_repeats < 1) { + SERIAL_PROTOCOLLNPGM("?(R)epeat value not plausible; must be at least 1."); + return UBL_ERR; } - if ( ! position_is_reachable_xy( x_pos, y_pos )) { + x_pos = code_seen('X') ? code_value_linear_units() : current_position[X_AXIS]; + y_pos = code_seen('Y') ? code_value_linear_units() : current_position[Y_AXIS]; + if (!position_is_reachable_xy(x_pos, y_pos)) { SERIAL_PROTOCOLLNPGM("?Specified X,Y coordinate out of bounds."); return UBL_ERR; } From 301958b3e0bfe5079353830c053519cd9642cffa Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 11 May 2017 01:21:46 -0500 Subject: [PATCH 057/189] Simplify mfdoc, mfpub --- buildroot/share/git/mfdoc | 12 ------------ buildroot/share/git/mfpub | 15 ++++++++------- 2 files changed, 8 insertions(+), 19 deletions(-) diff --git a/buildroot/share/git/mfdoc b/buildroot/share/git/mfdoc index 3880c6dac..4b28e9ca1 100755 --- a/buildroot/share/git/mfdoc +++ b/buildroot/share/git/mfdoc @@ -16,12 +16,6 @@ if [[ $ORG != "MarlinFirmware" || $REPO != "MarlinDocumentation" ]]; then exit fi -if [[ $BRANCH != "master" ]]; then - echo "Stashing changes and changing to master." - git stash - git checkout master -fi - opensite() { TOOL=$(which gnome-open xdg-open open | awk '{ print $1 }') URL="http://127.0.0.1:4000/" @@ -40,9 +34,3 @@ echo "Previewing MarlinDocumentation..." ( sleep 45; opensite ) & bundle exec jekyll serve --watch --incremental - -if [[ $BRANCH != "master" ]]; then - echo "Restoring branch '$BRANCH'" - git checkout $BRANCH - git stash pop -fi diff --git a/buildroot/share/git/mfpub b/buildroot/share/git/mfpub index 190e47ae8..9e590eb07 100755 --- a/buildroot/share/git/mfpub +++ b/buildroot/share/git/mfpub @@ -30,26 +30,25 @@ if [[ $BRANCH == "gh-pages" ]]; then exit fi -if [[ $BRANCH != "master" ]]; then - echo "Stashing any changes to files..." - echo "Don't forget to update and push 'master'!" - # GOJF Card - git stash -fi +echo "Stashing any changes to files..." +echo "Don't forget to update and push 'master'!" +# GOJF Card +git stash COMMIT=$( git log --format="%H" -n 1 ) # Clean out changes and other junk in the branch -git reset --hard git clean -d -f # Push 'master' to the fork and make a proper PR... if [[ $BRANCH == "master" ]]; then # Allow working directly with the main fork + echo echo -n "Pushing to origin/master... " git push -f origin + echo echo -n "Pushing to upstream/master... " git push -f upstream @@ -58,6 +57,7 @@ else if [ -z "$(git branch -vv | grep ^\* | grep \\[origin)" ]; then firstpush else + echo echo -n "Pushing to origin/$BRANCH... " git push -f origin fi @@ -79,6 +79,7 @@ fi # mv ./_plugins/jekyll-press.rb-disabled ./_plugins/jekyll-press.rb # bundle install +echo echo "Generating MarlinDocumentation..." # build the site statically and proof it From 94e90ca26c8c5af6a63c760382aea1bcb6d64cf6 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 11 May 2017 02:32:08 -0500 Subject: [PATCH 058/189] Tweak M80/M81 descriptions --- Marlin/Marlin_main.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 983ae939e..d789a51a4 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -97,8 +97,8 @@ * M76 - Pause the print job timer. * M77 - Stop the print job timer. * M78 - Show statistical information about the print jobs. (Requires PRINTCOUNTER) - * M80 - Turn on Power Supply. (Requires POWER_SUPPLY) - * M81 - Turn off Power Supply. (Requires POWER_SUPPLY) + * M80 - Turn on Power Supply. (Requires POWER_SUPPLY > 0) + * M81 - Turn off Power Supply. (Requires POWER_SUPPLY > 0) * M82 - Set E codes absolute (default). * M83 - Set E codes relative while in Absolute (G90) mode. * M84 - Disable steppers until next move, or use S to specify an idle From 92fbea2906cd5df9ba33baad9e53e4c6517e07ff Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 11 May 2017 22:25:06 -0500 Subject: [PATCH 059/189] Add some GCodes to the header of Marlin_main.cpp --- Marlin/Marlin_main.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index d789a51a4..adcbc1a59 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -56,6 +56,8 @@ * G12 - Clean tool * G20 - Set input units to inches * G21 - Set input units to millimeters + * G26 - Mesh Validation Pattern (Requires UBL_G26_MESH_EDITING) + * G27 - Park Nozzle (Requires NOZZLE_PARK_FEATURE) * G28 - Home one or more axes * G29 - Detailed Z probe, probes the bed at 3 or more points. Will fail if you haven't homed yet. * G30 - Single Z probe, probes bed at X Y location (defaults to current XY location) @@ -105,6 +107,7 @@ * duration after which steppers should turn off. S0 disables the timeout. * M85 - Set inactivity shutdown timer with parameter S. To disable set zero (default) * M92 - Set planner.axis_steps_per_mm for one or more axes. + * M100 - Watch Free Memory (for debugging) (Requires M100_FREE_MEMORY_WATCHER) * M104 - Set extruder target temp. * M105 - Report current temperatures. * M106 - Fan on. @@ -210,7 +213,6 @@ * M364 - SCARA calibration: Move to cal-position PSIC (90 deg to Theta calibration position) * * ************ Custom codes - This can change to suit future G-code regulations - * M100 - Watch Free Memory (For Debugging). (Requires M100_FREE_MEMORY_WATCHER) * M928 - Start SD logging: "M928 filename.gco". Stop with M29. (Requires SDSUPPORT) * M999 - Restart after being stopped by error * From b17e2d3dcdd67cc39514a2f440f070d7bf0b8df7 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 11 May 2017 23:22:58 -0500 Subject: [PATCH 060/189] Apply const in Marlin_main.cpp --- Marlin/Marlin_main.cpp | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index adcbc1a59..adc2a903e 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -3731,7 +3731,7 @@ inline void gcode_G28() { // Disable the leveling matrix before homing #if HAS_LEVELING #if ENABLED(AUTO_BED_LEVELING_UBL) - const bool bed_leveling_state_at_entry = ubl.state.active; + const bool ubl_state_at_entry = ubl.state.active; #endif set_bed_leveling_enabled(false); #endif @@ -3874,8 +3874,9 @@ inline void gcode_G28() { // move to a height where we can use the full xy-area do_blocking_move_to_z(delta_clip_start_height); #endif + #if ENABLED(AUTO_BED_LEVELING_UBL) - set_bed_leveling_enabled(bed_leveling_state_at_entry); + set_bed_leveling_enabled(ubl_state_at_entry); #endif clean_up_after_endstop_or_probe_move(); @@ -11119,7 +11120,7 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) { inline bool prepare_kinematic_move_to(float ltarget[XYZE]) { // Get the top feedrate of the move in the XY plane - float _feedrate_mm_s = MMS_SCALED(feedrate_mm_s); + const float _feedrate_mm_s = MMS_SCALED(feedrate_mm_s); // If the move is only in Z/E don't split up the move if (ltarget[X_AXIS] == current_position[X_AXIS] && ltarget[Y_AXIS] == current_position[Y_AXIS]) { @@ -11144,7 +11145,7 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) { if (UNEAR_ZERO(cartesian_mm)) return true; // Minimum number of seconds to move the given distance - float seconds = cartesian_mm / _feedrate_mm_s; + const float seconds = cartesian_mm / _feedrate_mm_s; // The number of segments-per-second times the duration // gives the number of segments @@ -11434,7 +11435,7 @@ void prepare_move_to_destination() { if (angular_travel == 0 && current_position[X_AXIS] == logical[X_AXIS] && current_position[Y_AXIS] == logical[Y_AXIS]) angular_travel += RADIANS(360); - float mm_of_travel = HYPOT(angular_travel * radius, fabs(linear_travel)); + const float mm_of_travel = HYPOT(angular_travel * radius, fabs(linear_travel)); if (mm_of_travel < 0.001) return; uint16_t segments = floor(mm_of_travel / (MM_PER_ARC_SEGMENT)); From 233f824dd6f6a935738a3bd425ce3cf222807239 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 11 May 2017 23:22:35 -0500 Subject: [PATCH 061/189] Define GRID_MAX_POINTS --- Marlin/Conditionals_post.h | 3 +++ Marlin/Marlin_main.cpp | 10 ++++------ Marlin/configuration_store.cpp | 4 ++-- Marlin/ubl_G29.cpp | 4 ++-- Marlin/ultralcd.cpp | 16 ++++++---------- 5 files changed, 17 insertions(+), 20 deletions(-) diff --git a/Marlin/Conditionals_post.h b/Marlin/Conditionals_post.h index 2a1f4e0b8..5280da81a 100644 --- a/Marlin/Conditionals_post.h +++ b/Marlin/Conditionals_post.h @@ -836,4 +836,7 @@ #endif #endif + // Shorthand + #define GRID_MAX_POINTS ((GRID_MAX_POINTS_X) * (GRID_MAX_POINTS_Y)) + #endif // CONDITIONALS_POST_H diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index adc2a903e..cf13f15fd 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -4031,7 +4031,7 @@ void home_all_axes() { gcode_G28(); } #endif } // If there's another point to sample, move there with optional lift. - if (mbl_probe_index < (GRID_MAX_POINTS_X) * (GRID_MAX_POINTS_Y)) { + if (mbl_probe_index < GRID_MAX_POINTS) { mbl.zigzag(mbl_probe_index, px, py); _manual_goto_xy(mbl.index_to_xpos[px], mbl.index_to_ypos[py]); @@ -4250,8 +4250,6 @@ void home_all_axes() { gcode_G28(); } ABL_VAR int left_probe_bed_position, right_probe_bed_position, front_probe_bed_position, back_probe_bed_position; ABL_VAR float xGridSpacing, yGridSpacing; - #define ABL_GRID_MAX (GRID_MAX_POINTS_X) * (GRID_MAX_POINTS_Y) - #if ABL_PLANAR ABL_VAR uint8_t abl_grid_points_x = GRID_MAX_POINTS_X, abl_grid_points_y = GRID_MAX_POINTS_Y; @@ -4265,7 +4263,7 @@ void home_all_axes() { gcode_G28(); } #if ABL_PLANAR ABL_VAR int abl2; #else // 3-point - int constexpr abl2 = ABL_GRID_MAX; + int constexpr abl2 = GRID_MAX_POINTS; #endif #endif @@ -4277,8 +4275,8 @@ void home_all_axes() { gcode_G28(); } ABL_VAR int indexIntoAB[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y]; - ABL_VAR float eqnAMatrix[ABL_GRID_MAX * 3], // "A" matrix of the linear system of equations - eqnBVector[ABL_GRID_MAX], // "B" vector of Z points + ABL_VAR float eqnAMatrix[GRID_MAX_POINTS * 3], // "A" matrix of the linear system of equations + eqnBVector[GRID_MAX_POINTS], // "B" vector of Z points mean; #endif diff --git a/Marlin/configuration_store.cpp b/Marlin/configuration_store.cpp index fe815af2c..201c03558 100644 --- a/Marlin/configuration_store.cpp +++ b/Marlin/configuration_store.cpp @@ -342,7 +342,7 @@ void MarlinSettings::postprocess() { #if ENABLED(MESH_BED_LEVELING) // Compile time test that sizeof(mbl.z_values) is as expected static_assert( - sizeof(mbl.z_values) == (GRID_MAX_POINTS_X) * (GRID_MAX_POINTS_Y) * sizeof(mbl.z_values[0][0]), + sizeof(mbl.z_values) == GRID_MAX_POINTS * sizeof(mbl.z_values[0][0]), "MBL Z array is the wrong size." ); const bool leveling_is_on = TEST(mbl.status, MBL_STATUS_HAS_MESH_BIT); @@ -386,7 +386,7 @@ void MarlinSettings::postprocess() { #if ENABLED(AUTO_BED_LEVELING_BILINEAR) // Compile time test that sizeof(z_values) is as expected static_assert( - sizeof(z_values) == (GRID_MAX_POINTS_X) * (GRID_MAX_POINTS_Y) * sizeof(z_values[0][0]), + sizeof(z_values) == GRID_MAX_POINTS * sizeof(z_values[0][0]), "Bilinear Z array is the wrong size." ); const uint8_t grid_max_x = GRID_MAX_POINTS_X, grid_max_y = GRID_MAX_POINTS_Y; diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 281182166..a44e9ee12 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -1048,8 +1048,8 @@ repeat_flag = code_seen('R'); if (repeat_flag) { - repetition_cnt = code_has_value() ? code_value_int() : (GRID_MAX_POINTS_X) * (GRID_MAX_POINTS_Y); - repetition_cnt = min(repetition_cnt, (GRID_MAX_POINTS_X) * (GRID_MAX_POINTS_Y)); + repetition_cnt = code_has_value() ? code_value_int() : GRID_MAX_POINTS; + NOMORE(repetition_cnt, GRID_MAX_POINTS); if (repetition_cnt < 1) { SERIAL_PROTOCOLLNPGM("?(R)epetition count invalid (1+).\n"); return UBL_ERR; diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index f563c09cc..a398a4fda 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -1430,17 +1430,13 @@ void kill_screen(const char* lcd_msg) { #endif // LCD probed points are from defaults - constexpr uint8_t total_probe_points = - #if ABL_GRID - (GRID_MAX_POINTS_X) * (GRID_MAX_POINTS_Y) - #elif ENABLED(AUTO_BED_LEVELING_3POINT) - int(3) - #elif ENABLED(AUTO_BED_LEVELING_UBL) - (GRID_MAX_POINTS_X) * (GRID_MAX_POINTS_Y) - #elif ENABLED(MESH_BED_LEVELING) - (GRID_MAX_POINTS_X) * (GRID_MAX_POINTS_Y) + constexpr uint8_t total_probe_points = ( + #if ENABLED(AUTO_BED_LEVELING_3POINT) + 3 + #elif ABL_GRID || ENABLED(AUTO_BED_LEVELING_UBL) || ENABLED(MESH_BED_LEVELING) + GRID_MAX_POINTS #endif - ; + ); #if ENABLED(MESH_BED_LEVELING) From cbfca29522db6da791ac3b8359637cc8c07f4294 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 12 May 2017 00:00:27 -0500 Subject: [PATCH 062/189] M421 tweaks, just to use const --- Marlin/Marlin_main.cpp | 71 ++++++++++++++++++++---------------------- 1 file changed, 34 insertions(+), 37 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index cf13f15fd..64ad8b4de 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -8414,17 +8414,15 @@ void quickstop_stepper() { * Use either 'M421 X Y Z' or 'M421 I J Z' */ inline void gcode_M421() { - int8_t px = 0, py = 0; - float z = 0; - bool hasX, hasY, hasZ, hasI, hasJ; - if ((hasX = code_seen('X'))) px = mbl.probe_index_x(code_value_linear_units()); - if ((hasY = code_seen('Y'))) py = mbl.probe_index_y(code_value_linear_units()); - if ((hasI = code_seen('I'))) px = code_value_linear_units(); - if ((hasJ = code_seen('J'))) py = code_value_linear_units(); - if ((hasZ = code_seen('Z'))) z = code_value_linear_units(); - if (hasX && hasY && hasZ) { + const bool hasX = code_seen('X'), hasI = !hasX && code_seen('I'); + const int8_t px = hasX || hasI ? mbl.probe_index_x(code_value_linear_units()) : 0; + const bool hasY = code_seen('Y'), hasJ = !hasY && code_seen('J'); + const int8_t py = hasY || hasJ ? mbl.probe_index_y(code_value_linear_units()) : 0; + const bool hasZ = code_seen('Z'); + const float z = hasZ ? code_value_linear_units() : 0; + if (hasX && hasY && hasZ) { if (px >= 0 && py >= 0) mbl.set_z(px, py, z); else { @@ -8451,18 +8449,18 @@ void quickstop_stepper() { /** * M421: Set a single Mesh Bed Leveling Z coordinate * + * Usage: * M421 I J Z - * or * M421 I J Q */ inline void gcode_M421() { - int8_t px = 0, py = 0; - float z = 0; - bool hasI, hasJ, hasZ, hasQ; - if ((hasI = code_seen('I'))) px = code_value_int(); - if ((hasJ = code_seen('J'))) py = code_value_int(); - if ((hasZ = code_seen('Z'))) z = code_value_linear_units(); - if ((hasQ = code_seen('Q'))) z = code_value_linear_units(); + + const bool hasI = code_seen('I'); + const int8_t px = hasI ? code_value_int() : 0; + const bool hasJ = code_seen('J'); + const int8_t py = hasJ ? code_value_int() : 0; + const bool hasZ = code_seen('Z'), hasQ = !hasZ && code_seen('Q'); + const float z = hasZ || hasQ ? code_value_linear_units() : 0; if (!hasI || !hasJ || (hasQ && hasZ) || (!hasQ && !hasZ)) { SERIAL_ERROR_START; @@ -8495,35 +8493,33 @@ void quickstop_stepper() { /** * M421: Set a single Mesh Bed Leveling Z coordinate * + * Usage: * M421 I J Z - * or * M421 I J Q + * M421 C Z + * M421 C Q */ - //todo: change multiple points simultaneously? - inline void gcode_M421() { - int8_t px = 0, py = 0; - float z = 0; - bool hasI, hasJ, hasZ, hasQ, hasC; - if ((hasI = code_seen('I'))) px = code_value_int(); - if ((hasJ = code_seen('J'))) py = code_value_int(); - if ((hasZ = code_seen('Z'))) z = code_value_linear_units(); - if ((hasQ = code_seen('Q'))) z = code_value_linear_units(); - hasC = code_seen('C'); - - if ( (!(hasI && hasJ) && !hasC) || (hasQ && hasZ) || (!hasQ && !hasZ)) { + + // Get the closest position for 'C', if needed + const mesh_index_pair location = find_closest_mesh_point_of_type(REAL, current_position[X_AXIS], current_position[Y_AXIS], USE_NOZZLE_AS_REFERENCE, NULL, false); + + const bool hasC = code_seen('C'), hasI = code_seen('I'); + const int8_t px = hasC ? location.x_index : hasI ? code_value_int() : 0; + + const bool hasJ = code_seen('J'); + const int8_t py = hasC ? location.y_index : hasJ ? code_value_int() : 0; + + const bool hasZ = code_seen('Z'), hasQ = !hasZ && code_seen('Q'); + const float z = hasZ || hasQ ? code_value_linear_units() : 0; + + if ( ((hasI && hasJ) == hasC) || (hasQ && hasZ) || (!hasQ && !hasZ)) { SERIAL_ERROR_START; SERIAL_ERRORLNPGM(MSG_ERR_M421_PARAMETERS); return; } - if (hasC) { // get closest position - const mesh_index_pair location = find_closest_mesh_point_of_type(REAL, current_position[X_AXIS], current_position[Y_AXIS], USE_NOZZLE_AS_REFERENCE, NULL, false); - px = location.x_index; - py = location.y_index; - } - if (WITHIN(px, 0, GRID_MAX_POINTS_X - 1) && WITHIN(py, 0, GRID_MAX_POINTS_Y - 1)) { if (hasZ) // doing an absolute mesh value ubl.z_values[px][py] = z; @@ -8535,7 +8531,8 @@ void quickstop_stepper() { SERIAL_ERRORLNPGM(MSG_ERR_MESH_XY); } } -#endif + +#endif // AUTO_BED_LEVELING_UBL #if HAS_M206_COMMAND From 0696dda4700589ccf88dfb4470180a556ff6b3a2 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 12 May 2017 01:05:11 -0500 Subject: [PATCH 063/189] Cleanups to UBL_DELTA --- Marlin/Conditionals_post.h | 10 +- Marlin/G26_Mesh_Validation_Tool.cpp | 13 +-- Marlin/Marlin_main.cpp | 43 ++++---- Marlin/SanityCheck.h | 29 ++---- Marlin/planner.cpp | 20 ++-- Marlin/ubl_motion.cpp | 149 +++++++++++++--------------- 6 files changed, 116 insertions(+), 148 deletions(-) diff --git a/Marlin/Conditionals_post.h b/Marlin/Conditionals_post.h index 5280da81a..b303b65aa 100644 --- a/Marlin/Conditionals_post.h +++ b/Marlin/Conditionals_post.h @@ -731,15 +731,12 @@ * Set granular options based on the specific type of leveling */ - #if ENABLED(AUTO_BED_LEVELING_UBL) && ENABLED(DELTA) - #define UBL_DELTA - #endif - + #define UBL_DELTA (ENABLED(AUTO_BED_LEVELING_UBL) && ENABLED(DELTA)) #define ABL_PLANAR (ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_3POINT)) #define ABL_GRID (ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)) #define HAS_ABL (ABL_PLANAR || ABL_GRID || ENABLED(AUTO_BED_LEVELING_UBL)) #define HAS_LEVELING (HAS_ABL || ENABLED(MESH_BED_LEVELING)) - #define PLANNER_LEVELING (ABL_PLANAR || ABL_GRID || ENABLED(MESH_BED_LEVELING) || ENABLED(UBL_DELTA)) + #define PLANNER_LEVELING (ABL_PLANAR || ABL_GRID || ENABLED(MESH_BED_LEVELING) || UBL_DELTA) #define HAS_PROBING_PROCEDURE (HAS_ABL || ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST)) #if HAS_PROBING_PROCEDURE #define PROBE_BED_WIDTH abs(RIGHT_PROBE_BED_POSITION - (LEFT_PROBE_BED_POSITION)) @@ -823,8 +820,7 @@ /** * DELTA_SEGMENT_MIN_LENGTH for UBL_DELTA */ - - #if ENABLED(UBL_DELTA) + #if UBL_DELTA #ifndef DELTA_SEGMENT_MIN_LENGTH #if IS_SCARA #define DELTA_SEGMENT_MIN_LENGTH 0.25 // SCARA minimum segment size is 0.25mm diff --git a/Marlin/G26_Mesh_Validation_Tool.cpp b/Marlin/G26_Mesh_Validation_Tool.cpp index 4f231c2ae..0cf414735 100644 --- a/Marlin/G26_Mesh_Validation_Tool.cpp +++ b/Marlin/G26_Mesh_Validation_Tool.cpp @@ -278,8 +278,7 @@ // If this mesh location is outside the printable_radius, skip it. - if ( ! position_is_reachable_raw_xy( circle_x, circle_y )) - continue; + if (!position_is_reachable_raw_xy(circle_x, circle_y)) continue; xi = location.x_index; // Just to shrink the next few lines and make them easier to understand yi = location.y_index; @@ -329,9 +328,7 @@ ye = circle_y + sin_table[tmp_div_30 + 1]; #if IS_KINEMATIC // Check to make sure this segment is entirely on the bed, skip if not. - if (( ! position_is_reachable_raw_xy( x , y )) || - ( ! position_is_reachable_raw_xy( xe, ye ))) - continue; + if (!position_is_reachable_raw_xy(x, y) || !position_is_reachable_raw_xy(xe, ye)) continue; #else // not, we need to skip x = constrain(x, X_MIN_POS + 1, X_MAX_POS - 1); // This keeps us from bumping the endstops y = constrain(y, Y_MIN_POS + 1, Y_MAX_POS - 1); @@ -459,8 +456,7 @@ sy = ey = constrain(pgm_read_float(&ubl.mesh_index_to_ypos[j]), Y_MIN_POS + 1, Y_MAX_POS - 1); ex = constrain(ex, X_MIN_POS + 1, X_MAX_POS - 1); - if (( position_is_reachable_raw_xy( sx, sy )) && - ( position_is_reachable_raw_xy( ex, ey ))) { + if (position_is_reachable_raw_xy(sx, sy) && position_is_reachable_raw_xy(ex, ey)) { if (ubl.g26_debug_flag) { SERIAL_ECHOPAIR(" Connecting with horizontal line (sx=", sx); @@ -494,8 +490,7 @@ sy = constrain(sy, Y_MIN_POS + 1, Y_MAX_POS - 1); ey = constrain(ey, Y_MIN_POS + 1, Y_MAX_POS - 1); - if (( position_is_reachable_raw_xy( sx, sy )) && - ( position_is_reachable_raw_xy( ex, ey ))) { + if (position_is_reachable_raw_xy(sx, sy) && position_is_reachable_raw_xy(ex, ey)) { if (ubl.g26_debug_flag) { SERIAL_ECHOPAIR(" Connecting with vertical line (sx=", sx); diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 64ad8b4de..05ce02c95 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -2427,9 +2427,12 @@ static void clean_up_after_endstop_or_probe_move() { #elif ENABLED(AUTO_BED_LEVELING_UBL) - #if ENABLED(UBL_DELTA) - if (( ubl.state.active ) && ( ! enable )) { // leveling from on to off - planner.unapply_leveling(current_position); + #if PLANNER_LEVELING + if (ubl.state.active != enable) { + if (!enable) // leveling from on to off + planner.apply_leveling(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS]); + else + planner.unapply_leveling(current_position); } #endif @@ -11104,7 +11107,7 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) { #endif // AUTO_BED_LEVELING_BILINEAR -#if IS_KINEMATIC && DISABLED(UBL_DELTA) +#if IS_KINEMATIC && !UBL_DELTA /** * Prepare a linear move in a DELTA or SCARA setup. @@ -11124,7 +11127,7 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) { } // Fail if attempting move outside printable radius - if ( ! position_is_reachable_xy( ltarget[X_AXIS], ltarget[Y_AXIS] )) return true; + if (!position_is_reachable_xy(ltarget[X_AXIS], ltarget[Y_AXIS])) return true; // Get the cartesian distances moved in XYZE float difference[XYZE]; @@ -11225,7 +11228,7 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) { return false; } -#else // !IS_KINEMATIC +#else // !IS_KINEMATIC || UBL_DELTA /** * Prepare a linear move in a Cartesian setup. @@ -11263,7 +11266,7 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) { return false; } -#endif // !IS_KINEMATIC +#endif // !IS_KINEMATIC || UBL_DELTA #if ENABLED(DUAL_X_CARRIAGE) @@ -11375,21 +11378,21 @@ void prepare_move_to_destination() { #endif - #if IS_KINEMATIC - #if ENABLED(UBL_DELTA) - if (ubl_prepare_linear_move_to(destination,feedrate_mm_s)) return; - #else - if (prepare_kinematic_move_to(destination)) return; - #endif - #else - #if ENABLED(DUAL_X_CARRIAGE) - if (prepare_move_to_destination_dualx()) return; - #elif ENABLED(UBL_DELTA) // will work for CARTESIAN too (smaller segments follow mesh more closely) - if (ubl_prepare_linear_move_to(destination,feedrate_mm_s)) return; + if ( + #if IS_KINEMATIC + #if UBL_DELTA + ubl_prepare_linear_move_to(destination, feedrate_mm_s) + #else + prepare_kinematic_move_to(destination) + #endif + #elif ENABLED(DUAL_X_CARRIAGE) + prepare_move_to_destination_dualx() + #elif UBL_DELTA // will work for CARTESIAN too (smaller segments follow mesh more closely) + ubl_prepare_linear_move_to(destination, feedrate_mm_s) #else - if (prepare_move_to_destination_cartesian()) return; + prepare_move_to_destination_cartesian() #endif - #endif + ) return; set_current_to_destination(); } diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index 006bf6829..3aa307298 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -248,11 +248,9 @@ #if ENABLED(DELTA) #if DISABLED(USE_XMAX_PLUG) && DISABLED(USE_YMAX_PLUG) && DISABLED(USE_ZMAX_PLUG) #error "You probably want to use Max Endstops for DELTA!" - #endif - #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) && DISABLED(UBL_DELTA) - #error "ENABLE_LEVELING_FADE_HEIGHT for DELTA requires UBL_DELTA and AUTO_BED_LEVELING_UBL." - #endif - #if ABL_GRID + #elif ENABLED(ENABLE_LEVELING_FADE_HEIGHT) && DISABLED(AUTO_BED_LEVELING_BILINEAR) && !UBL_DELTA + #error "ENABLE_LEVELING_FADE_HEIGHT on DELTA requires AUTO_BED_LEVELING_BILINEAR or AUTO_BED_LEVELING_UBL." + #elif ABL_GRID #if (GRID_MAX_POINTS_X & 1) == 0 || (GRID_MAX_POINTS_Y & 1) == 0 #error "DELTA requires GRID_MAX_POINTS_X and GRID_MAX_POINTS_Y to be odd numbers." #elif GRID_MAX_POINTS_X < 3 @@ -431,20 +429,11 @@ static_assert(1 >= 0 * Unified Bed Leveling */ #if ENABLED(AUTO_BED_LEVELING_UBL) - #if IS_KINEMATIC - #if ENABLED(DELTA) - #if DISABLED(UBL_DELTA) - #error "AUTO_BED_LEVELING_UBL requires UBL_DELTA for DELTA printers." - #endif - #else // SCARA - #error "AUTO_BED_LEVELING_UBL not supported for SCARA printers." - #endif - #endif - #if DISABLED(NEWPANEL) + #if IS_SCARA + #error "AUTO_BED_LEVELING_UBL does not yet support SCARA printers." + #elif DISABLED(NEWPANEL) #error "AUTO_BED_LEVELING_UBL requires an LCD controller." #endif -#elif ENABLED(UBL_DELTA) - #error "UBL_DELTA requires AUTO_BED_LEVELING_UBL." #endif /** @@ -603,10 +592,8 @@ static_assert(1 >= 0 /** * Delta and SCARA have limited bed leveling options */ - #if IS_KINEMATIC - #if DISABLED(AUTO_BED_LEVELING_BILINEAR) && DISABLED(UBL_DELTA) - #error "Only AUTO_BED_LEVELING_BILINEAR or AUTO_BED_LEVELING_UBL with UBL_DELTA support DELTA and SCARA bed leveling." - #endif + #if IS_SCARA && DISABLED(AUTO_BED_LEVELING_BILINEAR) + #error "Only AUTO_BED_LEVELING_BILINEAR currently supports SCARA bed leveling." #endif /** diff --git a/Marlin/planner.cpp b/Marlin/planner.cpp index 8c641fc26..21a98a304 100644 --- a/Marlin/planner.cpp +++ b/Marlin/planner.cpp @@ -534,12 +534,12 @@ void Planner::check_axes_activity() { */ void Planner::apply_leveling(float &lx, float &ly, float &lz) { - #if ENABLED(AUTO_BED_LEVELING_UBL) && ENABLED(UBL_DELTA) // probably should also be enabled for UBL without UBL_DELTA + #if ENABLED(AUTO_BED_LEVELING_UBL) && UBL_DELTA // probably should also be enabled for UBL without UBL_DELTA if (!ubl.state.active) return; #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) // if z_fade_height enabled (nonzero) and raw_z above it, no leveling required if ((planner.z_fade_height) && (planner.z_fade_height <= RAW_Z_POSITION(lz))) return; - lz += ubl.state.z_offset + ( ubl.get_z_correction(lx,ly) * ubl.fade_scaling_factor_for_z(lz)); + lz += ubl.state.z_offset + ubl.get_z_correction(lx,ly) * ubl.fade_scaling_factor_for_z(lz); #else // no fade lz += ubl.state.z_offset + ubl.get_z_correction(lx,ly); #endif // FADE @@ -598,13 +598,13 @@ void Planner::check_axes_activity() { void Planner::unapply_leveling(float logical[XYZ]) { - #if ENABLED(AUTO_BED_LEVELING_UBL) && ENABLED(UBL_DELTA) + #if ENABLED(AUTO_BED_LEVELING_UBL) && UBL_DELTA - if ( ubl.state.active ) { + if (ubl.state.active) { - float z_leveled = RAW_Z_POSITION(logical[Z_AXIS]); - float z_ublmesh = ubl.get_z_correction(logical[X_AXIS],logical[Y_AXIS]); - float z_unlevel = z_leveled - ubl.state.z_offset - z_ublmesh; + const float z_leveled = RAW_Z_POSITION(logical[Z_AXIS]), + z_ublmesh = ubl.get_z_correction(logical[X_AXIS], logical[Y_AXIS]); + float z_unlevel = z_leveled - ubl.state.z_offset - z_ublmesh; #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) @@ -616,9 +616,9 @@ void Planner::check_axes_activity() { // so U(1-M/H)==L-O-M // so U==(L-O-M)/(1-M/H) for U Date: Fri, 12 May 2017 01:19:08 -0500 Subject: [PATCH 064/189] Add disclaimer for verboten parameters --- Marlin/G26_Mesh_Validation_Tool.cpp | 4 ++-- Marlin/ubl_G29.cpp | 19 ++++++++++--------- 2 files changed, 12 insertions(+), 11 deletions(-) diff --git a/Marlin/G26_Mesh_Validation_Tool.cpp b/Marlin/G26_Mesh_Validation_Tool.cpp index 0cf414735..e4fa01dd3 100644 --- a/Marlin/G26_Mesh_Validation_Tool.cpp +++ b/Marlin/G26_Mesh_Validation_Tool.cpp @@ -686,7 +686,7 @@ } } - if (code_seen('N') || code_seen('n')) { + if (code_seen('N') || code_seen('n')) { // Warning! Use of 'N' / lowercase flouts established standards. nozzle = code_value_float(); if (!WITHIN(nozzle, 0.1, 1.0)) { SERIAL_PROTOCOLLNPGM("?Specified nozzle size not plausible."); @@ -728,7 +728,7 @@ } } - if (code_seen('M')) { + if (code_seen('M')) { // Warning! Use of 'M' flouts established standards. randomSeed(millis()); // This setting will persist for the next G26 random_deviation = code_has_value() ? code_value_float() : 50.0; diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index a44e9ee12..63f904619 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -328,7 +328,8 @@ return; } - if (!code_seen('N') && axis_unhomed_error(true, true, true)) // Don't allow auto-leveling without homing first + // Don't allow auto-leveling without homing first + if (!code_seen('N') && axis_unhomed_error(true, true, true)) // Warning! Use of 'N' flouts established standards. home_all_axes(); if (g29_parameter_parsing()) return; // abort if parsing the simple parameters causes a problem, @@ -385,7 +386,7 @@ if (code_seen('J')) { ubl.save_ubl_active_state_and_disable(); - ubl.tilt_mesh_based_on_probed_grid(code_seen('O') || code_seen('M')); + ubl.tilt_mesh_based_on_probed_grid(code_seen('O') || code_seen('M')); // Warning! Use of 'M' flouts established standards. ubl.restore_ubl_active_state_and_leave(); } @@ -419,7 +420,7 @@ SERIAL_PROTOCOLLNPGM(").\n"); } ubl.probe_entire_mesh(x_pos + X_PROBE_OFFSET_FROM_EXTRUDER, y_pos + Y_PROBE_OFFSET_FROM_EXTRUDER, - code_seen('O') || code_seen('M'), code_seen('E'), code_seen('U')); + code_seen('O') || code_seen('M'), code_seen('E'), code_seen('U')); // Warning! Use of 'M' flouts established standards. break; case 2: { @@ -468,7 +469,7 @@ return; } - manually_probe_remaining_mesh(x_pos, y_pos, height, card_thickness, code_seen('O') || code_seen('M')); + manually_probe_remaining_mesh(x_pos, y_pos, height, card_thickness, code_seen('O') || code_seen('M')); // Warning! Use of 'M' flouts established standards. SERIAL_PROTOCOLLNPGM("G29 P2 finished."); } break; @@ -504,7 +505,7 @@ // // Fine Tune (i.e., Edit) the Mesh // - fine_tune_mesh(x_pos, y_pos, code_seen('O') || code_seen('M')); + fine_tune_mesh(x_pos, y_pos, code_seen('O') || code_seen('M')); // Warning! Use of 'M' flouts established standards. break; case 5: ubl.find_mean_mesh_height(); break; @@ -549,7 +550,7 @@ // When we are fully debugged, the EEPROM dump command will get deleted also. But // right now, it is good to have the extra information. Soon... we prune this. // - if (code_seen('j')) g29_eeprom_dump(); // EEPROM Dump + if (code_seen('j')) g29_eeprom_dump(); // Warning! Use of lowercase flouts established standards. // // When we are fully debugged, this may go away. But there are some valid @@ -613,7 +614,7 @@ SERIAL_PROTOCOLLNPGM("Done.\n"); } - if (code_seen('O') || code_seen('M')) + if (code_seen('O') || code_seen('M')) // Warning! Use of 'M' flouts established standards. ubl.display_map(code_has_value() ? code_value_int() : 0); if (code_seen('Z')) { @@ -1128,8 +1129,8 @@ SERIAL_PROTOCOLLNPGM("Invalid map type.\n"); return UBL_ERR; } - - if (code_seen('M')) { // Check if a map type was specified + // Check if a map type was specified + if (code_seen('M')) { // Warning! Use of 'M' flouts established standards. map_type = code_has_value() ? code_value_int() : 0; if (!WITHIN(map_type, 0, 1)) { SERIAL_PROTOCOLLNPGM("Invalid map type.\n"); From 68ae7c8d7a797f74674f0ed2687f19c497c2ea9e Mon Sep 17 00:00:00 2001 From: Markus Towara Date: Fri, 12 May 2017 12:13:23 +0200 Subject: [PATCH 065/189] Bugfix PRINTER_EVENT_LEDS Extra closing curly bracket terminates while loop early if PRINTER_EVENT_LEDS defined --- Marlin/Marlin_main.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 983ae939e..fcd20ab6f 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -6873,7 +6873,6 @@ inline void gcode_M109() { const uint8_t red = map(constrain(temp, start_temp, target_temp), start_temp, target_temp, 0, 255); if (red != old_red) set_led_color((old_red = red), 0, 255); } - } #endif #if TEMP_BED_RESIDENCY_TIME > 0 From 0e582bcfb71ccbd4968bf9252ff8c1be54fc5cab Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 12 May 2017 05:17:38 -0500 Subject: [PATCH 066/189] Fix #6691 - redundant line in M665 --- Marlin/Marlin_main.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 05ce02c95..5c8d70ff1 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -7623,7 +7623,6 @@ inline void gcode_M205() { if (code_seen('H')) { home_offset[Z_AXIS] = code_value_linear_units() - DELTA_HEIGHT; current_position[Z_AXIS] += code_value_linear_units() - DELTA_HEIGHT - home_offset[Z_AXIS]; - home_offset[Z_AXIS] = code_value_linear_units() - DELTA_HEIGHT; update_software_endstops(Z_AXIS); } if (code_seen('L')) delta_diagonal_rod = code_value_linear_units(); From a7fb55ea6dc14c98c6ba293f73a117064a92781d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 12 May 2017 06:48:15 -0500 Subject: [PATCH 067/189] Use GRID_MAX_POINTS. Some formatting --- Marlin/G26_Mesh_Validation_Tool.cpp | 7 ++----- Marlin/planner.cpp | 4 ++-- Marlin/ubl.h | 4 +--- Marlin/ubl_G29.cpp | 18 ++++++++---------- Marlin/ultralcd.cpp | 16 ++++++++-------- 5 files changed, 21 insertions(+), 28 deletions(-) diff --git a/Marlin/G26_Mesh_Validation_Tool.cpp b/Marlin/G26_Mesh_Validation_Tool.cpp index e4fa01dd3..596f24f12 100644 --- a/Marlin/G26_Mesh_Validation_Tool.cpp +++ b/Marlin/G26_Mesh_Validation_Tool.cpp @@ -69,7 +69,7 @@ * B # Bed Set the Bed Temperature. If not specified, a default of 60 C. will be assumed. * * C Current When searching for Mesh Intersection points to draw, use the current nozzle location - as the base for any distance comparison. + * as the base for any distance comparison. * * D Disable Disable the Unified Bed Leveling System. In the normal case the user is invoking this * command to see how well a Mesh as been adjusted to match a print surface. In order to do @@ -748,10 +748,7 @@ } /** - * We save the question of what to do with the Unified Bed Leveling System's Activation until the very - * end. The reason is, if one of the parameters specified up above is incorrect, we don't want to - * alter the system's status. We wait until we know everything is correct before altering the state - * of the system. + * Wait until all parameters are verified before altering the state! */ ubl.state.active = !code_seen('D'); diff --git a/Marlin/planner.cpp b/Marlin/planner.cpp index 21a98a304..155a4717f 100644 --- a/Marlin/planner.cpp +++ b/Marlin/planner.cpp @@ -539,7 +539,7 @@ void Planner::check_axes_activity() { #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) // if z_fade_height enabled (nonzero) and raw_z above it, no leveling required if ((planner.z_fade_height) && (planner.z_fade_height <= RAW_Z_POSITION(lz))) return; - lz += ubl.state.z_offset + ubl.get_z_correction(lx,ly) * ubl.fade_scaling_factor_for_z(lz); + lz += ubl.state.z_offset + ubl.get_z_correction(lx, ly) * ubl.fade_scaling_factor_for_z(lz); #else // no fade lz += ubl.state.z_offset + ubl.get_z_correction(lx,ly); #endif // FADE @@ -617,7 +617,7 @@ void Planner::check_axes_activity() { // so U==(L-O-M)/(1-M/H) for U= ( GRID_MAX_POINTS_X * GRID_MAX_POINTS_Y )) { + if (repetition_cnt >= GRID_MAX_POINTS) { for ( uint8_t x = 0; x < GRID_MAX_POINTS_X; x++ ) { for ( uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++ ) { ubl.z_values[x][y] = ubl_constant; @@ -735,7 +735,7 @@ ubl.save_ubl_active_state_and_disable(); // we don't do bed level correction because we want the raw data when we probe DEPLOY_PROBE(); - uint16_t max_iterations = ( GRID_MAX_POINTS_X * GRID_MAX_POINTS_Y ); + uint16_t max_iterations = GRID_MAX_POINTS; do { if (ubl_lcd_clicked()) { @@ -941,7 +941,7 @@ return thickness; } - void manually_probe_remaining_mesh(const float &lx, const float &ly, float &z_clearance, const float &card_thickness, const bool do_ubl_mesh_map) { + void manually_probe_remaining_mesh(const float &lx, const float &ly, const float &z_clearance, const float &card_thickness, const bool do_ubl_mesh_map) { ubl.has_control_of_lcd_panel = true; ubl.save_ubl_active_state_and_disable(); // we don't do bed level correction because we want the raw data when we probe @@ -956,14 +956,11 @@ if (location.x_index < 0 && location.y_index < 0) continue; const float rawx = pgm_read_float(&ubl.mesh_index_to_xpos[location.x_index]), - rawy = pgm_read_float(&ubl.mesh_index_to_ypos[location.y_index]); - - const float xProbe = LOGICAL_X_POSITION(rawx), + rawy = pgm_read_float(&ubl.mesh_index_to_ypos[location.y_index]), + xProbe = LOGICAL_X_POSITION(rawx), yProbe = LOGICAL_Y_POSITION(rawy); - if ( ! position_is_reachable_raw_xy( rawx, rawy )) { // SHOULD NOT OCCUR (find_closest_mesh_point only returns reachable points) - break; - } + if (!position_is_reachable_raw_xy(rawx, rawy)) break; // SHOULD NOT OCCUR (find_closest_mesh_point only returns reachable points) do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); @@ -1129,6 +1126,7 @@ SERIAL_PROTOCOLLNPGM("Invalid map type.\n"); return UBL_ERR; } + // Check if a map type was specified if (code_seen('M')) { // Warning! Use of 'M' flouts established standards. map_type = code_has_value() ? code_value_int() : 0; diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index a398a4fda..7a810d3e3 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -1674,13 +1674,13 @@ void kill_screen(const char* lcd_msg) { void _lcd_ubl_level_bed(); - int UBL_STORAGE_SLOT = 0; - int CUSTOM_BED_TEMP = 50; - int CUSTOM_HOTEND_TEMP = 190; - int SIDE_POINTS = 3; - int UBL_FILLIN_AMOUNT = 5; - int UBL_HEIGHT_AMOUNT; - int map_type; + int UBL_STORAGE_SLOT = 0, + CUSTOM_BED_TEMP = 50, + CUSTOM_HOTEND_TEMP = 190, + SIDE_POINTS = 3, + UBL_FILLIN_AMOUNT = 5, + UBL_HEIGHT_AMOUNT, + map_type; char UBL_LCD_GCODE [30]; @@ -1858,7 +1858,7 @@ void kill_screen(const char* lcd_msg) { * UBL Build Mesh submenu */ void _lcd_ubl_build_mesh() { - int GRID_NUM_POINTS = GRID_MAX_POINTS_X * GRID_MAX_POINTS_Y ; + int GRID_NUM_POINTS = GRID_MAX_POINTS; START_MENU(); MENU_BACK(MSG_UBL_TOOLS); #if (WATCH_THE_BED) From 37399e3cb593b05233a6c03ef80a107f69ca503c Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 13 May 2017 04:09:21 -0500 Subject: [PATCH 068/189] Fix prepare_move_to_destination_cartesian for UBL --- Marlin/Marlin_main.cpp | 56 ++++++++++++++++++++++-------------------- 1 file changed, 30 insertions(+), 26 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 6f6a15ea3..c31481c6c 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -11235,32 +11235,36 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) { * Returns true if the caller didn't update current_position. */ inline bool prepare_move_to_destination_cartesian() { - // Do not use feedrate_percentage for E or Z only moves - if (current_position[X_AXIS] == destination[X_AXIS] && current_position[Y_AXIS] == destination[Y_AXIS]) { - line_to_destination(); - } - else { - #if ENABLED(MESH_BED_LEVELING) - if (mbl.active()) { - mesh_line_to_destination(MMS_SCALED(feedrate_mm_s)); - return true; - } - else - #elif ENABLED(AUTO_BED_LEVELING_UBL) - if (ubl.state.active) { - ubl_line_to_destination_cartesian(MMS_SCALED(feedrate_mm_s), active_extruder); - return true; - } - else - #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) - if (planner.abl_enabled) { - bilinear_line_to_destination(MMS_SCALED(feedrate_mm_s)); - return true; - } - else - #endif - line_to_destination(MMS_SCALED(feedrate_mm_s)); - } + #if ENABLED(AUTO_BED_LEVELING_UBL) + const float fr_scaled = MMS_SCALED(feedrate_mm_s); + if (ubl.state.active) { + ubl_line_to_destination_cartesian(fr_scaled, active_extruder); + return true; + } + else + line_to_destination(fr_scaled); + #else + // Do not use feedrate_percentage for E or Z only moves + if (current_position[X_AXIS] == destination[X_AXIS] && current_position[Y_AXIS] == destination[Y_AXIS]) + line_to_destination(); + else { + const float fr_scaled = MMS_SCALED(feedrate_mm_s); + #if ENABLED(MESH_BED_LEVELING) + if (mbl.active()) { + mesh_line_to_destination(fr_scaled); + return true; + } + else + #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) + if (planner.abl_enabled) { + bilinear_line_to_destination(fr_scaled); + return true; + } + else + #endif + line_to_destination(fr_scaled); + } + #endif return false; } From 67c9b1e3325414c54ba5c7cb2844f6f6f1659df2 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 13 May 2017 05:11:29 -0500 Subject: [PATCH 069/189] Update M665 comment, fix M665 code_value code. --- Marlin/Marlin_main.cpp | 17 +++++++++-------- 1 file changed, 9 insertions(+), 8 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index c31481c6c..07a011cc6 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -7610,13 +7610,14 @@ inline void gcode_M205() { /** * M665: Set delta configurations * - * H = diagonal rod // AC-version + * H = delta height * L = diagonal rod * R = delta radius * S = segments per second - * A = Alpha (Tower 1) diagonal rod trim - * B = Beta (Tower 2) diagonal rod trim - * C = Gamma (Tower 3) diagonal rod trim + * B = delta calibration radius + * X = Alpha (Tower 1) angle trim + * Y = Beta (Tower 2) angle trim + * Z = Rotate A and B by this angle */ inline void gcode_M665() { if (code_seen('H')) { @@ -7628,11 +7629,11 @@ inline void gcode_M205() { if (code_seen('R')) delta_radius = code_value_linear_units(); if (code_seen('S')) delta_segments_per_second = code_value_float(); if (code_seen('B')) delta_calibration_radius = code_value_float(); - if (code_seen('X')) delta_tower_angle_trim[A_AXIS] = code_value_linear_units(); - if (code_seen('Y')) delta_tower_angle_trim[B_AXIS] = code_value_linear_units(); + if (code_seen('X')) delta_tower_angle_trim[A_AXIS] = code_value_float(); + if (code_seen('Y')) delta_tower_angle_trim[B_AXIS] = code_value_float(); if (code_seen('Z')) { // rotate all 3 axis for Z = 0 - delta_tower_angle_trim[A_AXIS] -= code_value_linear_units(); - delta_tower_angle_trim[B_AXIS] -= code_value_linear_units(); + delta_tower_angle_trim[A_AXIS] -= code_value_float(); + delta_tower_angle_trim[B_AXIS] -= code_value_float(); } recalc_delta_settings(delta_radius, delta_diagonal_rod); } From 15040821e05d2f4727baf93e7fe8b338c3b3af32 Mon Sep 17 00:00:00 2001 From: Roxy-3D Date: Sat, 13 May 2017 15:14:03 -0500 Subject: [PATCH 070/189] Setup FolgerTech-i3-2020 files better for the user (#6724) UltiPanel was enabled, but technically, it is a REPRAP_DISCOUNT_SMART_CONTROLLER Either configuration works on the machine. But we want it 'Right'. Setup the Proportional Font spacing so columns line up nicer on PronterFace and Repetier Host. --- .../example_configurations/FolgerTech-i3-2020/Configuration.h | 2 +- .../FolgerTech-i3-2020/Configuration_adv.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h index 1c473e035..268afb71f 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h @@ -1271,7 +1271,7 @@ // // ULTIPANEL as seen on Thingiverse. // -#define ULTIPANEL +//#define ULTIPANEL // // Cartesio UI diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h index b818e90f1..62025ff15 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h @@ -1173,6 +1173,6 @@ * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust * accordingly for your client and font. */ -#define PROPORTIONAL_FONT_RATIO 1.0 +#define PROPORTIONAL_FONT_RATIO 1.5 #endif // CONFIGURATION_ADV_H From c06af63f87ffe32848f0662c7920f7dc324107a4 Mon Sep 17 00:00:00 2001 From: Roxy-3D Date: Sat, 13 May 2017 15:53:44 -0500 Subject: [PATCH 071/189] G26's default behaviour ought to be the entire mesh (#6726) Adding the capability to specify ahead of time how much of the validation pattern to print made it so by default G26 only did one circle and no connecting lines. It is more natural for the unsophisticated user to just do the entire mesh (bed). We default the repetition count to GRID_MAX_POINTS+1 to insure we get every last one of them! --- Marlin/G26_Mesh_Validation_Tool.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/G26_Mesh_Validation_Tool.cpp b/Marlin/G26_Mesh_Validation_Tool.cpp index 596f24f12..58369a68f 100644 --- a/Marlin/G26_Mesh_Validation_Tool.cpp +++ b/Marlin/G26_Mesh_Validation_Tool.cpp @@ -734,7 +734,7 @@ random_deviation = code_has_value() ? code_value_float() : 50.0; } - g26_repeats = code_seen('R') ? (code_has_value() ? code_value_int() : 999) : 1; + g26_repeats = code_seen('R') ? (code_has_value() ? code_value_int() : GRID_MAX_POINTS+1) : GRID_MAX_POINTS+1; if (g26_repeats < 1) { SERIAL_PROTOCOLLNPGM("?(R)epeat value not plausible; must be at least 1."); return UBL_ERR; From 40d95a4e23a3207b11f13ebbdebc4a96a70d99c5 Mon Sep 17 00:00:00 2001 From: Roxy-3D Date: Sat, 13 May 2017 16:33:04 -0500 Subject: [PATCH 072/189] Update the gMax files to display better with Proportional Fonts (#6727) Update the gMax files to display better with Proportional Fonts --- .../example_configurations/gCreate_gMax1.5+/Configuration_adv.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h index 3f38210b5..52bc16cbc 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h @@ -1173,6 +1173,6 @@ * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust * accordingly for your client and font. */ -#define PROPORTIONAL_FONT_RATIO 1.0 +#define PROPORTIONAL_FONT_RATIO 1.5 #endif // CONFIGURATION_ADV_H From 645096b87a5b1077835e336b9920ad5152e12368 Mon Sep 17 00:00:00 2001 From: Aaron Busca Date: Sun, 14 May 2017 18:29:50 +0200 Subject: [PATCH 073/189] Updated Basque translation Updated Basque translation with new strings. --- Marlin/language_eu.h | 165 +++++++++++++++++++++++++++++++------------ 1 file changed, 120 insertions(+), 45 deletions(-) diff --git a/Marlin/language_eu.h b/Marlin/language_eu.h index 063d161b4..dc6d51338 100644 --- a/Marlin/language_eu.h +++ b/Marlin/language_eu.h @@ -33,35 +33,48 @@ #define DISPLAY_CHARSET_ISO10646_1 #define WELCOME_MSG MACHINE_NAME _UxGT(" prest.") +#define MSG_BACK _UxGT("Atzera") #define MSG_SD_INSERTED _UxGT("Txartela sartuta") #define MSG_SD_REMOVED _UxGT("Txartela kenduta") +#define MSG_LCD_ENDSTOPS _UxGT("Endstops") // Max length 8 characters #define MSG_MAIN _UxGT("Menu nagusia") #define MSG_AUTOSTART _UxGT("Auto hasiera") #define MSG_DISABLE_STEPPERS _UxGT("Itzali motoreak") +#define MSG_DEBUG_MENU _UxGT("Arazketa Menua") +#define MSG_PROGRESS_BAR_TEST _UxGT("Prog. Barra Proba") #define MSG_AUTO_HOME _UxGT("Hasierara joan") -#define MSG_LEVEL_BED_HOMING _UxGT("Homing XYZ") -#define MSG_LEVEL_BED_WAITING _UxGT("Click to Begin") -#define MSG_LEVEL_BED_DONE _UxGT("Leveling Done!") -#define MSG_LEVEL_BED_CANCEL _UxGT("Cancel") -#define MSG_SET_HOME_OFFSETS _UxGT("Set home offsets") -#define MSG_HOME_OFFSETS_APPLIED _UxGT("Offsets applied") +#define MSG_AUTO_HOME_X _UxGT("X jatorria") +#define MSG_AUTO_HOME_Y _UxGT("Y jatorria") +#define MSG_AUTO_HOME_Z _UxGT("Z jatorria") +#define MSG_LEVEL_BED_HOMING _UxGT("XYZ hasieraratzen") +#define MSG_LEVEL_BED_WAITING _UxGT("Klik egin hasteko") +#define MSG_LEVEL_BED_NEXT_POINT _UxGT("Hurrengo Puntua") +#define MSG_LEVEL_BED_DONE _UxGT("Berdintzea eginda") +#define MSG_LEVEL_BED_CANCEL _UxGT("Ezeztatu") +#define MSG_SET_HOME_OFFSETS _UxGT("Etxe. offset eza.") +#define MSG_HOME_OFFSETS_APPLIED _UxGT("Offsetak ezarrita") #define MSG_SET_ORIGIN _UxGT("Hasiera ipini") -#define MSG_PREHEAT_1 _UxGT("Aurreberotu PLA") -#define MSG_PREHEAT_1_N _UxGT("Aurreberotu PLA ") -#define MSG_PREHEAT_1_ALL _UxGT("Berotu PLA Guztia") -#define MSG_PREHEAT_1_BEDONLY _UxGT("Berotu PLA Ohea") -#define MSG_PREHEAT_1_SETTINGS _UxGT("Berotu PLA Konfig") -#define MSG_PREHEAT_2 _UxGT("Aurreberotu ABS") -#define MSG_PREHEAT_2_N _UxGT("Aurreberotu ABS ") -#define MSG_PREHEAT_2_ALL _UxGT("Berotu ABS Guztia") -#define MSG_PREHEAT_2_BEDONLY _UxGT("Berotu ABS Ohea") -#define MSG_PREHEAT_2_SETTINGS _UxGT("Berotu ABS Konfig") +#define MSG_PREHEAT_1 _UxGT("Berotu PLA") +#define MSG_PREHEAT_1_N MSG_PREHEAT_1 _UxGT(" ") +#define MSG_PREHEAT_1_ALL MSG_PREHEAT_1 _UxGT(" Guztia") +#define MSG_PREHEAT_1_END MSG_PREHEAT_1 _UxGT(" Amaia") +#define MSG_PREHEAT_1_BEDONLY MSG_PREHEAT_1 _UxGT(" Ohea") +#define MSG_PREHEAT_1_SETTINGS MSG_PREHEAT_1 _UxGT(" konf.") +#define MSG_PREHEAT_2 _UxGT("Berotu ABS") +#define MSG_PREHEAT_2_N MSG_PREHEAT_1 _UxGT(" ") +#define MSG_PREHEAT_2_ALL MSG_PREHEAT_1 _UxGT(" Guztia") +#define MSG_PREHEAT_2_END MSG_PREHEAT_2 _UxGT(" Amaia") +#define MSG_PREHEAT_2_BEDONLY MSG_PREHEAT_1 _UxGT(" Ohea") +#define MSG_PREHEAT_2_SETTINGS MSG_PREHEAT_1 _UxGT(" konf.") #define MSG_COOLDOWN _UxGT("Hoztu") #define MSG_SWITCH_PS_ON _UxGT("Energia piztu") #define MSG_SWITCH_PS_OFF _UxGT("Energia itzali") #define MSG_EXTRUDE _UxGT("Estruitu") #define MSG_RETRACT _UxGT("Atzera eragin") #define MSG_MOVE_AXIS _UxGT("Ardatzak mugitu") +#define MSG_LEVEL_BED _UxGT("Ohea Berdindu") +#define MSG_MOVING _UxGT("Mugitzen...") +#define MSG_FREE_XY _UxGT("Askatu XY") #define MSG_MOVE_X _UxGT("Mugitu X") #define MSG_MOVE_Y _UxGT("Mugitu Y") #define MSG_MOVE_Z _UxGT("Mugitu Z") @@ -70,14 +83,15 @@ #define MSG_MOVE_1MM _UxGT("Mugitu 1mm") #define MSG_MOVE_10MM _UxGT("Mugitu 10mm") #define MSG_SPEED _UxGT("Abiadura") +#define MSG_BED_Z _UxGT("Z Ohea") #define MSG_NOZZLE _UxGT("Pita") #define MSG_BED _UxGT("Ohea") -#define MSG_FAN_SPEED _UxGT("Haizagailua") +#define MSG_FAN_SPEED _UxGT("Haizagailu abiada") #define MSG_FLOW _UxGT("Fluxua") #define MSG_CONTROL _UxGT("Kontrola") -#define MSG_MIN LCD_STR_THERMOMETER _UxGT(" Min") -#define MSG_MAX LCD_STR_THERMOMETER _UxGT(" Max") -#define MSG_FACTOR LCD_STR_THERMOMETER _UxGT(" Faktorea") +#define MSG_MIN _UxGT(" ") LCD_STR_THERMOMETER _UxGT(" Min") +#define MSG_MAX _UxGT(" ") LCD_STR_THERMOMETER _UxGT(" Max") +#define MSG_FACTOR _UxGT(" ") LCD_STR_THERMOMETER _UxGT(" Fakt") #define MSG_AUTOTEMP _UxGT("Auto tenperatura") #define MSG_ON _UxGT("On ") #define MSG_OFF _UxGT("Off") @@ -85,6 +99,7 @@ #define MSG_PID_I _UxGT("PID-I") #define MSG_PID_D _UxGT("PID-D") #define MSG_PID_C _UxGT("PID-C") +#define MSG_SELECT _UxGT("Aukeratu") #define MSG_ACC _UxGT("Azelerazioa") #define MSG_VX_JERK _UxGT("Vx-astindua") #define MSG_VY_JERK _UxGT("Vy-astindua") @@ -92,9 +107,10 @@ #define MSG_VE_JERK _UxGT("Ve-astindua") #define MSG_VMAX _UxGT("Vmax ") #define MSG_VMIN _UxGT("Vmin") -#define MSG_VTRAV_MIN _UxGT("VTrav min") +#define MSG_VTRAV_MIN _UxGT("VBidaia min") #define MSG_AMAX _UxGT("Amax ") #define MSG_A_RETRACT _UxGT("A-retrakt") +#define MSG_A_TRAVEL _UxGT("A-bidaia") #define MSG_XSTEPS _UxGT("X pausoak/mm") #define MSG_YSTEPS _UxGT("Y pausoak/mm") #define MSG_ZSTEPS _UxGT("Z pausoak/mm") @@ -106,9 +122,10 @@ #define MSG_E5STEPS _UxGT("E5 pausoak/mm") #define MSG_TEMPERATURE _UxGT("Tenperatura") #define MSG_MOTION _UxGT("Mugimendua") -#define MSG_FILAMENT _UxGT("Filament") -#define MSG_VOLUMETRIC_ENABLED _UxGT("E in mm3") -#define MSG_FILAMENT_DIAM _UxGT("Fil. Dia.") +#define MSG_FILAMENT _UxGT("Harizpia") +#define MSG_VOLUMETRIC_ENABLED _UxGT("E mm3-tan") +#define MSG_FILAMENT_DIAM _UxGT("Hariz. Dia.") +#define MSG_ADVANCE_K _UxGT("K Aurrerapena") #define MSG_CONTRAST _UxGT("LCD kontrastea") #define MSG_STORE_EEPROM _UxGT("Gorde memoria") #define MSG_LOAD_EEPROM _UxGT("Kargatu memoria") @@ -121,37 +138,95 @@ #define MSG_RESUME_PRINT _UxGT("Jarraitu inprima.") #define MSG_STOP_PRINT _UxGT("Gelditu inprima.") #define MSG_CARD_MENU _UxGT("SD-tik inprimatu") -#define MSG_NO_CARD _UxGT("Ez dago txartelik") +#define MSG_NO_CARD _UxGT("Ez dago SD-rik") #define MSG_DWELL _UxGT("Lo egin...") #define MSG_USERWAIT _UxGT("Aginduak zain...") #define MSG_RESUMING _UxGT("Jarraitzen inpri.") -#define MSG_PRINT_ABORTED _UxGT("Print aborted") -#define MSG_NO_MOVE _UxGT("Mugimendu gabe") -#define MSG_KILLED _UxGT("LARRIALDI GELDIA") +#define MSG_PRINT_ABORTED _UxGT("Inprim. deusezta.") +#define MSG_NO_MOVE _UxGT("Mugimendu gabe.") +#define MSG_KILLED _UxGT("AKABATUTA. ") #define MSG_STOPPED _UxGT("GELDITUTA. ") #define MSG_CONTROL_RETRACT _UxGT("Atzera egin mm") -#define MSG_CONTROL_RETRACT_SWAP _UxGT("Swap Atzera egin mm") +#define MSG_CONTROL_RETRACT_SWAP _UxGT("Swap Atzera mm") #define MSG_CONTROL_RETRACTF _UxGT("Atzera egin V") #define MSG_CONTROL_RETRACT_ZLIFT _UxGT("Igo mm") #define MSG_CONTROL_RETRACT_RECOVER _UxGT("Atzera egin mm") -#define MSG_CONTROL_RETRACT_RECOVER_SWAP _UxGT("Swap Atzera egin mm") +#define MSG_CONTROL_RETRACT_RECOVER_SWAP _UxGT("Swap Atzera mm") #define MSG_CONTROL_RETRACT_RECOVERF _UxGT("Atzera egin V") #define MSG_AUTORETRACT _UxGT("Atzera egin") -#define MSG_FILAMENTCHANGE _UxGT("Aldatu filament.") -#define MSG_INIT_SDCARD _UxGT("Hasieratu txartela") +#define MSG_FILAMENTCHANGE _UxGT("Aldatu harizpia") +#define MSG_INIT_SDCARD _UxGT("Hasieratu SD-a") #define MSG_CNG_SDCARD _UxGT("Aldatu txartela") -#define MSG_ZPROBE_OUT _UxGT("Z ohe hasiera") -#define MSG_HOME _UxGT("Home") // Used as MSG_HOME " " MSG_X MSG_Y MSG_Z " " MSG_FIRST -#define MSG_FIRST _UxGT("first") -#define MSG_ZPROBE_ZOFFSET _UxGT("Z konpentsatu") -#define MSG_BABYSTEP_X _UxGT("Babystep X") -#define MSG_BABYSTEP_Y _UxGT("Babystep Y") -#define MSG_BABYSTEP_Z _UxGT("Babystep Z") -#define MSG_ENDSTOP_ABORT _UxGT("Endstop deuseztat") -#define MSG_DELTA_CALIBRATE _UxGT("Delta Calibration") -#define MSG_DELTA_CALIBRATE_X _UxGT("Calibrate X") -#define MSG_DELTA_CALIBRATE_Y _UxGT("Calibrate Y") -#define MSG_DELTA_CALIBRATE_Z _UxGT("Calibrate Z") -#define MSG_DELTA_CALIBRATE_CENTER _UxGT("Calibrate Center") +#define MSG_ZPROBE_OUT _UxGT("Z zunda kanpora") +#define MSG_BLTOUCH_SELFTEST _UxGT("BLTouch AutoProba") +#define MSG_BLTOUCH_RESET _UxGT("BLTouch berrabia.") +#define MSG_HOME _UxGT("Etxera") // Used as MSG_HOME " " MSG_X MSG_Y MSG_Z " " MSG_FIRST +#define MSG_FIRST _UxGT("lehenengo") +#define MSG_ZPROBE_ZOFFSET _UxGT("Z Konpentsatu") +#define MSG_BABYSTEP_X _UxGT("Mikro-urratsa X") +#define MSG_BABYSTEP_Y _UxGT("Mikro-urratsa Y") +#define MSG_BABYSTEP_Z _UxGT("Mikro-urratsa Z") +#define MSG_ENDSTOP_ABORT _UxGT("Endstop deusezta.") +#define MSG_HEATING_FAILED_LCD _UxGT("Err: Beroketa") +#define MSG_ERR_REDUNDANT_TEMP _UxGT("Err: Tenperatura") +#define MSG_THERMAL_RUNAWAY _UxGT("TENP. KONTROL EZA") +#define MSG_ERR_MAXTEMP _UxGT("Err: Tenp Maximoa") +#define MSG_ERR_MINTEMP _UxGT("Err: Tenp Minimoa") +#define MSG_ERR_MAXTEMP_BED _UxGT("Err: Ohe Tenp Max") +#define MSG_ERR_MINTEMP_BED _UxGT("Err: Ohe Tenp Min") +#define MSG_ERR_Z_HOMING _UxGT("G28 Z Debekatua") +#define MSG_HALTED _UxGT("INPRIMA. GELDIRIK") +#define MSG_PLEASE_RESET _UxGT("Berrabia. Mesedez") +#define MSG_SHORT_DAY _UxGT("d") // One character only +#define MSG_SHORT_HOUR _UxGT("h") // One character only +#define MSG_SHORT_MINUTE _UxGT("m") // One character only +#define MSG_HEATING _UxGT("Berotzen...") +#define MSG_HEATING_COMPLETE _UxGT("Berotzea prest.") +#define MSG_BED_HEATING _UxGT("Ohea Berotzen.") +#define MSG_BED_DONE _UxGT("Ohea Berotuta.") +#define MSG_DELTA_CALIBRATE _UxGT("Delta Kalibraketa") +#define MSG_DELTA_CALIBRATE_X _UxGT("Kalibratu X") +#define MSG_DELTA_CALIBRATE_Y _UxGT("Kalibratu Y") +#define MSG_DELTA_CALIBRATE_Z _UxGT("Kalibratu Z") +#define MSG_DELTA_CALIBRATE_CENTER _UxGT("Kalibratu Zentrua") +#define MSG_DELTA_AUTO_CALIBRATE _UxGT("Auto Kalibraketa") +#define MSG_DELTA_HEIGHT_CALIBRATE _UxGT("Delta Alt. Ezar.") +#define MSG_INFO_MENU _UxGT("Inprimagailu Inf.") +#define MSG_INFO_PRINTER_MENU _UxGT("Inprimagailu Inf.") +#define MSG_INFO_STATS_MENU _UxGT("Inprima. estatis.") +#define MSG_INFO_BOARD_MENU _UxGT("Txartelaren Info.") +#define MSG_INFO_THERMISTOR_MENU _UxGT("Termistoreak") +#define MSG_INFO_EXTRUDERS _UxGT("Estrusoreak") +#define MSG_INFO_BAUDRATE _UxGT("Baudioak") +#define MSG_INFO_PROTOCOL _UxGT("Protokoloa") +#define MSG_LIGHTS_ON _UxGT("Kabina Argia ON") +#define MSG_LIGHTS_OFF _UxGT("Kabina Argia OFF") +#if LCD_WIDTH > 19 + #define MSG_INFO_PRINT_COUNT _UxGT("Inprim. Zenbaketa") + #define MSG_INFO_COMPLETED_PRINTS _UxGT("Burututa") + #define MSG_INFO_PRINT_TIME _UxGT("Inprim. denbora") + #define MSG_INFO_PRINT_LONGEST _UxGT("Imprimatze luzeena") + #define MSG_INFO_PRINT_FILAMENT _UxGT("Estruituta guztira") +#else + #define MSG_INFO_PRINT_COUNT _UxGT("Inprimatze") + #define MSG_INFO_COMPLETED_PRINTS _UxGT("Burututa") + #define MSG_INFO_PRINT_TIME _UxGT("Guztira") + #define MSG_INFO_PRINT_LONGEST _UxGT("Luzeena") + #define MSG_INFO_PRINT_FILAMENT _UxGT("Estrusio") +#endif +#define MSG_INFO_MIN_TEMP _UxGT("Tenp. Minimoa") +#define MSG_INFO_MAX_TEMP _UxGT("Tenp. Maximoa") +#define MSG_INFO_PSU _UxGT("Elikadura Iturria") +#define MSG_DRIVE_STRENGTH _UxGT("Driver Potentzia") +#define MSG_DAC_PERCENT _UxGT("Driver %") +#define MSG_DAC_EEPROM_WRITE _UxGT("Idatzi DAC EEPROM") + +#define MSG_FILAMENT_CHANGE_HEADER _UxGT("HARIZPIA ALDATU") +#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("ALDAKETA AUKERAK:") +#define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("Gehiago estruitu") +#define MSG_FILAMENT_CHANGE_OPTION_RESUME _UxGT("Inprima. jarraitu") + +#define MSG_FILAMENT_CHANGE_MINTEMP _UxGT("Tenp Minimoa ") +#define MSG_FILAMENT_CHANGE_NOZZLE _UxGT(" Pita: ") #endif // LANGUAGE_EU_H From 267f77b18b424f99c820c6a0aaa973630b837bc1 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 14 May 2017 15:57:37 -0500 Subject: [PATCH 074/189] More constraint on axis_unhomed_error --- Marlin/G26_Mesh_Validation_Tool.cpp | 2 +- Marlin/Marlin.h | 2 +- Marlin/Marlin_main.cpp | 34 ++++++++++++++--------------- Marlin/ubl_G29.cpp | 2 +- 4 files changed, 19 insertions(+), 21 deletions(-) diff --git a/Marlin/G26_Mesh_Validation_Tool.cpp b/Marlin/G26_Mesh_Validation_Tool.cpp index 58369a68f..105c78690 100644 --- a/Marlin/G26_Mesh_Validation_Tool.cpp +++ b/Marlin/G26_Mesh_Validation_Tool.cpp @@ -201,7 +201,7 @@ // Don't allow Mesh Validation without homing first, // or if the parameter parsing did not go OK, abort - if (axis_unhomed_error(true, true, true) || parse_G26_parameters()) return; + if (axis_unhomed_error() || parse_G26_parameters()) return; if (current_position[Z_AXIS] < Z_CLEARANCE_BETWEEN_PROBES) { do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); diff --git a/Marlin/Marlin.h b/Marlin/Marlin.h index e74ad8ae0..9d505d87f 100644 --- a/Marlin/Marlin.h +++ b/Marlin/Marlin.h @@ -426,7 +426,7 @@ void do_blocking_move_to_z(const float &z, const float &fr_mm_s=0.0); void do_blocking_move_to_xy(const float &x, const float &y, const float &fr_mm_s=0.0); #if ENABLED(Z_PROBE_ALLEN_KEY) || ENABLED(Z_PROBE_SLED) || HAS_PROBING_PROCEDURE || HOTENDS > 1 || ENABLED(NOZZLE_CLEAN_FEATURE) || ENABLED(NOZZLE_PARK_FEATURE) - bool axis_unhomed_error(const bool x, const bool y, const bool z); + bool axis_unhomed_error(const bool x=true, const bool y=true, const bool z=true); #endif /** diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 07a011cc6..3269de46a 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -1851,10 +1851,10 @@ static void clean_up_after_endstop_or_probe_move() { #if HAS_PROBING_PROCEDURE || HOTENDS > 1 || ENABLED(Z_PROBE_ALLEN_KEY) || ENABLED(Z_PROBE_SLED) || ENABLED(NOZZLE_CLEAN_FEATURE) || ENABLED(NOZZLE_PARK_FEATURE) || ENABLED(DELTA_AUTO_CALIBRATION) - bool axis_unhomed_error(const bool x, const bool y, const bool z) { - const bool xx = x && !axis_homed[X_AXIS], - yy = y && !axis_homed[Y_AXIS], - zz = z && !axis_homed[Z_AXIS]; + bool axis_unhomed_error(const bool x/*=true*/, const bool y/*=true*/, const bool z/*=true*/) { + const bool xx = x && !axis_known_position[X_AXIS], + yy = y && !axis_known_position[Y_AXIS], + zz = z && !axis_known_position[Z_AXIS]; if (xx || yy || zz) { SERIAL_ECHO_START; SERIAL_ECHOPGM(MSG_HOME " "); @@ -2169,15 +2169,13 @@ static void clean_up_after_endstop_or_probe_move() { return true; } } - #elif ENABLED(Z_PROBE_SLED) - if (axis_unhomed_error(true, false, false)) { - SERIAL_ERROR_START; - SERIAL_ERRORLNPGM(MSG_STOP_UNHOMED); - stop(); - return true; - } - #elif ENABLED(Z_PROBE_ALLEN_KEY) - if (axis_unhomed_error(true, true, true )) { + #elif ENABLED(Z_PROBE_SLED) || ENABLED(Z_PROBE_ALLEN_KEY) + #if ENABLED(Z_PROBE_SLED) + #define _AUE_ARGS true, false, false + #else + #define _AUE_ARGS + #endif + if (axis_unhomed_error(_AUE_ARGS)) { SERIAL_ERROR_START; SERIAL_ERRORLNPGM(MSG_STOP_UNHOMED); stop(); @@ -3414,7 +3412,7 @@ inline void gcode_G4() { */ inline void gcode_G12() { // Don't allow nozzle cleaning without homing first - if (axis_unhomed_error(true, true, true)) return; + if (axis_unhomed_error()) return; const uint8_t pattern = code_seen('P') ? code_value_ushort() : 0, strokes = code_seen('S') ? code_value_ushort() : NOZZLE_CLEAN_STROKES, @@ -3443,7 +3441,7 @@ inline void gcode_G4() { */ inline void gcode_G27() { // Don't allow nozzle parking without homing first - if (axis_unhomed_error(true, true, true)) return; + if (axis_unhomed_error()) return; Nozzle::park(code_seen('P') ? code_value_ushort() : 0); } #endif // NOZZLE_PARK_FEATURE @@ -4222,7 +4220,7 @@ void home_all_axes() { gcode_G28(); } #endif // Don't allow auto-leveling without homing first - if (axis_unhomed_error(true, true, true)) return; + if (axis_unhomed_error()) return; // Define local vars 'static' for manual probing, 'auto' otherwise #if ENABLED(PROBE_MANUALLY) @@ -6174,7 +6172,7 @@ inline void gcode_M42() { */ inline void gcode_M48() { - if (axis_unhomed_error(true, true, true)) return; + if (axis_unhomed_error()) return; const int8_t verbose_level = code_seen('V') ? code_value_byte() : 1; if (!WITHIN(verbose_level, 0, 4)) { @@ -9427,7 +9425,7 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool n feedrate_mm_s = fr_mm_s > 0.0 ? fr_mm_s : XY_PROBE_FEEDRATE_MM_S; if (tmp_extruder != active_extruder) { - if (!no_move && axis_unhomed_error(true, true, true)) { + if (!no_move && axis_unhomed_error()) { SERIAL_ECHOLNPGM("No move on toolchange"); no_move = true; } diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index c6984ab7b..0259be69b 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -329,7 +329,7 @@ } // Don't allow auto-leveling without homing first - if (!code_seen('N') && axis_unhomed_error(true, true, true)) // Warning! Use of 'N' flouts established standards. + if (!(code_seen('N') && code_value_bool()) && axis_unhomed_error()) // Warning! Use of 'N' flouts established standards. home_all_axes(); if (g29_parameter_parsing()) return; // abort if parsing the simple parameters causes a problem, From 1fbcbc05f6e48a444ab72b7ed3258da347baaf19 Mon Sep 17 00:00:00 2001 From: Roxy-3D Date: Mon, 15 May 2017 16:25:01 -0500 Subject: [PATCH 075/189] UBL no longer flout's the sacred GCode standard (#6745) Also clean up ubl_motion.cpp debug info and fix declaration of cx & cy --- Marlin/G26_Mesh_Validation_Tool.cpp | 26 +++--- Marlin/Marlin_main.cpp | 2 +- Marlin/ubl_G29.cpp | 131 ++++++++++------------------ Marlin/ubl_motion.cpp | 37 ++------ 4 files changed, 63 insertions(+), 133 deletions(-) diff --git a/Marlin/G26_Mesh_Validation_Tool.cpp b/Marlin/G26_Mesh_Validation_Tool.cpp index 105c78690..b6cd3e1e9 100644 --- a/Marlin/G26_Mesh_Validation_Tool.cpp +++ b/Marlin/G26_Mesh_Validation_Tool.cpp @@ -88,17 +88,6 @@ * * L # Layer Layer height. (Height of nozzle above bed) If not specified .20mm will be used. * - * Q # Multiplier Retraction Multiplier. Normally not needed. Retraction defaults to 1.0mm and - * un-retraction is at 1.2mm These numbers will be scaled by the specified amount - * - * M # Random Randomize the order that the circles are drawn on the bed. The search for the closest - * undrawn cicle is still done. But the distance to the location for each circle has a - * random number of the size specified added to it. Specifying R50 will give an interesting - * deviation from the normal behaviour on a 10 x 10 Mesh. - - * N # Nozzle Used to control the size of nozzle diameter. If not specified, a .4mm nozzle is assumed. - * 'n' can be used instead if your host program does not appreciate you using 'N'. - * * O # Ooooze How much your nozzle will Ooooze filament while getting in position to print. This * is over kill, but using this parameter will let you get the very first 'circle' perfect * so you have a trophy to peel off of the bed and hang up to show how perfectly you have your @@ -111,10 +100,20 @@ * printing the Mesh. You can carefully remove the spent filament with a needle nose * pliers while holding the LCD Click wheel in a depressed state. * + * Q # Multiplier Retraction Multiplier. Normally not needed. Retraction defaults to 1.0mm and + * un-retraction is at 1.2mm These numbers will be scaled by the specified amount + * * R # Repeat Prints the number of patterns given as a parameter, starting at the current location. * If a parameter isn't given, every point will be printed unless G26 is interrupted. * This works the same way that the UBL G29 P4 R parameter works. * + * S # Nozzle Used to control the size of nozzle diameter. If not specified, a .4mm nozzle is assumed. + * + * U # Random Randomize the order that the circles are drawn on the bed. The search for the closest + * undrawn cicle is still done. But the distance to the location for each circle has a + * random number of the size specified added to it. Specifying S50 will give an interesting + * deviation from the normal behaviour on a 10 x 10 Mesh. + * * X # X Coord. Specify the starting location of the drawing activity. * * Y # Y Coord. Specify the starting location of the drawing activity. @@ -686,7 +685,7 @@ } } - if (code_seen('N') || code_seen('n')) { // Warning! Use of 'N' / lowercase flouts established standards. + if (code_seen('S')) { nozzle = code_value_float(); if (!WITHIN(nozzle, 0.1, 1.0)) { SERIAL_PROTOCOLLNPGM("?Specified nozzle size not plausible."); @@ -728,9 +727,8 @@ } } - if (code_seen('M')) { // Warning! Use of 'M' flouts established standards. + if (code_seen('U')) { randomSeed(millis()); - // This setting will persist for the next G26 random_deviation = code_has_value() ? code_value_float() : 50.0; } diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 3269de46a..70d5f36e6 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -5761,7 +5761,7 @@ inline void gcode_M31() { /** * M32: Select file and start SD Print */ - inline void gcode_M32() { + inline void gcode_M32() { // Why is M32 allowed to flout the sacred GCode standard? if (card.sdprinting) stepper.synchronize(); diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 0259be69b..629eaaae0 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -116,8 +116,7 @@ * invalidate. * * J # Grid * Perform a Grid Based Leveling of the current Mesh using a grid with n points on a side. - * - * j EEPROM Dump This function probably goes away after debug is complete. + * Not specifying a grid size will invoke the 3-Point leveling function. * * K # Kompare Kompare current Mesh with stored Mesh # replacing current Mesh with the result. This * command literally performs a diff between two Meshes. @@ -264,8 +263,6 @@ * at a later date. The GCode output can be saved and later replayed by the host software * to reconstruct the current mesh on another machine. * - * T 3-Point Perform a 3 Point Bed Leveling on the current Mesh - * * U Unlevel Perform a probe of the outer perimeter to assist in physically leveling unlevel beds. * Only used for G29 P1 O U It will speed up the probing of the edge of the bed. This * is useful when the entire bed does not need to be probed because it will be adjusted. @@ -276,12 +273,6 @@ * * Y # * * Y Location for this line of commands * - * Z Zero * Probes to set the Z Height of the nozzle. The entire Mesh can be raised or lowered - * by just doing a G29 Z - * - * Z # Zero * The entire Mesh can be raised or lowered to conform with the specified difference. - * zprobe_zoffset is added to the calculation. - * * * Release Notes: * You MUST do M502, M500 to initialize the storage. Failure to do this will cause all @@ -329,7 +320,7 @@ } // Don't allow auto-leveling without homing first - if (!(code_seen('N') && code_value_bool()) && axis_unhomed_error()) // Warning! Use of 'N' flouts established standards. + if (axis_unhomed_error()) home_all_axes(); if (g29_parameter_parsing()) return; // abort if parsing the simple parameters causes a problem, @@ -353,13 +344,16 @@ } if (code_seen('Q')) { - const int test_pattern = code_has_value() ? code_value_int() : -1; - if (!WITHIN(test_pattern, 0, 2)) { + const int test_pattern = code_has_value() ? code_value_int() : -99; + if (!WITHIN(test_pattern, -1, 2)) { SERIAL_PROTOCOLLNPGM("Invalid test_pattern value. (0-2)\n"); return; } SERIAL_PROTOCOLLNPGM("Loading test_pattern values.\n"); switch (test_pattern) { + case -1: + g29_eeprom_dump(); + break; case 0: for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) { // Create a bowl shape - similar to for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) { // a poorly calibrated Delta. @@ -385,9 +379,33 @@ } if (code_seen('J')) { - ubl.save_ubl_active_state_and_disable(); - ubl.tilt_mesh_based_on_probed_grid(code_seen('O') || code_seen('M')); // Warning! Use of 'M' flouts established standards. - ubl.restore_ubl_active_state_and_leave(); + if (grid_size!=0) { // if not 0 it is a normal n x n grid being probed + ubl.save_ubl_active_state_and_disable(); + ubl.tilt_mesh_based_on_probed_grid(code_seen('O')); + ubl.restore_ubl_active_state_and_leave(); + } else { // grid_size==0 which means a 3-Point leveling has been requested + float z1 = probe_pt(LOGICAL_X_POSITION(UBL_PROBE_PT_1_X), LOGICAL_Y_POSITION(UBL_PROBE_PT_1_Y), false, g29_verbose_level), + z2 = probe_pt(LOGICAL_X_POSITION(UBL_PROBE_PT_2_X), LOGICAL_Y_POSITION(UBL_PROBE_PT_2_Y), false, g29_verbose_level), + z3 = probe_pt(LOGICAL_X_POSITION(UBL_PROBE_PT_3_X), LOGICAL_Y_POSITION(UBL_PROBE_PT_3_Y), true, g29_verbose_level); + + if ( isnan(z1) || isnan(z2) || isnan(z3)) { // probe_pt will return NAN if unreachable + SERIAL_ERROR_START; + SERIAL_ERRORLNPGM("Attempt to probe off the bed."); + goto LEAVE; + } + + // We need to adjust z1, z2, z3 by the Mesh Height at these points. Just because they are non-zero doesn't mean + // the Mesh is tilted! (We need to compensate each probe point by what the Mesh says that location's height is) + + ubl.save_ubl_active_state_and_disable(); + z1 -= ubl.get_z_correction(LOGICAL_X_POSITION(UBL_PROBE_PT_1_X), LOGICAL_Y_POSITION(UBL_PROBE_PT_1_Y)) /* + zprobe_zoffset */ ; + z2 -= ubl.get_z_correction(LOGICAL_X_POSITION(UBL_PROBE_PT_2_X), LOGICAL_Y_POSITION(UBL_PROBE_PT_2_Y)) /* + zprobe_zoffset */ ; + z3 -= ubl.get_z_correction(LOGICAL_X_POSITION(UBL_PROBE_PT_3_X), LOGICAL_Y_POSITION(UBL_PROBE_PT_3_Y)) /* + zprobe_zoffset */ ; + + do_blocking_move_to_xy(0.5 * (UBL_MESH_MAX_X - (UBL_MESH_MIN_X)), 0.5 * (UBL_MESH_MAX_Y - (UBL_MESH_MIN_Y))); + ubl.tilt_mesh_based_on_3pts(z1, z2, z3); + ubl.restore_ubl_active_state_and_leave(); + } } if (code_seen('P')) { @@ -420,7 +438,7 @@ SERIAL_PROTOCOLLNPGM(").\n"); } ubl.probe_entire_mesh(x_pos + X_PROBE_OFFSET_FROM_EXTRUDER, y_pos + Y_PROBE_OFFSET_FROM_EXTRUDER, - code_seen('O') || code_seen('M'), code_seen('E'), code_seen('U')); // Warning! Use of 'M' flouts established standards. + code_seen('O'), code_seen('E'), code_seen('U')); break; case 2: { @@ -469,7 +487,7 @@ return; } - manually_probe_remaining_mesh(x_pos, y_pos, height, card_thickness, code_seen('O') || code_seen('M')); // Warning! Use of 'M' flouts established standards. + manually_probe_remaining_mesh(x_pos, y_pos, height, card_thickness, code_seen('O')); SERIAL_PROTOCOLLNPGM("G29 P2 finished."); } break; @@ -505,7 +523,7 @@ // // Fine Tune (i.e., Edit) the Mesh // - fine_tune_mesh(x_pos, y_pos, code_seen('O') || code_seen('M')); // Warning! Use of 'M' flouts established standards. + fine_tune_mesh(x_pos, y_pos, code_seen('O')); break; case 5: ubl.find_mean_mesh_height(); break; @@ -515,43 +533,12 @@ } - if (code_seen('T')) { - - float z1 = probe_pt(LOGICAL_X_POSITION(UBL_PROBE_PT_1_X), LOGICAL_Y_POSITION(UBL_PROBE_PT_1_Y), false, g29_verbose_level), - z2 = probe_pt(LOGICAL_X_POSITION(UBL_PROBE_PT_2_X), LOGICAL_Y_POSITION(UBL_PROBE_PT_2_Y), false, g29_verbose_level), - z3 = probe_pt(LOGICAL_X_POSITION(UBL_PROBE_PT_3_X), LOGICAL_Y_POSITION(UBL_PROBE_PT_3_Y), true, g29_verbose_level); - - if ( isnan(z1) || isnan(z2) || isnan(z3)) { // probe_pt will return NAN if unreachable - SERIAL_ERROR_START; - SERIAL_ERRORLNPGM("Attempt to probe off the bed."); - goto LEAVE; - } - - // We need to adjust z1, z2, z3 by the Mesh Height at these points. Just because they are non-zero doesn't mean - // the Mesh is tilted! (We need to compensate each probe point by what the Mesh says that location's height is) - - ubl.save_ubl_active_state_and_disable(); - z1 -= ubl.get_z_correction(LOGICAL_X_POSITION(UBL_PROBE_PT_1_X), LOGICAL_Y_POSITION(UBL_PROBE_PT_1_Y)) /* + zprobe_zoffset */ ; - z2 -= ubl.get_z_correction(LOGICAL_X_POSITION(UBL_PROBE_PT_2_X), LOGICAL_Y_POSITION(UBL_PROBE_PT_2_Y)) /* + zprobe_zoffset */ ; - z3 -= ubl.get_z_correction(LOGICAL_X_POSITION(UBL_PROBE_PT_3_X), LOGICAL_Y_POSITION(UBL_PROBE_PT_3_Y)) /* + zprobe_zoffset */ ; - - do_blocking_move_to_xy(0.5 * (UBL_MESH_MAX_X - (UBL_MESH_MIN_X)), 0.5 * (UBL_MESH_MAX_Y - (UBL_MESH_MIN_Y))); - ubl.tilt_mesh_based_on_3pts(z1, z2, z3); - ubl.restore_ubl_active_state_and_leave(); - } - // // Much of the 'What?' command can be eliminated. But until we are fully debugged, it is // good to have the extra information. Soon... we prune this to just a few items // if (code_seen('W')) ubl.g29_what_command(); - // - // When we are fully debugged, the EEPROM dump command will get deleted also. But - // right now, it is good to have the extra information. Soon... we prune this. - // - if (code_seen('j')) g29_eeprom_dump(); // Warning! Use of lowercase flouts established standards. - // // When we are fully debugged, this may go away. But there are some valid // use cases for the users. So we can wait and see what to do with it. @@ -614,9 +601,12 @@ SERIAL_PROTOCOLLNPGM("Done.\n"); } - if (code_seen('O') || code_seen('M')) // Warning! Use of 'M' flouts established standards. + if (code_seen('O')) ubl.display_map(code_has_value() ? code_value_int() : 0); + /* + * This code may not be needed... Prepare for its removal... + * if (code_seen('Z')) { if (code_has_value()) ubl.state.z_offset = code_value_float(); // do the simple case. Just lock in the specified value @@ -669,6 +659,7 @@ ubl.restore_ubl_active_state_and_leave(); } } + */ LEAVE: @@ -1069,8 +1060,8 @@ } if (code_seen('J')) { - grid_size = code_has_value() ? code_value_int() : 3; - if (!WITHIN(grid_size, 2, 9)) { + grid_size = code_has_value() ? code_value_int() : 0; + if (grid_size!=0 && !WITHIN(grid_size, 2, 9)) { SERIAL_PROTOCOLLNPGM("?Invalid grid size (J) specified (2-9).\n"); err_flag = true; } @@ -1126,43 +1117,9 @@ SERIAL_PROTOCOLLNPGM("Invalid map type.\n"); return UBL_ERR; } - - // Check if a map type was specified - if (code_seen('M')) { // Warning! Use of 'M' flouts established standards. - map_type = code_has_value() ? code_value_int() : 0; - if (!WITHIN(map_type, 0, 1)) { - SERIAL_PROTOCOLLNPGM("Invalid map type.\n"); - return UBL_ERR; - } - } - return UBL_OK; } - /** - * This function goes away after G29 debug is complete. But for right now, it is a handy - * routine to dump binary data structures. - */ - /* - void dump(char * const str, const float &f) { - char *ptr; - - SERIAL_PROTOCOL(str); - SERIAL_PROTOCOL_F(f, 8); - SERIAL_PROTOCOLPGM(" "); - ptr = (char*)&f; - for (uint8_t i = 0; i < 4; i++) - SERIAL_PROTOCOLPAIR(" ", hex_byte(*ptr++)); - SERIAL_PROTOCOLPAIR(" isnan()=", isnan(f)); - SERIAL_PROTOCOLPAIR(" isinf()=", isinf(f)); - - if (f == -INFINITY) - SERIAL_PROTOCOLPGM(" Minus Infinity detected."); - - SERIAL_EOL; - } - //*/ - static int ubl_state_at_invocation = 0, ubl_state_recursion_chk = 0; diff --git a/Marlin/ubl_motion.cpp b/Marlin/ubl_motion.cpp index 1d59e31b9..2cc4767dd 100644 --- a/Marlin/ubl_motion.cpp +++ b/Marlin/ubl_motion.cpp @@ -55,12 +55,8 @@ dy = current_position[Y_AXIS] - destination[Y_AXIS], xy_dist = HYPOT(dx, dy); - if (xy_dist == 0.0) { - return; - //SERIAL_ECHOPGM(" FPMM="); - //const float fpmm = de / xy_dist; - //SERIAL_PROTOCOL_F(fpmm, 6); - } + if (xy_dist == 0.0) + return; else { SERIAL_ECHOPGM(" fpmm="); const float fpmm = de / xy_dist; @@ -276,16 +272,7 @@ */ if (y != start[Y_AXIS]) { if (!inf_normalized_flag) { - - //on_axis_distance = y - start[Y_AXIS]; on_axis_distance = use_x_dist ? x - start[X_AXIS] : y - start[Y_AXIS]; - - //on_axis_distance = use_x_dist ? next_mesh_line_x - start[X_AXIS] : y - start[Y_AXIS]; - //on_axis_distance = use_x_dist ? x - start[X_AXIS] : next_mesh_line_y - start[Y_AXIS]; - - //on_axis_distance = use_x_dist ? next_mesh_line_x - start[X_AXIS] : y - start[Y_AXIS]; - //on_axis_distance = use_x_dist ? x - start[X_AXIS] : next_mesh_line_y - start[Y_AXIS]; - e_position = start[E_AXIS] + on_axis_distance * e_normalized_dist; z_position = start[Z_AXIS] + on_axis_distance * z_normalized_dist; } @@ -350,13 +337,7 @@ */ if (x != start[X_AXIS]) { if (!inf_normalized_flag) { - - //on_axis_distance = x - start[X_AXIS]; on_axis_distance = use_x_dist ? x - start[X_AXIS] : y - start[Y_AXIS]; - - //on_axis_distance = use_x_dist ? next_mesh_line_x - start[X_AXIS] : y - start[Y_AXIS]; - //on_axis_distance = use_x_dist ? x - start[X_AXIS] : next_mesh_line_y - start[Y_AXIS]; - e_position = start[E_AXIS] + on_axis_distance * e_normalized_dist; // is based on X or Y because this is a horizontal move z_position = start[Z_AXIS] + on_axis_distance * z_normalized_dist; } @@ -613,20 +594,14 @@ cell_xi = constrain(cell_xi, 0, (GRID_MAX_POINTS_X) - 1); cell_yi = constrain(cell_yi, 0, (GRID_MAX_POINTS_Y) - 1); - // float x0 = (UBL_MESH_MIN_X) + ((MESH_X_DIST) * cell_xi ); // lower left cell corner - // float y0 = (UBL_MESH_MIN_Y) + ((MESH_Y_DIST) * cell_yi ); // lower left cell corner - // float x1 = x0 + MESH_X_DIST; // upper right cell corner - // float y1 = y0 + MESH_Y_DIST; // upper right cell corner - const float x0 = pgm_read_float(&(ubl.mesh_index_to_xpos[cell_xi ])), // 64 byte table lookup avoids mul+add y0 = pgm_read_float(&(ubl.mesh_index_to_ypos[cell_yi ])), // 64 byte table lookup avoids mul+add x1 = pgm_read_float(&(ubl.mesh_index_to_xpos[cell_xi+1])), // 64 byte table lookup avoids mul+add - y1 = pgm_read_float(&(ubl.mesh_index_to_ypos[cell_yi+1])), // 64 byte table lookup avoids mul+add - - cx = rx - x0, // cell-relative x - cy = ry - y0; // cell-relative y + y1 = pgm_read_float(&(ubl.mesh_index_to_ypos[cell_yi+1])); // 64 byte table lookup avoids mul+add - float z_x0y0 = ubl.z_values[cell_xi ][cell_yi ], // z at lower left corner + float cx = rx - x0, // cell-relative x + cy = ry - y0; // cell-relative y + z_x0y0 = ubl.z_values[cell_xi ][cell_yi ], // z at lower left corner z_x1y0 = ubl.z_values[cell_xi+1][cell_yi ], // z at upper left corner z_x0y1 = ubl.z_values[cell_xi ][cell_yi+1], // z at lower right corner z_x1y1 = ubl.z_values[cell_xi+1][cell_yi+1]; // z at upper right corner From 6f86c46fa6d76dbd12f55c9855c26045c7659843 Mon Sep 17 00:00:00 2001 From: Roxy-3D Date: Mon, 15 May 2017 23:13:45 -0500 Subject: [PATCH 076/189] Fix typo that caused scope issues for DELTA (#6750) --- Marlin/ubl_motion.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/ubl_motion.cpp b/Marlin/ubl_motion.cpp index 2cc4767dd..1ebee9e5f 100644 --- a/Marlin/ubl_motion.cpp +++ b/Marlin/ubl_motion.cpp @@ -600,7 +600,7 @@ y1 = pgm_read_float(&(ubl.mesh_index_to_ypos[cell_yi+1])); // 64 byte table lookup avoids mul+add float cx = rx - x0, // cell-relative x - cy = ry - y0; // cell-relative y + cy = ry - y0, // cell-relative y z_x0y0 = ubl.z_values[cell_xi ][cell_yi ], // z at lower left corner z_x1y0 = ubl.z_values[cell_xi+1][cell_yi ], // z at upper left corner z_x0y1 = ubl.z_values[cell_xi ][cell_yi+1], // z at lower right corner From b213a45efbcd9233d14291e49959ef0b4efc312c Mon Sep 17 00:00:00 2001 From: oldmcg Date: Tue, 16 May 2017 00:30:29 -0500 Subject: [PATCH 077/189] UBL_DELTA post merge cleanup (#6705) * UBL_DELTA post merge cleanup: fix fade_height, lost during some previous merge fix float cx,cy which are not const move repeated z_cxcy calc line inside loop style fixes and comment fixes/alignment * Update ubl_motion.cpp remove unnecessary parentheses * Update Conditionals_post.h Change name of define to more accurate meaning: UBL_GRANULAR_SEGMENTATION_FOR_CARTESIAN which is not and should not be the default for cartesians with UBL. --- Marlin/Conditionals_post.h | 2 +- Marlin/ubl_motion.cpp | 40 ++++++++++++++++++++++++-------------- 2 files changed, 26 insertions(+), 16 deletions(-) diff --git a/Marlin/Conditionals_post.h b/Marlin/Conditionals_post.h index b303b65aa..258736eab 100644 --- a/Marlin/Conditionals_post.h +++ b/Marlin/Conditionals_post.h @@ -731,7 +731,7 @@ * Set granular options based on the specific type of leveling */ - #define UBL_DELTA (ENABLED(AUTO_BED_LEVELING_UBL) && ENABLED(DELTA)) + #define UBL_DELTA (ENABLED(AUTO_BED_LEVELING_UBL) && (ENABLED(DELTA) || ENABLED(UBL_GRANULAR_SEGMENTATION_FOR_CARTESIAN))) #define ABL_PLANAR (ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_3POINT)) #define ABL_GRID (ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)) #define HAS_ABL (ABL_PLANAR || ABL_GRID || ENABLED(AUTO_BED_LEVELING_UBL)) diff --git a/Marlin/ubl_motion.cpp b/Marlin/ubl_motion.cpp index 1ebee9e5f..b3ec6023e 100644 --- a/Marlin/ubl_motion.cpp +++ b/Marlin/ubl_motion.cpp @@ -506,13 +506,13 @@ ltarget[E_AXIS] - current_position[E_AXIS] }; - const float cartesian_xy_mm = HYPOT(difference[X_AXIS], difference[Y_AXIS]); // total horizontal xy distance + const float cartesian_xy_mm = HYPOT(difference[X_AXIS], difference[Y_AXIS]); // total horizontal xy distance #if IS_KINEMATIC - const float seconds = cartesian_xy_mm / feedrate; // seconds to move xy distance at requested rate - uint16_t segments = lroundf(delta_segments_per_second * seconds), // preferred number of segments for distance @ feedrate + const float seconds = cartesian_xy_mm / feedrate; // seconds to move xy distance at requested rate + uint16_t segments = lroundf(delta_segments_per_second * seconds), // preferred number of segments for distance @ feedrate seglimit = lroundf(cartesian_xy_mm * (1.0 / (DELTA_SEGMENT_MIN_LENGTH))); // number of segments at minimum segment length - NOMORE(segments, seglimit); // limit to minimum segment length (fewer segments) + NOMORE(segments, seglimit); // limit to minimum segment length (fewer segments) #else uint16_t segments = lroundf(cartesian_xy_mm * (1.0 / (DELTA_SEGMENT_MIN_LENGTH))); // cartesian fixed segment length #endif @@ -570,6 +570,10 @@ // Otherwise perform per-segment leveling + #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) + const float fade_scaling_factor = ubl.fade_scaling_factor_for_z(ltarget[Z_AXIS]); + #endif + float seg_dest[XYZE]; // per-segment destination, initialize to first segment LOOP_XYZE(i) seg_dest[i] = current_position[i] + segment_distance[i]; @@ -614,13 +618,14 @@ const float z_xmy0 = (z_x1y0 - z_x0y0) * (1.0 / (MESH_X_DIST)), // z slope per x along y0 (lower left to lower right) z_xmy1 = (z_x1y1 - z_x0y1) * (1.0 / (MESH_X_DIST)); // z slope per x along y1 (upper left to upper right) - float z_cxy0 = z_x0y0 + z_xmy0 * cx; // z height along y0 at cx + float z_cxy0 = z_x0y0 + z_xmy0 * cx; // z height along y0 at cx - const float z_cxy1 = z_x0y1 + z_xmy1 * cx, // z height along y1 at cx - z_cxyd = z_cxy1 - z_cxy0; // z height difference along cx from y0 to y1 + const float z_cxy1 = z_x0y1 + z_xmy1 * cx, // z height along y1 at cx + z_cxyd = z_cxy1 - z_cxy0; // z height difference along cx from y0 to y1 - float z_cxym = z_cxyd * (1.0 / (MESH_Y_DIST)), // z slope per y along cx from y0 to y1 - z_cxcy = z_cxy0 + z_cxym * cy; // z height along cx at cy + float z_cxym = z_cxyd * (1.0 / (MESH_Y_DIST)); // z slope per y along cx from y0 to y1 + + // float z_cxcy = z_cxy0 + z_cxym * cy; // interpolated mesh z height along cx at cy (do inside the segment loop) // As subsequent segments step through this cell, the z_cxy0 intercept will change // and the z_cxym slope will change, both as a function of cx within the cell, and @@ -631,9 +636,15 @@ do { // for all segments within this mesh cell - z_cxcy += ubl.state.z_offset; + float z_cxcy = z_cxy0 + z_cxym * cy; // interpolated mesh z height along cx at cy + + #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) + z_cxcy *= fade_scaling_factor; // apply fade factor to interpolated mesh height + #endif + + z_cxcy += ubl.state.z_offset; // add fixed mesh offset from G29 Z - if (--segments == 0) { // this is last segment, use ltarget for exact + if (--segments == 0) { // if this is last segment, use ltarget for exact COPY(seg_dest, ltarget); seg_dest[Z_AXIS] += z_cxcy; ubl_buffer_line_segment(seg_dest, feedrate, active_extruder); @@ -657,11 +668,10 @@ } // Next segment still within same mesh cell, adjust the per-segment - // slope and intercept and compute next z height. + // slope and intercept to compute next z height. - z_cxy0 += z_sxy0; // adjust z_cxy0 by per-segment z_sxy0 - z_cxym += z_sxym; // adjust z_cxym by per-segment z_sxym - z_cxcy = z_cxy0 + z_cxym * cy; // recompute z_cxcy from adjusted slope and intercept + z_cxy0 += z_sxy0; // adjust z_cxy0 by per-segment z_sxy0 + z_cxym += z_sxym; // adjust z_cxym by per-segment z_sxym } while (true); // per-segment loop exits by break after last segment within cell, or by return on final segment } while (true); // per-cell loop From 2266c0780dc03cdc9b1cb3faedeee2596f5b2220 Mon Sep 17 00:00:00 2001 From: moebyusDev Date: Fri, 12 May 2017 17:44:53 +0200 Subject: [PATCH 078/189] fixed spanish lang It was missing MSG_FILAMENT_CHANGE_HEAT_2 and MSG_FILAMENT_CHANGE_HEATING_2 --- Marlin/language_es.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Marlin/language_es.h b/Marlin/language_es.h index c1f0d904a..21bd330a8 100644 --- a/Marlin/language_es.h +++ b/Marlin/language_es.h @@ -254,6 +254,8 @@ #define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Esperando imp.") #define MSG_FILAMENT_CHANGE_RESUME_2 _UxGT("para resumir") #define MSG_FILAMENT_CHANGE_HEAT_1 _UxGT("Oprima boton para") +#define MSG_FILAMENT_CHANGE_HEAT_2 _UxGT("Calentar la boquilla") #define MSG_FILAMENT_CHANGE_HEATING_1 _UxGT("Calentando boquilla") +#define MSG_FILAMENT_CHANGE_HEATING_2 _UxGT("Espere por favor") #endif // LANGUAGE_ES_H From f1a1c6873e43fb2c8d998ec4a0c2b397ab97fa2a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 14 May 2017 00:12:09 -0500 Subject: [PATCH 079/189] Patch lcd_implementation_status_screen compiler warning --- Marlin/ultralcd_impl_HD44780.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/ultralcd_impl_HD44780.h b/Marlin/ultralcd_impl_HD44780.h index 0cb0d524f..0f8e03493 100644 --- a/Marlin/ultralcd_impl_HD44780.h +++ b/Marlin/ultralcd_impl_HD44780.h @@ -777,7 +777,7 @@ static void lcd_implementation_status_screen() { // Draw the progress bar if the message has shown long enough // or if there is no message set. - if (card.isFileOpen() && ELAPSED(millis(), progress_bar_ms + PROGRESS_BAR_MSG_TIME) || !lcd_status_message[0]) + if (card.isFileOpen() && (ELAPSED(millis(), progress_bar_ms + PROGRESS_BAR_MSG_TIME) || !lcd_status_message[0])) return lcd_draw_progress_bar(card.percentDone()); #elif ENABLED(FILAMENT_LCD_DISPLAY) && ENABLED(SDSUPPORT) From 4ec4ecff1a83fe6d84eb61740e8910b29a7c3e74 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 15 May 2017 21:09:06 -0500 Subject: [PATCH 080/189] Reduce find_closest_mesh_point_of_type a little --- Marlin/ubl_G29.cpp | 23 +++++++---------------- 1 file changed, 7 insertions(+), 16 deletions(-) diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 629eaaae0..b5b031dcc 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -1308,12 +1308,10 @@ mesh_index_pair out_mesh; out_mesh.x_index = out_mesh.y_index = -1; - const float current_x = current_position[X_AXIS], - current_y = current_position[Y_AXIS]; - // Get our reference position. Either the nozzle or probe location. - const float px = lx - (probe_as_reference == USE_PROBE_AS_REFERENCE ? X_PROBE_OFFSET_FROM_EXTRUDER : 0), - py = ly - (probe_as_reference == USE_PROBE_AS_REFERENCE ? Y_PROBE_OFFSET_FROM_EXTRUDER : 0); + const float px = RAW_X_POSITION(lx) - (probe_as_reference == USE_PROBE_AS_REFERENCE ? X_PROBE_OFFSET_FROM_EXTRUDER : 0), + py = RAW_Y_POSITION(ly) - (probe_as_reference == USE_PROBE_AS_REFERENCE ? Y_PROBE_OFFSET_FROM_EXTRUDER : 0), + raw_x = RAW_CURRENT_POSITION(X), raw_y = RAW_CURRENT_POSITION(Y); float closest = far_flag ? -99999.99 : 99999.99; @@ -1327,27 +1325,20 @@ // We only get here if we found a Mesh Point of the specified type - const float rawx = pgm_read_float(&ubl.mesh_index_to_xpos[i]), // Check if we can probe this mesh location - rawy = pgm_read_float(&ubl.mesh_index_to_ypos[j]); + const float mx = pgm_read_float(&ubl.mesh_index_to_xpos[i]), // Check if we can probe this mesh location + my = pgm_read_float(&ubl.mesh_index_to_ypos[j]); // If using the probe as the reference there are some unreachable locations. // Also for round beds, there are grid points outside the bed that nozzle can't reach. // Prune them from the list and ignore them till the next Phase (manual nozzle probing). - bool reachable = probe_as_reference ? - position_is_reachable_by_probe_raw_xy( rawx, rawy ) : - position_is_reachable_raw_xy( rawx, rawy ); - - if ( ! reachable ) + if ((probe_as_reference && position_is_reachable_by_probe_raw_xy(mx, my)) || position_is_reachable_raw_xy(mx, my)) continue; // Reachable. Check if it's the closest location to the nozzle. // Add in a weighting factor that considers the current location of the nozzle. - const float mx = LOGICAL_X_POSITION(rawx), // Check if we can probe this mesh location - my = LOGICAL_Y_POSITION(rawy); - - float distance = HYPOT(px - mx, py - my) + HYPOT(current_x - mx, current_y - my) * 0.1; + float distance = HYPOT(px - mx, py - my) + HYPOT(raw_x - mx, raw_y - my) * 0.1; /** * If doing the far_flag action, we want to be as far as possible From 091f94a6bfa7447d9651147fe63c3445d764b4f0 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 13 May 2017 00:43:12 -0500 Subject: [PATCH 081/189] Fix up M421 and some comments --- Marlin/Marlin_main.cpp | 114 +++++++++++++++-------------------------- 1 file changed, 42 insertions(+), 72 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 70d5f36e6..01151bc96 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -170,6 +170,8 @@ * M302 - Allow cold extrudes, or set the minimum extrude S. (Requires PREVENT_COLD_EXTRUSION) * M303 - PID relay autotune S sets the target temperature. Default 150C. (Requires PIDTEMP) * M304 - Set bed PID parameters P I and D. (Requires PIDTEMPBED) + * M350 - Set microstepping mode. (Requires digital microstepping pins.) + * M351 - Toggle MS1 MS2 pins directly. (Requires digital microstepping pins.) * M355 - Turn the Case Light on/off and set its brightness. (Requires CASE_LIGHT_PIN) * M380 - Activate solenoid on active extruder. (Requires EXT_SOLENOID) * M381 - Disable all solenoids. (Requires EXT_SOLENOID) @@ -194,6 +196,7 @@ * M666 - Set delta endstop adjustment. (Requires DELTA) * M605 - Set dual x-carriage movement mode: "M605 S [X] [R]". (Requires DUAL_X_CARRIAGE) * M851 - Set Z probe's Z offset in current units. (Negative = below the nozzle.) + * M900 - Get and/or Set advance K factor and WH/D ratio. (Requires LIN_ADVANCE) * M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given. (Requires HAVE_TMC2130) * M907 - Set digital trimpot motor current using axis codes. (Requires a board with digital trimpots) * M908 - Control digital trimpot directly. (Requires DAC_STEPPER_CURRENT or DIGIPOTSS_PIN) @@ -203,8 +206,6 @@ * M912 - Clear stepper driver overtemperature pre-warn condition flag. (Requires HAVE_TMC2130) * M913 - Set HYBRID_THRESHOLD speed. (Requires HYBRID_THRESHOLD) * M914 - Set SENSORLESS_HOMING sensitivity. (Requires SENSORLESS_HOMING) - * M350 - Set microstepping mode. (Requires digital microstepping pins.) - * M351 - Toggle MS1 MS2 pins directly. (Requires digital microstepping pins.) * * M360 - SCARA calibration: Move to cal-position ThetaA (0 deg calibration) * M361 - SCARA calibration: Move to cal-position ThetaB (90 deg calibration - steps per degree) @@ -7141,7 +7142,7 @@ inline void gcode_M82() { axis_relative_modes[E_AXIS] = false; } inline void gcode_M83() { axis_relative_modes[E_AXIS] = true; } /** - * M18, M84: Disable all stepper motors + * M18, M84: Disable stepper motors */ inline void gcode_M18_M84() { if (code_seen('S')) { @@ -8166,7 +8167,7 @@ inline void gcode_M303() { } /** - * M364: SCARA calibration: Move to cal-position PSIC (90 deg to Theta calibration position) + * M364: SCARA calibration: Move to cal-position PsiC (90 deg to Theta calibration position) */ inline bool gcode_M364() { SERIAL_ECHOLNPGM(" Cal: Theta-Psi 90"); @@ -8409,39 +8410,33 @@ void quickstop_stepper() { #endif #if ENABLED(MESH_BED_LEVELING) + /** * M421: Set a single Mesh Bed Leveling Z coordinate - * Use either 'M421 X Y Z' or 'M421 I J Z' + * + * Usage: + * M421 X Y Z + * M421 X Y Q + * M421 I J Z + * M421 I J Q */ inline void gcode_M421() { + const bool hasX = code_seen('X'), hasI = code_seen('I'); + const int8_t ix = hasI ? code_value_byte() : hasX ? mbl.probe_index_x(RAW_X_POSITION(code_value_linear_units())) : -1; + const bool hasY = code_seen('Y'), hasJ = code_seen('J'); + const int8_t iy = hasJ ? code_value_byte() : hasY ? mbl.probe_index_y(RAW_Y_POSITION(code_value_linear_units())) : -1; + const bool hasZ = code_seen('Z'), hasQ = code_seen('Q'); - const bool hasX = code_seen('X'), hasI = !hasX && code_seen('I'); - const int8_t px = hasX || hasI ? mbl.probe_index_x(code_value_linear_units()) : 0; - const bool hasY = code_seen('Y'), hasJ = !hasY && code_seen('J'); - const int8_t py = hasY || hasJ ? mbl.probe_index_y(code_value_linear_units()) : 0; - const bool hasZ = code_seen('Z'); - const float z = hasZ ? code_value_linear_units() : 0; - - if (hasX && hasY && hasZ) { - if (px >= 0 && py >= 0) - mbl.set_z(px, py, z); - else { - SERIAL_ERROR_START; - SERIAL_ERRORLNPGM(MSG_ERR_MESH_XY); - } - } - else if (hasI && hasJ && hasZ) { - if (WITHIN(px, 0, GRID_MAX_POINTS_X - 1) && WITHIN(py, 0, GRID_MAX_POINTS_Y - 1)) - mbl.set_z(px, py, z); - else { - SERIAL_ERROR_START; - SERIAL_ERRORLNPGM(MSG_ERR_MESH_XY); - } - } - else { + if (int(hasI && hasJ) + int(hasX && hasY) != 1 || hasZ == hasQ) { SERIAL_ERROR_START; SERIAL_ERRORLNPGM(MSG_ERR_M421_PARAMETERS); } + else if (ix < 0 || iy < 0) { + SERIAL_ERROR_START; + SERIAL_ERRORLNPGM(MSG_ERR_MESH_XY); + } + else + mbl.set_z(ix, iy, code_value_linear_units() + (hasQ ? mbl.z_values[ix][iy] : 0)); } #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) @@ -8454,38 +8449,26 @@ void quickstop_stepper() { * M421 I J Q */ inline void gcode_M421() { - const bool hasI = code_seen('I'); - const int8_t px = hasI ? code_value_int() : 0; + const int8_t ix = hasI ? code_value_byte() : -1; const bool hasJ = code_seen('J'); - const int8_t py = hasJ ? code_value_int() : 0; - const bool hasZ = code_seen('Z'), hasQ = !hasZ && code_seen('Q'); - const float z = hasZ || hasQ ? code_value_linear_units() : 0; + const int8_t iy = hasJ ? code_value_byte() : -1; + const bool hasZ = code_seen('Z'), hasQ = code_seen('Q'); - if (!hasI || !hasJ || (hasQ && hasZ) || (!hasQ && !hasZ)) { + if (!hasI || !hasJ || hasZ == hasQ) { SERIAL_ERROR_START; SERIAL_ERRORLNPGM(MSG_ERR_M421_PARAMETERS); - return; - } - - if (WITHIN(px, 0, GRID_MAX_POINTS_X - 1) && WITHIN(py, 0, GRID_MAX_POINTS_Y - 1)) { - if (hasZ) { // doing an absolute mesh value - z_values[px][py] = z; - #if ENABLED(ABL_BILINEAR_SUBDIVISION) - bed_level_virt_interpolate(); - #endif - } - else { // doing an offset of a mesh value - z_values[px][py] += z; - #if ENABLED(ABL_BILINEAR_SUBDIVISION) - bed_level_virt_interpolate(); - #endif - } } - else { // bad indexes were specified for the mesh point + else if (!WITHIN(ix, 0, GRID_MAX_POINTS_X - 1) || !WITHIN(iy, 0, GRID_MAX_POINTS_Y - 1)) { SERIAL_ERROR_START; SERIAL_ERRORLNPGM(MSG_ERR_MESH_XY); } + else { + z_values[ix][iy] = code_value_linear_units() + (hasQ ? z_values[ix][iy] : 0); + #if ENABLED(ABL_BILINEAR_SUBDIVISION) + bed_level_virt_interpolate(); + #endif + } } #elif ENABLED(AUTO_BED_LEVELING_UBL) @@ -8499,37 +8482,24 @@ void quickstop_stepper() { * M421 C Z * M421 C Q */ - inline void gcode_M421() { - - // Get the closest position for 'C', if needed const mesh_index_pair location = find_closest_mesh_point_of_type(REAL, current_position[X_AXIS], current_position[Y_AXIS], USE_NOZZLE_AS_REFERENCE, NULL, false); - const bool hasC = code_seen('C'), hasI = code_seen('I'); - const int8_t px = hasC ? location.x_index : hasI ? code_value_int() : 0; - + const int8_t ix = hasI ? code_value_byte() : hasC ? location.x_index : -1; const bool hasJ = code_seen('J'); - const int8_t py = hasC ? location.y_index : hasJ ? code_value_int() : 0; + const int8_t iy = hasJ ? code_value_byte() : hasC ? location.y_index : -1; + const bool hasZ = code_seen('Z'), hasQ = code_seen('Q'); - const bool hasZ = code_seen('Z'), hasQ = !hasZ && code_seen('Q'); - const float z = hasZ || hasQ ? code_value_linear_units() : 0; - - if ( ((hasI && hasJ) == hasC) || (hasQ && hasZ) || (!hasQ && !hasZ)) { + if (int(hasC) + int(hasI && hasJ) != 1 || hasZ == hasQ) { SERIAL_ERROR_START; SERIAL_ERRORLNPGM(MSG_ERR_M421_PARAMETERS); - return; } - - if (WITHIN(px, 0, GRID_MAX_POINTS_X - 1) && WITHIN(py, 0, GRID_MAX_POINTS_Y - 1)) { - if (hasZ) // doing an absolute mesh value - ubl.z_values[px][py] = z; - else // doing an offset of a mesh value - ubl.z_values[px][py] += z; - } - else { // bad indexes were specified for the mesh point + else if (!WITHIN(ix, 0, GRID_MAX_POINTS_X - 1) || !WITHIN(iy, 0, GRID_MAX_POINTS_Y - 1)) { SERIAL_ERROR_START; SERIAL_ERRORLNPGM(MSG_ERR_MESH_XY); } + else + ubl.z_values[ix][iy] = code_value_linear_units() + (hasQ ? ubl.z_values[ix][iy] : 0); } #endif // AUTO_BED_LEVELING_UBL From 56e2e331ed927982e888725ac3e93637bff5e51e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 15 May 2017 23:20:09 -0500 Subject: [PATCH 082/189] UBL G29: replace 'O' with 'T' MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Since we already used 'T' for `G29` Topology Report in the past, and since 'T' is available… --- Marlin/ubl_G29.cpp | 34 ++++++++++++++++------------------ 1 file changed, 16 insertions(+), 18 deletions(-) diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index b5b031dcc..659c4712a 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -107,10 +107,10 @@ * * I # Invalidate Invalidate specified number of Mesh Points. The nozzle location is used unless * the X and Y parameter are used. If no number is specified, only the closest Mesh - * point to the location is invalidated. The M parameter is available as well to produce + * point to the location is invalidated. The 'T' parameter is also available to produce * a map after the operation. This command is useful to invalidate a portion of the * Mesh so it can be adjusted using other tools in the Unified Bed Leveling System. When - * attempting to invalidate an isolated bad point in the mesh, the M option will indicate + * attempting to invalidate an isolated bad point in the mesh, the 'T' option will indicate * where the nozzle is positioned in the Mesh with (#). You can move the nozzle around on * the bed and use this feature to select the center of the area (or cell) you want to * invalidate. @@ -126,14 +126,6 @@ * L # Load * Load Mesh from the specified location in the EEPROM. Set this location as activated * for subsequent Load and Store operations. * - * O Map * Display the Mesh Map Topology. - * The parameter can be specified alone (ie. G29 O) or in combination with many of the - * other commands. The Mesh Map option works with all of the Phase - * commands (ie. G29 P4 R 5 X 50 Y100 C -.1 O) The Map parameter can also of a Map Type - * specified. A map type of 0 is the default is user readable. A map type of 1 can - * be specified and is suitable to Cut & Paste into Excel to allow graphing of the user's - * mesh. - * * The P or Phase commands are used for the bulk of the work to setup a Mesh. In general, your Mesh will * start off being initialized with a G29 P0 or a G29 P1. Further refinement of the Mesh happens with * each additional Phase that processes it. @@ -173,7 +165,7 @@ * area you are manually probing. Note that the command tries to start you in a corner * of the bed where movement will be predictable. You can force the location to be used in * the distance calculations by using the X and Y parameters. You may find it is helpful to - * print out a Mesh Map (G29 O) to understand where the mesh is invalidated and where + * print out a Mesh Map (G29 T) to understand where the mesh is invalidated and where * the nozzle will need to move in order to complete the command. The C parameter is * available on the Phase 2 command also and indicates the search for points to measure should * be done based on the current location of the nozzle. @@ -189,7 +181,7 @@ * to get it to grasp the shim with the same force as when you measured the thickness of the * shim at the start of the command. * - * Phase 2 allows the O (Map) parameter to be specified. This helps the user see the progression + * Phase 2 allows the T (Map) parameter to be specified. This helps the user see the progression * of the Mesh being built. * * P3 Phase 3 Fill the unpopulated regions of the Mesh with a fixed value. There are two different paths the @@ -263,6 +255,12 @@ * at a later date. The GCode output can be saved and later replayed by the host software * to reconstruct the current mesh on another machine. * + * T Topology Display the Mesh Map Topology. + * 'T' can be used alone (e.g., G29 T) or in combination with some of the other commands. + * This option works with all Phase commands (e.g., G29 P4 R 5 X 50 Y100 C -.1 O) + * This parameter can also specify a Map Type. T0 (the default) is user-readable. T1 can + * is suitable to paste into a spreadsheet for a 3D graph of the mesh. + * * U Unlevel Perform a probe of the outer perimeter to assist in physically leveling unlevel beds. * Only used for G29 P1 O U It will speed up the probing of the edge of the bed. This * is useful when the entire bed does not need to be probed because it will be adjusted. @@ -381,7 +379,7 @@ if (code_seen('J')) { if (grid_size!=0) { // if not 0 it is a normal n x n grid being probed ubl.save_ubl_active_state_and_disable(); - ubl.tilt_mesh_based_on_probed_grid(code_seen('O')); + ubl.tilt_mesh_based_on_probed_grid(code_seen('T')); ubl.restore_ubl_active_state_and_leave(); } else { // grid_size==0 which means a 3-Point leveling has been requested float z1 = probe_pt(LOGICAL_X_POSITION(UBL_PROBE_PT_1_X), LOGICAL_Y_POSITION(UBL_PROBE_PT_1_Y), false, g29_verbose_level), @@ -438,7 +436,7 @@ SERIAL_PROTOCOLLNPGM(").\n"); } ubl.probe_entire_mesh(x_pos + X_PROBE_OFFSET_FROM_EXTRUDER, y_pos + Y_PROBE_OFFSET_FROM_EXTRUDER, - code_seen('O'), code_seen('E'), code_seen('U')); + code_seen('T'), code_seen('E'), code_seen('U')); break; case 2: { @@ -487,7 +485,7 @@ return; } - manually_probe_remaining_mesh(x_pos, y_pos, height, card_thickness, code_seen('O')); + manually_probe_remaining_mesh(x_pos, y_pos, height, card_thickness, code_seen('T')); SERIAL_PROTOCOLLNPGM("G29 P2 finished."); } break; @@ -523,7 +521,7 @@ // // Fine Tune (i.e., Edit) the Mesh // - fine_tune_mesh(x_pos, y_pos, code_seen('O')); + fine_tune_mesh(x_pos, y_pos, code_seen('T')); break; case 5: ubl.find_mean_mesh_height(); break; @@ -601,7 +599,7 @@ SERIAL_PROTOCOLLNPGM("Done.\n"); } - if (code_seen('O')) + if (code_seen('T')) ubl.display_map(code_has_value() ? code_value_int() : 0); /* @@ -1112,7 +1110,7 @@ } #endif - map_type = code_seen('O') && code_has_value() ? code_value_int() : 0; + map_type = code_seen('T') && code_has_value() ? code_value_int() : 0; if (!WITHIN(map_type, 0, 1)) { SERIAL_PROTOCOLLNPGM("Invalid map type.\n"); return UBL_ERR; From 14a4257c7bc70e180746891ee42b66849f429639 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 15 May 2017 18:46:07 -0500 Subject: [PATCH 083/189] UBL tabs, whitespace, spelling, etc. --- Marlin/G26_Mesh_Validation_Tool.cpp | 6 +-- Marlin/configuration_store.cpp | 5 +-- Marlin/ubl.h | 2 +- Marlin/ubl_G29.cpp | 68 ++++++++++++++--------------- Marlin/ubl_motion.cpp | 12 ++--- Marlin/ultralcd.cpp | 2 +- 6 files changed, 46 insertions(+), 49 deletions(-) diff --git a/Marlin/G26_Mesh_Validation_Tool.cpp b/Marlin/G26_Mesh_Validation_Tool.cpp index b6cd3e1e9..5e65a200b 100644 --- a/Marlin/G26_Mesh_Validation_Tool.cpp +++ b/Marlin/G26_Mesh_Validation_Tool.cpp @@ -466,7 +466,7 @@ SERIAL_EOL; //debug_current_and_destination(PSTR("Connecting horizontal line.")); } - + print_line_from_here_to_there(LOGICAL_X_POSITION(sx), LOGICAL_Y_POSITION(sy), layer_height, LOGICAL_X_POSITION(ex), LOGICAL_Y_POSITION(ey), layer_height); } bit_set(horizontal_mesh_line_flags, i, j); // Mark it as done so we don't do it again, even if we skipped it @@ -685,7 +685,7 @@ } } - if (code_seen('S')) { + if (code_seen('S')) { nozzle = code_value_float(); if (!WITHIN(nozzle, 0.1, 1.0)) { SERIAL_PROTOCOLLNPGM("?Specified nozzle size not plausible."); @@ -727,7 +727,7 @@ } } - if (code_seen('U')) { + if (code_seen('U')) { randomSeed(millis()); random_deviation = code_has_value() ? code_value_float() : 50.0; } diff --git a/Marlin/configuration_store.cpp b/Marlin/configuration_store.cpp index 201c03558..a4d1ed279 100644 --- a/Marlin/configuration_store.cpp +++ b/Marlin/configuration_store.cpp @@ -1458,10 +1458,7 @@ void MarlinSettings::reset() { #endif SERIAL_EOL; - if (!forReplay) { - ubl.g29_what_command(); - - } + if (!forReplay) ubl.g29_what_command(); #elif HAS_ABL diff --git a/Marlin/ubl.h b/Marlin/ubl.h index 1a25997c1..93718d6c5 100644 --- a/Marlin/ubl.h +++ b/Marlin/ubl.h @@ -110,7 +110,7 @@ void save_ubl_active_state_and_disable(); void restore_ubl_active_state_and_leave(); void g29_what_command(); - void g29_eeprom_dump() ; + void g29_eeprom_dump(); void g29_compare_current_mesh_to_stored_mesh(); void fine_tune_mesh(const float &lx, const float &ly, const bool do_ubl_mesh_map); void smart_fill_mesh(); diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 659c4712a..a48b10d1f 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -74,18 +74,17 @@ * A Activate Activate the Unified Bed Leveling system. * * B # Business Use the 'Business Card' mode of the Manual Probe subsystem. This is invoked as - * G29 P2 B The mode of G29 P2 allows you to use a bussiness card or recipe card + * G29 P2 B. The mode of G29 P2 allows you to use a business card or recipe card * as a shim that the nozzle will pinch as it is lowered. The idea is that you * can easily feel the nozzle getting to the same height by the amount of resistance * the business card exhibits to movement. You should try to achieve the same amount * of resistance on each probed point to facilitate accurate and repeatable measurements. - * You should be very careful not to drive the nozzle into the bussiness card with a + * You should be very careful not to drive the nozzle into the business card with a * lot of force as it is very possible to cause damage to your printer if your are - * careless. If you use the B option with G29 P2 B you can leave the number parameter off - * on its first use to enable measurement of the business card thickness. Subsequent usage - * of the B parameter can have the number previously measured supplied to the command. - * Incidently, you are much better off using something like a Spark Gap feeler gauge than - * something that compresses like a Business Card. + * careless. If you use the B option with G29 P2 B you can omit the numeric value + * on first use to measure the business card's thickness. Subsequent usage of 'B' + * will apply the previously-measured thickness as the default. + * Note: A non-compressible Spark Gap feeler gauge is recommended over a Business Card. * * C Continue Continue, Constant, Current Location. This is not a primary command. C is used to * further refine the behaviour of several other commands. Issuing a G29 P1 C will @@ -98,7 +97,7 @@ * * E Stow_probe Stow the probe after each sampled point. * - * F # Fade * Fade the amount of Mesh Based Compensation over a specified height. At the + * F # Fade Fade the amount of Mesh Based Compensation over a specified height. At the * specified height, no correction is applied and natural printer kenimatics take over. If no * number is specified for the command, 10mm is assumed to be reasonable. * @@ -115,15 +114,15 @@ * the bed and use this feature to select the center of the area (or cell) you want to * invalidate. * - * J # Grid * Perform a Grid Based Leveling of the current Mesh using a grid with n points on a side. + * J # Grid Perform a Grid Based Leveling of the current Mesh using a grid with n points on a side. * Not specifying a grid size will invoke the 3-Point leveling function. * * K # Kompare Kompare current Mesh with stored Mesh # replacing current Mesh with the result. This * command literally performs a diff between two Meshes. * - * L Load * Load Mesh from the previously activated location in the EEPROM. + * L Load Load Mesh from the previously activated location in the EEPROM. * - * L # Load * Load Mesh from the specified location in the EEPROM. Set this location as activated + * L # Load Load Mesh from the specified location in the EEPROM. Set this location as activated * for subsequent Load and Store operations. * * The P or Phase commands are used for the bulk of the work to setup a Mesh. In general, your Mesh will @@ -143,12 +142,11 @@ * probing needed locations. This allows you to invalidate portions of the Mesh but still * use the automatic probing capabilities of the Unified Bed Leveling System. An X and Y * parameter can be given to prioritize where the command should be trying to measure points. - * If the X and Y parameters are not specified the current probe position is used. Phase 1 - * allows you to specify the M (Map) parameter so you can watch the generation of the Mesh. - * Phase 1 also watches for the LCD Panel's Encoder Switch being held in a depressed state. - * It will suspend generation of the Mesh if it sees the user request that. (This check is - * only done between probe points. You will need to press and hold the switch until the - * Phase 1 command can detect it.) + * If the X and Y parameters are not specified the current probe position is used. + * P1 accepts a 'T' (Topology) parameter so you can observe mesh generation. + * P1 also watches for the LCD Panel Encoder Switch to be held down, and will suspend + * generation of the Mesh in that case. (Note: This check is only done between probe points, + * so you must press and hold the switch until the Phase 1 command detects it.) * * P2 Phase 2 Probe areas of the Mesh that can't be automatically handled. Phase 2 respects an H * parameter to control the height between Mesh points. The default height for movement @@ -171,7 +169,7 @@ * be done based on the current location of the nozzle. * * A B parameter is also available for this command and described up above. It places the - * manual probe subsystem into Business Card mode where the thickness of a business care is + * manual probe subsystem into Business Card mode where the thickness of a business card is * measured and then used to accurately set the nozzle height in all manual probing for the * duration of the command. (S for Shim mode would be a better parameter name, but S is needed * for Save or Store of the Mesh to EEPROM) A Business card can be used, but you will have @@ -237,7 +235,7 @@ * you should have the Mesh adjusted for a Mean Height of 0.00 and the Z-Probe measuring * 0.000 at the Z Home location. * - * Q Test * Load specified Test Pattern to assist in checking correct operation of system. This + * Q Test Load specified Test Pattern to assist in checking correct operation of system. This * command is not anticipated to be of much value to the typical user. It is intended * for developers to help them verify correct operation of the Unified Bed Leveling System. * @@ -262,14 +260,16 @@ * is suitable to paste into a spreadsheet for a 3D graph of the mesh. * * U Unlevel Perform a probe of the outer perimeter to assist in physically leveling unlevel beds. - * Only used for G29 P1 O U It will speed up the probing of the edge of the bed. This - * is useful when the entire bed does not need to be probed because it will be adjusted. + * Only used for G29 P1 O U. This speeds up the probing of the edge of the bed. Useful + * when the entire bed doesn't need to be probed because it will be adjusted. * - * W What? Display valuable data the Unified Bed Leveling System knows. + * V # Verbosity Set the verbosity level (0-4) for extra details. (Default 0) * - * X # * * X Location for this line of commands + * W What? Display valuable Unified Bed Leveling System data. * - * Y # * * Y Location for this line of commands + * X # X Location for this command + * + * Y # Y Location for this command * * * Release Notes: @@ -318,7 +318,7 @@ } // Don't allow auto-leveling without homing first - if (axis_unhomed_error()) + if (axis_unhomed_error()) home_all_axes(); if (g29_parameter_parsing()) return; // abort if parsing the simple parameters causes a problem, @@ -377,7 +377,7 @@ } if (code_seen('J')) { - if (grid_size!=0) { // if not 0 it is a normal n x n grid being probed + if (grid_size) { // if not 0 it is a normal n x n grid being probed ubl.save_ubl_active_state_and_disable(); ubl.tilt_mesh_based_on_probed_grid(code_seen('T')); ubl.restore_ubl_active_state_and_leave(); @@ -479,7 +479,7 @@ } if (code_seen('H') && code_has_value()) height = code_value_float(); - + if ( !position_is_reachable_xy( x_pos, y_pos )) { SERIAL_PROTOCOLLNPGM("(X,Y) outside printable radius."); return; @@ -497,15 +497,15 @@ * - Allow 'G29 P3' to choose a 'reasonable' constant. */ if (c_flag) { - if (repetition_cnt >= GRID_MAX_POINTS) { - for ( uint8_t x = 0; x < GRID_MAX_POINTS_X; x++ ) { - for ( uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++ ) { + for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) { + for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) { ubl.z_values[x][y] = ubl_constant; } } - } else { - while (repetition_cnt--) { // this only populates reachable mesh points near + } + else { + while (repetition_cnt--) { // this only populates reachable mesh points near const mesh_index_pair location = find_closest_mesh_point_of_type(INVALID, x_pos, y_pos, USE_NOZZLE_AS_REFERENCE, NULL, false); if (location.x_index < 0) break; // No more reachable invalid Mesh Points to populate ubl.z_values[location.x_index][location.y_index] = ubl_constant; @@ -536,7 +536,7 @@ // good to have the extra information. Soon... we prune this to just a few items // if (code_seen('W')) ubl.g29_what_command(); - + // // When we are fully debugged, this may go away. But there are some valid // use cases for the users. So we can wait and see what to do with it. @@ -1578,7 +1578,7 @@ SERIAL_ECHOPGM("Could not complete LSF!"); return; } - + if (g29_verbose_level > 3) { SERIAL_ECHOPGM("LSF Results A="); SERIAL_PROTOCOL_F(lsf_results.A, 7); diff --git a/Marlin/ubl_motion.cpp b/Marlin/ubl_motion.cpp index b3ec6023e..32a17b37b 100644 --- a/Marlin/ubl_motion.cpp +++ b/Marlin/ubl_motion.cpp @@ -55,8 +55,8 @@ dy = current_position[Y_AXIS] - destination[Y_AXIS], xy_dist = HYPOT(dx, dy); - if (xy_dist == 0.0) - return; + if (xy_dist == 0.0) + return; else { SERIAL_ECHOPGM(" fpmm="); const float fpmm = de / xy_dist; @@ -461,7 +461,7 @@ static float scara_feed_factor, scara_oldA, scara_oldB; #endif - // We don't want additional apply_leveling() performed by regular buffer_line or buffer_line_kinematic, + // We don't want additional apply_leveling() performed by regular buffer_line or buffer_line_kinematic, // so we call _buffer_line directly here. Per-segmented leveling performed first. static inline void ubl_buffer_line_segment(const float ltarget[XYZE], const float &fr_mm_s, const uint8_t extruder) { @@ -530,7 +530,7 @@ difference[X_AXIS] * inv_segments, difference[Y_AXIS] * inv_segments, difference[Z_AXIS] * inv_segments, - difference[E_AXIS] * inv_segments + difference[E_AXIS] * inv_segments }; // Note that E segment distance could vary slightly as z mesh height @@ -610,7 +610,7 @@ z_x0y1 = ubl.z_values[cell_xi ][cell_yi+1], // z at lower right corner z_x1y1 = ubl.z_values[cell_xi+1][cell_yi+1]; // z at upper right corner - if (isnan(z_x0y0)) z_x0y0 = 0; // ideally activating ubl.state.active (G29 A) + if (isnan(z_x0y0)) z_x0y0 = 0; // ideally activating ubl.state.active (G29 A) if (isnan(z_x1y0)) z_x1y0 = 0; // should refuse if any invalid mesh points if (isnan(z_x0y1)) z_x0y1 = 0; // in order to avoid isnan tests per cell, if (isnan(z_x1y1)) z_x1y1 = 0; // thus guessing zero for undefined points @@ -664,7 +664,7 @@ if (!WITHIN(cx, 0, MESH_X_DIST) || !WITHIN(cy, 0, MESH_Y_DIST)) { // done within this cell, break to next rx = RAW_X_POSITION(seg_dest[X_AXIS]); ry = RAW_Y_POSITION(seg_dest[Y_AXIS]); - break; + break; } // Next segment still within same mesh cell, adjust the per-segment diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 7a810d3e3..6c0689543 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -1945,7 +1945,7 @@ void kill_screen(const char* lcd_msg) { /** * UBL System submenu - * + * * Prepare * - Unified Bed Leveling * - Activate UBL From 0fef9a2983ce788065f37207337a498eeddb0a7c Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 16 May 2017 01:19:31 -0500 Subject: [PATCH 084/189] Remove "ubl." prefix from calls within ubl method --- Marlin/ubl_G29.cpp | 34 +++++++++++++++++----------------- 1 file changed, 17 insertions(+), 17 deletions(-) diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index a48b10d1f..5a4e01edd 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -1152,17 +1152,17 @@ say_ubl_name(); SERIAL_PROTOCOLPGM("System Version " UBL_VERSION " "); - if (ubl.state.active) + if (state.active) SERIAL_PROTOCOLCHAR('A'); else SERIAL_PROTOCOLPGM("Ina"); SERIAL_PROTOCOLLNPGM("ctive.\n"); safe_delay(50); - if (ubl.state.eeprom_storage_slot == -1) + if (state.eeprom_storage_slot == -1) SERIAL_PROTOCOLPGM("No Mesh Loaded."); else { - SERIAL_PROTOCOLPAIR("Mesh ", ubl.state.eeprom_storage_slot); + SERIAL_PROTOCOLPAIR("Mesh ", state.eeprom_storage_slot); SERIAL_PROTOCOLPGM(" Loaded."); } SERIAL_EOL; @@ -1179,7 +1179,7 @@ SERIAL_PROTOCOL_F(zprobe_zoffset, 7); SERIAL_EOL; - SERIAL_PROTOCOLLNPAIR("ubl.eeprom_start=", hex_address((void*)ubl.eeprom_start)); + SERIAL_PROTOCOLLNPAIR("ubl.eeprom_start=", hex_address((void*)eeprom_start)); SERIAL_ECHOLNPAIR("GRID_MAX_POINTS_X ", GRID_MAX_POINTS_X); SERIAL_ECHOLNPAIR("GRID_MAX_POINTS_Y ", GRID_MAX_POINTS_Y); @@ -1191,7 +1191,7 @@ SERIAL_PROTOCOLPGM("X-Axis Mesh Points at: "); for (uint8_t i = 0; i < GRID_MAX_POINTS_X; i++) { - SERIAL_PROTOCOL_F(LOGICAL_X_POSITION(pgm_read_float(&ubl.mesh_index_to_xpos[i])), 3); + SERIAL_PROTOCOL_F(LOGICAL_X_POSITION(pgm_read_float(&mesh_index_to_xpos[i])), 3); SERIAL_PROTOCOLPGM(" "); safe_delay(25); } @@ -1199,26 +1199,26 @@ SERIAL_PROTOCOLPGM("Y-Axis Mesh Points at: "); for (uint8_t i = 0; i < GRID_MAX_POINTS_Y; i++) { - SERIAL_PROTOCOL_F(LOGICAL_Y_POSITION(pgm_read_float(&ubl.mesh_index_to_ypos[i])), 3); + SERIAL_PROTOCOL_F(LOGICAL_Y_POSITION(pgm_read_float(&mesh_index_to_ypos[i])), 3); SERIAL_PROTOCOLPGM(" "); safe_delay(25); } SERIAL_EOL; - SERIAL_PROTOCOLLNPAIR("Free EEPROM space starts at: ", hex_address((void*)ubl.eeprom_start)); + SERIAL_PROTOCOLLNPAIR("Free EEPROM space starts at: ", hex_address((void*)eeprom_start)); SERIAL_PROTOCOLLNPAIR("end of EEPROM: ", hex_address((void*)E2END)); safe_delay(25); - SERIAL_PROTOCOLPAIR("sizeof(ubl.state) : ", (int)sizeof(ubl.state)); + SERIAL_PROTOCOLPAIR("sizeof(ubl.state) : ", (int)sizeof(state)); SERIAL_EOL; - SERIAL_PROTOCOLLNPAIR("z_value[][] size: ", (int)sizeof(ubl.z_values)); + SERIAL_PROTOCOLLNPAIR("z_value[][] size: ", (int)sizeof(z_values)); SERIAL_EOL; safe_delay(25); SERIAL_PROTOCOLLNPAIR("EEPROM free for UBL: ", hex_address((void*)k)); safe_delay(25); - SERIAL_PROTOCOLPAIR("EEPROM can hold ", k / sizeof(ubl.z_values)); + SERIAL_PROTOCOLPAIR("EEPROM can hold ", k / sizeof(z_values)); SERIAL_PROTOCOLLNPGM(" meshes.\n"); safe_delay(25); @@ -1239,7 +1239,7 @@ SERIAL_ECHOLNPAIR("=", UBL_MESH_MAX_Y); safe_delay(25); - if (!ubl.sanity_check()) { + if (!sanity_check()) { say_ubl_name(); SERIAL_PROTOCOLLNPGM("sanity checks passed."); } @@ -1554,11 +1554,11 @@ SERIAL_ECHOPGM(") measured: "); SERIAL_PROTOCOL_F(measured_z, 7); SERIAL_ECHOPGM(" correction: "); - SERIAL_PROTOCOL_F(ubl.get_z_correction(LOGICAL_X_POSITION(x), LOGICAL_Y_POSITION(y)), 7); + SERIAL_PROTOCOL_F(get_z_correction(LOGICAL_X_POSITION(x), LOGICAL_Y_POSITION(y)), 7); } #endif - measured_z -= ubl.get_z_correction(LOGICAL_X_POSITION(x), LOGICAL_Y_POSITION(y)) /* + zprobe_zoffset */ ; + measured_z -= get_z_correction(LOGICAL_X_POSITION(x), LOGICAL_Y_POSITION(y)) /* + zprobe_zoffset */ ; #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) { @@ -1605,9 +1605,9 @@ for (uint8_t i = 0; i < GRID_MAX_POINTS_X; i++) { for (uint8_t j = 0; j < GRID_MAX_POINTS_Y; j++) { - float x_tmp = pgm_read_float(&ubl.mesh_index_to_xpos[i]), - y_tmp = pgm_read_float(&ubl.mesh_index_to_ypos[j]), - z_tmp = ubl.z_values[i][j]; + float x_tmp = pgm_read_float(&mesh_index_to_xpos[i]), + y_tmp = pgm_read_float(&mesh_index_to_ypos[j]), + z_tmp = z_values[i][j]; #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) { @@ -1637,7 +1637,7 @@ } #endif - ubl.z_values[i][j] += z_tmp - lsf_results.D; + z_values[i][j] += z_tmp - lsf_results.D; } } From a5737cba7cd8de8dde344aa7288eabd1294b9a1d Mon Sep 17 00:00:00 2001 From: Johann Delahayes Date: Tue, 16 May 2017 12:27:42 +0200 Subject: [PATCH 085/189] Update french language --- Marlin/language_fr.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/language_fr.h b/Marlin/language_fr.h index f0ea9b7d0..61097ea84 100644 --- a/Marlin/language_fr.h +++ b/Marlin/language_fr.h @@ -121,7 +121,7 @@ #define MSG_E3STEPS _UxGT("E3pas/mm") #define MSG_E4STEPS _UxGT("E4pas/mm") #define MSG_E5STEPS _UxGT("E5pas/mm") -#define MSG_TEMPERATURE _UxGT("Tempzrature") +#define MSG_TEMPERATURE _UxGT("Température") #define MSG_MOTION _UxGT("Mouvement") #define MSG_FILAMENT _UxGT("Filament") #define MSG_VOLUMETRIC_ENABLED _UxGT("E en mm3") From 0cd398c25d4101818c1d0a5ffc7566dede104404 Mon Sep 17 00:00:00 2001 From: Tannoo Date: Tue, 16 May 2017 07:45:31 -0600 Subject: [PATCH 086/189] UBL Menu Updates (#6751) Things should be pretty stable for a while. But it wouldn't surprise me if the Delta people have a need for a few special commands. --- Marlin/ubl_G29.cpp | 8 +++++--- Marlin/ultralcd.cpp | 34 +++++++++++++++++----------------- 2 files changed, 22 insertions(+), 20 deletions(-) diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 5a4e01edd..ce1d91412 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -318,8 +318,11 @@ } // Don't allow auto-leveling without homing first - if (axis_unhomed_error()) - home_all_axes(); + if (axis_unhomed_error()) { + if (code_seen('P') && !code_seen('P6') || code_seen('J')) { + home_all_axes(); + } + } if (g29_parameter_parsing()) return; // abort if parsing the simple parameters causes a problem, @@ -528,7 +531,6 @@ case 6: ubl.shift_mesh_height(); break; } - } // diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 6c0689543..0c2117912 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -1719,12 +1719,12 @@ void kill_screen(const char* lcd_msg) { if (UBL_HEIGHT_AMOUNT < 0) { // Convert to positive for the `sprintf_P` string. UBL_HEIGHT_AMOUNT = (UBL_HEIGHT_AMOUNT - (UBL_HEIGHT_AMOUNT * 2)); // Convert to positive - sprintf_P(UBL_LCD_GCODE, PSTR("G29 N Z-.%i"), UBL_HEIGHT_AMOUNT); + sprintf_P(UBL_LCD_GCODE, PSTR("G29 P6-.%i"), UBL_HEIGHT_AMOUNT); // Convert back to negative to preserve the user setting. UBL_HEIGHT_AMOUNT = (UBL_HEIGHT_AMOUNT - (UBL_HEIGHT_AMOUNT * 2)); // Convert back to negative } else { - sprintf_P(UBL_LCD_GCODE, PSTR("G29 N Z.%i"), UBL_HEIGHT_AMOUNT); + sprintf_P(UBL_LCD_GCODE, PSTR("G29 P6.%i"), UBL_HEIGHT_AMOUNT); } enqueue_and_echo_command(UBL_LCD_GCODE); } @@ -1748,8 +1748,8 @@ void kill_screen(const char* lcd_msg) { START_MENU(); MENU_BACK(MSG_UBL_TOOLS); MENU_BACK(MSG_UBL_LEVEL_BED); - MENU_ITEM(gcode, MSG_UBL_FINE_TUNE_ALL, PSTR("G29 P4 R O")); - MENU_ITEM(gcode, MSG_UBL_FINE_TUNE_CLOSEST, PSTR("G29 P4 O")); + MENU_ITEM(gcode, MSG_UBL_FINE_TUNE_ALL, PSTR("G29 P4 R T")); + MENU_ITEM(gcode, MSG_UBL_FINE_TUNE_CLOSEST, PSTR("G29 P4 T")); MENU_ITEM(submenu, MSG_UBL_MESH_HEIGHT_ADJUST, _lcd_ubl_height_adjust_menu); MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); END_MENU(); @@ -1813,7 +1813,7 @@ void kill_screen(const char* lcd_msg) { void _lcd_ubl_mesh_leveling() { START_MENU(); MENU_BACK(MSG_UBL_TOOLS); - MENU_ITEM(gcode, MSG_UBL_3POINT_MESH_LEVELING, PSTR("G29 T")); + MENU_ITEM(gcode, MSG_UBL_3POINT_MESH_LEVELING, PSTR("G29 J0")); MENU_ITEM(submenu, MSG_UBL_GRID_MESH_LEVELING, _lcd_ubl_grid_level); MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); END_MENU(); @@ -1823,7 +1823,7 @@ void kill_screen(const char* lcd_msg) { * UBL Fill-in Amount Mesh Command */ void _lcd_ubl_fillin_amount_cmd() { - sprintf_P(UBL_LCD_GCODE, PSTR("G29 P3 R C.%i N"), UBL_FILLIN_AMOUNT); + sprintf_P(UBL_LCD_GCODE, PSTR("G29 P3 R C.%i"), UBL_FILLIN_AMOUNT); enqueue_and_echo_command(UBL_LCD_GCODE); } @@ -1831,7 +1831,7 @@ void kill_screen(const char* lcd_msg) { * UBL Smart Fill-in Command */ void _lcd_ubl_smart_fillin_cmd() { - sprintf_P(UBL_LCD_GCODE, PSTR("G29 P3 N O%i"), map_type); + sprintf_P(UBL_LCD_GCODE, PSTR("G29 P3 T%i"), map_type); enqueue_and_echo_command(UBL_LCD_GCODE); } @@ -1844,7 +1844,7 @@ void kill_screen(const char* lcd_msg) { MENU_ITEM_EDIT(int3, MSG_UBL_FILLIN_AMOUNT, &UBL_FILLIN_AMOUNT, 0, 9); MENU_ITEM(function, MSG_UBL_FILLIN_MESH, _lcd_ubl_fillin_amount_cmd); MENU_ITEM(function, MSG_UBL_SMART_FILLIN, _lcd_ubl_smart_fillin_cmd); - MENU_ITEM(gcode, MSG_UBL_MANUAL_FILLIN, PSTR("G29 P2 B O")); + MENU_ITEM(gcode, MSG_UBL_MANUAL_FILLIN, PSTR("G29 P2 B T0")); MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); END_MENU(); } @@ -1886,7 +1886,7 @@ void kill_screen(const char* lcd_msg) { * UBL Load Mesh Command */ void _lcd_ubl_load_mesh_cmd() { - sprintf_P(UBL_LCD_GCODE, PSTR("G29 N L%i"), UBL_STORAGE_SLOT); + sprintf_P(UBL_LCD_GCODE, PSTR("G29 L%i"), UBL_STORAGE_SLOT); enqueue_and_echo_command(UBL_LCD_GCODE); } @@ -1894,7 +1894,7 @@ void kill_screen(const char* lcd_msg) { * UBL Save Mesh Command */ void _lcd_ubl_save_mesh_cmd() { - sprintf_P(UBL_LCD_GCODE, PSTR("G29 N S%i"), UBL_STORAGE_SLOT); + sprintf_P(UBL_LCD_GCODE, PSTR("G29 S%i"), UBL_STORAGE_SLOT); enqueue_and_echo_command(UBL_LCD_GCODE); } @@ -1914,7 +1914,7 @@ void kill_screen(const char* lcd_msg) { * UBL Output map Command */ void _lcd_ubl_output_map_cmd() { - sprintf_P(UBL_LCD_GCODE, PSTR("G29 N O%i"), map_type); + sprintf_P(UBL_LCD_GCODE, PSTR("G29 T%i"), map_type); enqueue_and_echo_command(UBL_LCD_GCODE); } @@ -2002,12 +2002,12 @@ void kill_screen(const char* lcd_msg) { void _lcd_ubl_level_bed() { START_MENU(); MENU_BACK(MSG_PREPARE); - MENU_ITEM(gcode, MSG_UBL_ACTIVATE_MESH, PSTR("G29 A N")); - MENU_ITEM(gcode, MSG_UBL_DEACTIVATE_MESH, PSTR("G29 D N")); + MENU_ITEM(gcode, MSG_UBL_ACTIVATE_MESH, PSTR("G29 A")); + MENU_ITEM(gcode, MSG_UBL_DEACTIVATE_MESH, PSTR("G29 D")); MENU_ITEM(submenu, MSG_UBL_STORAGE_MESH_MENU, _lcd_ubl_storage_mesh); MENU_ITEM(submenu, MSG_UBL_OUTPUT_MAP, _lcd_ubl_output_map); MENU_ITEM(submenu, MSG_UBL_TOOLS, _lcd_ubl_tools_menu); - MENU_ITEM(gcode, MSG_UBL_INFO_UBL, PSTR("G29 W N")); + MENU_ITEM(gcode, MSG_UBL_INFO_UBL, PSTR("G29 W")); END_MENU(); } #endif @@ -2497,10 +2497,10 @@ void kill_screen(const char* lcd_msg) { #if ENABLED(EEPROM_SETTINGS) MENU_ITEM(function, MSG_STORE_EEPROM, lcd_store_settings); MENU_ITEM(function, MSG_LOAD_EEPROM, lcd_load_settings); + MENU_ITEM(function, MSG_RESTORE_FAILSAFE, lcd_factory_settings); + MENU_ITEM(gcode, MSG_INIT_EEPROM, PSTR("M502\nM500\nM501")); #endif - - MENU_ITEM(function, MSG_RESTORE_FAILSAFE, lcd_factory_settings); - END_MENU(); + END_MENU(); } /** From 86066443438076b8a02552b660f44f68c25744f2 Mon Sep 17 00:00:00 2001 From: Roxy-3D Date: Tue, 16 May 2017 11:23:50 -0500 Subject: [PATCH 087/189] M48 Fix for Delta Configuration Files & UBL G29 only homes when necessary (#6757) * Fix M48 for Delta's There was a scope issue: DELTA_PROBEABLE_RADIUS wasn't getting defined. * Check if the specified G29 command requires homing --- .../delta/generic/Configuration.h | 6 ++-- .../delta/kossel_mini/Configuration.h | 6 ++-- .../delta/kossel_pro/Configuration.h | 6 ++-- .../delta/kossel_xl/Configuration.h | 6 ++-- Marlin/ubl_G29.cpp | 29 +++++++++++++------ 5 files changed, 36 insertions(+), 17 deletions(-) diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index 996100182..7b5fdad7a 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -922,6 +922,10 @@ // at which point movement will be level to the machine's XY plane. // The height can be set with M420 Z //#define ENABLE_LEVELING_FADE_HEIGHT + + // Set the boundaries for probing (where the probe can reach). + #define DELTA_PROBEABLE_RADIUS (DELTA_PRINTABLE_RADIUS - 10) + #endif #if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR) @@ -931,8 +935,6 @@ #define GRID_MAX_POINTS_X 9 #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X - // Set the boundaries for probing (where the probe can reach). - #define DELTA_PROBEABLE_RADIUS (DELTA_PRINTABLE_RADIUS - 10) #define LEFT_PROBE_BED_POSITION -(DELTA_PROBEABLE_RADIUS) #define RIGHT_PROBE_BED_POSITION DELTA_PROBEABLE_RADIUS #define FRONT_PROBE_BED_POSITION -(DELTA_PROBEABLE_RADIUS) diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index 0bf14708d..e48cceb50 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -920,6 +920,10 @@ // at which point movement will be level to the machine's XY plane. // The height can be set with M420 Z //#define ENABLE_LEVELING_FADE_HEIGHT + + // Set the boundaries for probing (where the probe can reach). + #define DELTA_PROBEABLE_RADIUS (DELTA_PRINTABLE_RADIUS - 10) + #endif #if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR) @@ -929,8 +933,6 @@ #define GRID_MAX_POINTS_X 9 #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X - // Set the boundaries for probing (where the probe can reach). - #define DELTA_PROBEABLE_RADIUS (DELTA_PRINTABLE_RADIUS - 10) #define LEFT_PROBE_BED_POSITION -(DELTA_PROBEABLE_RADIUS) #define RIGHT_PROBE_BED_POSITION DELTA_PROBEABLE_RADIUS #define FRONT_PROBE_BED_POSITION -(DELTA_PROBEABLE_RADIUS) diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration.h b/Marlin/example_configurations/delta/kossel_pro/Configuration.h index bb769b172..0cbd2dbb6 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration.h @@ -926,6 +926,10 @@ // at which point movement will be level to the machine's XY plane. // The height can be set with M420 Z //#define ENABLE_LEVELING_FADE_HEIGHT + + // Set the boundaries for probing (where the probe can reach). + #define DELTA_PROBEABLE_RADIUS (DELTA_PRINTABLE_RADIUS - 10) + #endif #if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR) @@ -935,8 +939,6 @@ #define GRID_MAX_POINTS_X 7 #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X - // Set the boundaries for probing (where the probe can reach). - #define DELTA_PROBEABLE_RADIUS (DELTA_PRINTABLE_RADIUS - 25) #define LEFT_PROBE_BED_POSITION -(DELTA_PROBEABLE_RADIUS) #define RIGHT_PROBE_BED_POSITION DELTA_PROBEABLE_RADIUS #define FRONT_PROBE_BED_POSITION -(DELTA_PROBEABLE_RADIUS) diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration.h b/Marlin/example_configurations/delta/kossel_xl/Configuration.h index b8038252e..b1f834b6a 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration.h @@ -989,6 +989,10 @@ // at which point movement will be level to the machine's XY plane. // The height can be set with M420 Z //#define ENABLE_LEVELING_FADE_HEIGHT + + // Set the boundaries for probing (where the probe can reach). + #define DELTA_PROBEABLE_RADIUS (DELTA_PRINTABLE_RADIUS - 10) + #endif #if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR) @@ -998,8 +1002,6 @@ #define GRID_MAX_POINTS_X 5 #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X - // Set the boundaries for probing (where the probe can reach). - #define DELTA_PROBEABLE_RADIUS (DELTA_PRINTABLE_RADIUS - 10) #define LEFT_PROBE_BED_POSITION -(DELTA_PROBEABLE_RADIUS) #define RIGHT_PROBE_BED_POSITION DELTA_PROBEABLE_RADIUS #define FRONT_PROBE_BED_POSITION - (DELTA_PROBEABLE_RADIUS - 20) diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index ce1d91412..4b34b8f96 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -135,9 +135,12 @@ * a subsequent G or T leveling operation for backward compatibility. * * P1 Phase 1 Invalidate entire Mesh and continue with automatic generation of the Mesh data using - * the Z-Probe. Depending upon the values of DELTA_PROBEABLE_RADIUS and - * DELTA_PRINTABLE_RADIUS some area of the bed will not have Mesh Data automatically - * generated. This will be handled in Phase 2. If the Phase 1 command is given the + * the Z-Probe. Usually the probe can not reach all areas that the nozzle can reach. + * In Cartesian printers, mesh points within the X_OFFSET_FROM_EXTRUDER and Y_OFFSET_FROM_EXTRUDER + * area can not be automatically probed. For Delta printers the area in which DELTA_PROBEABLE_RADIUS + * and DELTA_PRINTABLE_RADIUS do not overlap will not be automatically probed. + * + * These points will be handled in Phase 2 and Phase 3. If the Phase 1 command is given the * C (Continue) parameter it does not invalidate the Mesh prior to automatically * probing needed locations. This allows you to invalidate portions of the Mesh but still * use the automatic probing capabilities of the Unified Bed Leveling System. An X and Y @@ -254,13 +257,13 @@ * to reconstruct the current mesh on another machine. * * T Topology Display the Mesh Map Topology. - * 'T' can be used alone (e.g., G29 T) or in combination with some of the other commands. - * This option works with all Phase commands (e.g., G29 P4 R 5 X 50 Y100 C -.1 O) + * 'T' can be used alone (e.g., G29 T) or in combination with most of the other commands. + * This option works with all Phase commands (e.g., G29 P4 R 5 T X 50 Y100 C -.1 O) * This parameter can also specify a Map Type. T0 (the default) is user-readable. T1 can * is suitable to paste into a spreadsheet for a 3D graph of the mesh. * * U Unlevel Perform a probe of the outer perimeter to assist in physically leveling unlevel beds. - * Only used for G29 P1 O U. This speeds up the probing of the edge of the bed. Useful + * Only used for G29 P1 T U. This speeds up the probing of the edge of the bed. Useful * when the entire bed doesn't need to be probed because it will be adjusted. * * V # Verbosity Set the verbosity level (0-4) for extra details. (Default 0) @@ -317,11 +320,19 @@ return; } - // Don't allow auto-leveling without homing first + // Check for commands that require the printer to be homed. if (axis_unhomed_error()) { - if (code_seen('P') && !code_seen('P6') || code_seen('J')) { + if (code_seen('J')) home_all_axes(); - } + else + if (code_seen('P')) { + int p_val; + if (code_has_value()) { + p_val = code_value_int(); + if ( p_val==1 || p_val==2 || p_val==4 ) + home_all_axes(); + } + } } if (g29_parameter_parsing()) return; // abort if parsing the simple parameters causes a problem, From 5a9e52a3e08738ccb45cecb40991225526a424be Mon Sep 17 00:00:00 2001 From: oldmcg Date: Tue, 16 May 2017 11:47:51 -0500 Subject: [PATCH 088/189] Use COPY_XYZE macro to copy exactly 4 elements (#6758) Fix undefined DELTA_PROBEABLE_RADIUS for UBL_DELTA --- Marlin/Conditionals_post.h | 7 +++++-- Marlin/ubl_motion.cpp | 16 ++++++++++++---- 2 files changed, 17 insertions(+), 6 deletions(-) diff --git a/Marlin/Conditionals_post.h b/Marlin/Conditionals_post.h index 258736eab..1a99ee2fb 100644 --- a/Marlin/Conditionals_post.h +++ b/Marlin/Conditionals_post.h @@ -818,7 +818,7 @@ #endif /** - * DELTA_SEGMENT_MIN_LENGTH for UBL_DELTA + * DELTA_SEGMENT_MIN_LENGTH and DELTA_PROBEABLE_RADIUS for UBL_DELTA */ #if UBL_DELTA #ifndef DELTA_SEGMENT_MIN_LENGTH @@ -830,8 +830,11 @@ #define DELTA_SEGMENT_MIN_LENGTH 1.00 // mm (similar to G2/G3 arc segmentation) #endif #endif + #ifndef DELTA_PROBEABLE_RADIUS + #define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS + #endif #endif - + // Shorthand #define GRID_MAX_POINTS ((GRID_MAX_POINTS_X) * (GRID_MAX_POINTS_Y)) diff --git a/Marlin/ubl_motion.cpp b/Marlin/ubl_motion.cpp index 32a17b37b..b31516086 100644 --- a/Marlin/ubl_motion.cpp +++ b/Marlin/ubl_motion.cpp @@ -457,6 +457,14 @@ #if UBL_DELTA + // macro to inline copy exactly 4 floats, don't rely on sizeof operator + #define COPY_XYZE( target, source ) { \ + target[X_AXIS] = source[X_AXIS]; \ + target[Y_AXIS] = source[Y_AXIS]; \ + target[Z_AXIS] = source[Z_AXIS]; \ + target[E_AXIS] = source[E_AXIS]; \ + } + #if IS_SCARA // scale the feed rate from mm/s to degrees/s static float scara_feed_factor, scara_oldA, scara_oldB; #endif @@ -550,8 +558,8 @@ const float z_offset = ubl.state.active ? ubl.state.z_offset : 0.0; - float seg_dest[XYZE]; // per-segment destination, - COPY(seg_dest, current_position); // starting from current position + float seg_dest[XYZE]; // per-segment destination, + COPY_XYZE(seg_dest, current_position); // starting from current position while (--segments) { LOOP_XYZE(i) seg_dest[i] += segment_distance[i]; @@ -562,7 +570,7 @@ } // Since repeated adding segment_distance accumulates small errors, final move to exact destination. - COPY(seg_dest, ltarget); + COPY_XYZE(seg_dest, ltarget); seg_dest[Z_AXIS] += z_offset; ubl_buffer_line_segment(seg_dest, feedrate, active_extruder); return false; // moved but did not set_current_to_destination(); @@ -645,7 +653,7 @@ z_cxcy += ubl.state.z_offset; // add fixed mesh offset from G29 Z if (--segments == 0) { // if this is last segment, use ltarget for exact - COPY(seg_dest, ltarget); + COPY_XYZE(seg_dest, ltarget); seg_dest[Z_AXIS] += z_cxcy; ubl_buffer_line_segment(seg_dest, feedrate, active_extruder); return false; // did not set_current_to_destination() From d30e478f97509775b3e5e8df98a09c6ef6c476bd Mon Sep 17 00:00:00 2001 From: Roxy-3D Date: Tue, 16 May 2017 15:24:24 -0500 Subject: [PATCH 089/189] Fix incorrectly optimized find_closest_mesh_point_of_type() function (#6761) --- Marlin/ubl_G29.cpp | 16 +++++++++++----- 1 file changed, 11 insertions(+), 5 deletions(-) diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 4b34b8f96..e3a6294cd 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -730,7 +730,7 @@ * Probe all invalidated locations of the mesh that can be reached by the probe. * This attempts to fill in locations closest to the nozzle's start location first. */ - void unified_bed_leveling::probe_entire_mesh(const float &lx, const float &ly, const bool do_ubl_mesh_map, const bool stow_probe, bool do_furthest) { + void unified_bed_leveling::probe_entire_mesh(const float &lx, const float &ly, const bool do_ubl_mesh_map, const bool stow_probe, bool close_or_far) { mesh_index_pair location; ubl.has_control_of_lcd_panel = true; @@ -751,10 +751,9 @@ return; } - location = find_closest_mesh_point_of_type(INVALID, lx, ly, USE_PROBE_AS_REFERENCE, NULL, do_furthest); + location = find_closest_mesh_point_of_type(INVALID, lx, ly, USE_PROBE_AS_REFERENCE, NULL, close_or_far); if (location.x_index >= 0) { // mesh point found and is reachable by probe - const float rawx = pgm_read_float(&ubl.mesh_index_to_xpos[location.x_index]), rawy = pgm_read_float(&ubl.mesh_index_to_ypos[location.y_index]); @@ -763,7 +762,6 @@ } if (do_ubl_mesh_map) ubl.display_map(map_type); - } while ((location.x_index >= 0) && (--max_iterations)); STOW_PROBE(); @@ -1343,7 +1341,15 @@ // Also for round beds, there are grid points outside the bed that nozzle can't reach. // Prune them from the list and ignore them till the next Phase (manual nozzle probing). - if ((probe_as_reference && position_is_reachable_by_probe_raw_xy(mx, my)) || position_is_reachable_raw_xy(mx, my)) +// if ((probe_as_reference && position_is_reachable_by_probe_raw_xy(mx, my)) || position_is_reachable_raw_xy(mx, my)) +// continue; +// +// THE ABOVE CODE IS NOT A REPLACEMENT FOR THE CODE BELOW!!!!!!! +// + bool reachable = probe_as_reference ? + position_is_reachable_by_probe_raw_xy( mx, my ) : + position_is_reachable_raw_xy( mx, my ); + if ( ! reachable ) continue; // Reachable. Check if it's the closest location to the nozzle. From 6b6630e11bad64bc5a493fb0b1b479a77de47c1d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 16 May 2017 15:25:30 -0500 Subject: [PATCH 090/189] Clean up trailing whitespace and tabs --- Marlin/Conditionals_post.h | 2 +- .../delta/generic/Configuration.h | 4 +-- .../delta/kossel_mini/Configuration.h | 4 +-- .../delta/kossel_pro/Configuration.h | 4 +-- .../delta/kossel_xl/Configuration.h | 4 +-- Marlin/ubl_G29.cpp | 26 ++++++------------- Marlin/ubl_motion.cpp | 4 +-- 7 files changed, 19 insertions(+), 29 deletions(-) diff --git a/Marlin/Conditionals_post.h b/Marlin/Conditionals_post.h index 1a99ee2fb..5c34ac48b 100644 --- a/Marlin/Conditionals_post.h +++ b/Marlin/Conditionals_post.h @@ -834,7 +834,7 @@ #define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS #endif #endif - + // Shorthand #define GRID_MAX_POINTS ((GRID_MAX_POINTS_X) * (GRID_MAX_POINTS_Y)) diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index 7b5fdad7a..9b810fcf3 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -922,10 +922,10 @@ // at which point movement will be level to the machine's XY plane. // The height can be set with M420 Z //#define ENABLE_LEVELING_FADE_HEIGHT - + // Set the boundaries for probing (where the probe can reach). #define DELTA_PROBEABLE_RADIUS (DELTA_PRINTABLE_RADIUS - 10) - + #endif #if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR) diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index e48cceb50..8db5f7c35 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -920,10 +920,10 @@ // at which point movement will be level to the machine's XY plane. // The height can be set with M420 Z //#define ENABLE_LEVELING_FADE_HEIGHT - + // Set the boundaries for probing (where the probe can reach). #define DELTA_PROBEABLE_RADIUS (DELTA_PRINTABLE_RADIUS - 10) - + #endif #if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR) diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration.h b/Marlin/example_configurations/delta/kossel_pro/Configuration.h index 0cbd2dbb6..2eb723ff3 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration.h @@ -926,10 +926,10 @@ // at which point movement will be level to the machine's XY plane. // The height can be set with M420 Z //#define ENABLE_LEVELING_FADE_HEIGHT - + // Set the boundaries for probing (where the probe can reach). #define DELTA_PROBEABLE_RADIUS (DELTA_PRINTABLE_RADIUS - 10) - + #endif #if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR) diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration.h b/Marlin/example_configurations/delta/kossel_xl/Configuration.h index b1f834b6a..a6d08014b 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration.h @@ -989,10 +989,10 @@ // at which point movement will be level to the machine's XY plane. // The height can be set with M420 Z //#define ENABLE_LEVELING_FADE_HEIGHT - + // Set the boundaries for probing (where the probe can reach). #define DELTA_PROBEABLE_RADIUS (DELTA_PRINTABLE_RADIUS - 10) - + #endif #if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR) diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index e3a6294cd..065256c8d 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -322,17 +322,15 @@ // Check for commands that require the printer to be homed. if (axis_unhomed_error()) { - if (code_seen('J')) + if (code_seen('J')) home_all_axes(); - else - if (code_seen('P')) { - int p_val; - if (code_has_value()) { - p_val = code_value_int(); - if ( p_val==1 || p_val==2 || p_val==4 ) - home_all_axes(); - } + else if (code_seen('P')) { + if (code_has_value()) { + const int p_val = code_value_int(); + if (p_val == 1 || p_val == 2 || p_val == 4) + home_all_axes(); } + } } if (g29_parameter_parsing()) return; // abort if parsing the simple parameters causes a problem, @@ -1341,15 +1339,7 @@ // Also for round beds, there are grid points outside the bed that nozzle can't reach. // Prune them from the list and ignore them till the next Phase (manual nozzle probing). -// if ((probe_as_reference && position_is_reachable_by_probe_raw_xy(mx, my)) || position_is_reachable_raw_xy(mx, my)) -// continue; -// -// THE ABOVE CODE IS NOT A REPLACEMENT FOR THE CODE BELOW!!!!!!! -// - bool reachable = probe_as_reference ? - position_is_reachable_by_probe_raw_xy( mx, my ) : - position_is_reachable_raw_xy( mx, my ); - if ( ! reachable ) + if ( ! (probe_as_reference ? position_is_reachable_by_probe_raw_xy(mx, my) : position_is_reachable_raw_xy(mx, my)) ) continue; // Reachable. Check if it's the closest location to the nozzle. diff --git a/Marlin/ubl_motion.cpp b/Marlin/ubl_motion.cpp index b31516086..64aac5e17 100644 --- a/Marlin/ubl_motion.cpp +++ b/Marlin/ubl_motion.cpp @@ -632,7 +632,7 @@ z_cxyd = z_cxy1 - z_cxy0; // z height difference along cx from y0 to y1 float z_cxym = z_cxyd * (1.0 / (MESH_Y_DIST)); // z slope per y along cx from y0 to y1 - + // float z_cxcy = z_cxy0 + z_cxym * cy; // interpolated mesh z height along cx at cy (do inside the segment loop) // As subsequent segments step through this cell, the z_cxy0 intercept will change @@ -649,7 +649,7 @@ #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) z_cxcy *= fade_scaling_factor; // apply fade factor to interpolated mesh height #endif - + z_cxcy += ubl.state.z_offset; // add fixed mesh offset from G29 Z if (--segments == 0) { // if this is last segment, use ltarget for exact From 238fb5361721fe38c58dad2f95d4b3789e94c3d8 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 16 May 2017 16:18:38 -0500 Subject: [PATCH 091/189] Patch home_all_axes to ignore G28 XYZ parameters --- Marlin/Marlin_main.cpp | 30 ++++++++++++++++-------------- 1 file changed, 16 insertions(+), 14 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 01151bc96..d59143d19 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -3713,7 +3713,7 @@ inline void gcode_G4() { * Z Home to the Z endstop * */ -inline void gcode_G28() { +inline void gcode_G28(const bool always_home_all) { #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) { @@ -3760,14 +3760,16 @@ inline void gcode_G28() { #else // NOT DELTA - const bool homeX = code_seen('X'), homeY = code_seen('Y'), homeZ = code_seen('Z'), - home_all_axis = (!homeX && !homeY && !homeZ) || (homeX && homeY && homeZ); + const bool homeX = always_home_all || code_seen('X'), + homeY = always_home_all || code_seen('Y'), + homeZ = always_home_all || code_seen('Z'), + home_all = (!homeX && !homeY && !homeZ) || (homeX && homeY && homeZ); set_destination_to_current(); #if Z_HOME_DIR > 0 // If homing away from BED do Z first - if (home_all_axis || homeZ) { + if (home_all || homeZ) { HOMEAXIS(Z); #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) DEBUG_POS("> HOMEAXIS(Z)", current_position); @@ -3776,7 +3778,7 @@ inline void gcode_G28() { #else - if (home_all_axis || homeX || homeY) { + if (home_all || homeX || homeY) { // Raise Z before homing any other axes and z is not already high enough (never lower z) destination[Z_AXIS] = LOGICAL_Z_POSITION(Z_HOMING_HEIGHT); if (destination[Z_AXIS] > current_position[Z_AXIS]) { @@ -3794,14 +3796,14 @@ inline void gcode_G28() { #if ENABLED(QUICK_HOME) - if (home_all_axis || (homeX && homeY)) quick_home_xy(); + if (home_all || (homeX && homeY)) quick_home_xy(); #endif #if ENABLED(HOME_Y_BEFORE_X) // Home Y - if (home_all_axis || homeY) { + if (home_all || homeY) { HOMEAXIS(Y); #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) DEBUG_POS("> homeY", current_position); @@ -3811,7 +3813,7 @@ inline void gcode_G28() { #endif // Home X - if (home_all_axis || homeX) { + if (home_all || homeX) { #if ENABLED(DUAL_X_CARRIAGE) @@ -3844,7 +3846,7 @@ inline void gcode_G28() { #if DISABLED(HOME_Y_BEFORE_X) // Home Y - if (home_all_axis || homeY) { + if (home_all || homeY) { HOMEAXIS(Y); #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) DEBUG_POS("> homeY", current_position); @@ -3854,16 +3856,16 @@ inline void gcode_G28() { // Home Z last if homing towards the bed #if Z_HOME_DIR < 0 - if (home_all_axis || homeZ) { + if (home_all || homeZ) { #if ENABLED(Z_SAFE_HOMING) home_z_safely(); #else HOMEAXIS(Z); #endif #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) DEBUG_POS("> (home_all_axis || homeZ) > final", current_position); + if (DEBUGGING(LEVELING)) DEBUG_POS("> (home_all || homeZ) > final", current_position); #endif - } // home_all_axis || homeZ + } // home_all || homeZ #endif // Z_HOME_DIR < 0 SYNC_PLAN_POSITION_KINEMATIC(); @@ -3895,7 +3897,7 @@ inline void gcode_G28() { #endif } // G28 -void home_all_axes() { gcode_G28(); } +void home_all_axes() { gcode_G28(true); } #if HAS_PROBING_PROCEDURE @@ -9858,7 +9860,7 @@ void process_next_command() { #endif // NOZZLE_PARK_FEATURE case 28: // G28: Home all axes, one at a time - gcode_G28(); + gcode_G28(false); break; #if HAS_LEVELING From c2321b1cdd18710625316ad37e2bbc21ce1bfa8a Mon Sep 17 00:00:00 2001 From: fixoid Date: Fri, 12 May 2017 22:09:40 +0300 Subject: [PATCH 092/189] Separate SWITCHING_NOZZLE and SWITCHING_EXTRUDER --- Marlin/Conditionals_LCD.h | 42 +++++++++---------- Marlin/Conditionals_post.h | 2 +- Marlin/Configuration.h | 10 ++++- Marlin/Marlin_main.cpp | 32 +++++++++++--- Marlin/SanityCheck.h | 23 ++++++---- Marlin/configuration_store.cpp | 2 +- .../Cartesio/Configuration.h | 10 ++++- .../Felix/Configuration.h | 10 ++++- .../Felix/DUAL/Configuration.h | 10 ++++- .../FolgerTech-i3-2020/Configuration.h | 10 ++++- .../Hephestos/Configuration.h | 10 ++++- .../Hephestos_2/Configuration.h | 10 ++++- .../K8200/Configuration.h | 10 ++++- .../K8400/Configuration.h | 10 ++++- .../K8400/Dual-head/Configuration.h | 10 ++++- .../RepRapWorld/Megatronics/Configuration.h | 10 ++++- .../RigidBot/Configuration.h | 10 ++++- .../SCARA/Configuration.h | 10 ++++- .../TAZ4/Configuration.h | 10 ++++- .../TinyBoy2/Configuration.h | 10 ++++- .../WITBOX/Configuration.h | 10 ++++- .../adafruit/ST7565/Configuration.h | 10 ++++- .../FLSUN/auto_calibrate/Configuration.h | 10 ++++- .../delta/FLSUN/kossel_mini/Configuration.h | 10 ++++- .../delta/generic/Configuration.h | 10 ++++- .../delta/kossel_mini/Configuration.h | 10 ++++- .../delta/kossel_pro/Configuration.h | 10 ++++- .../delta/kossel_xl/Configuration.h | 10 ++++- .../gCreate_gMax1.5+/Configuration.h | 10 ++++- .../makibox/Configuration.h | 10 ++++- .../tvrrug/Round2/Configuration.h | 10 ++++- .../wt150/Configuration.h | 10 ++++- README.md | 2 +- 33 files changed, 280 insertions(+), 93 deletions(-) diff --git a/Marlin/Conditionals_LCD.h b/Marlin/Conditionals_LCD.h index 19c7f8109..3c775a115 100644 --- a/Marlin/Conditionals_LCD.h +++ b/Marlin/Conditionals_LCD.h @@ -291,36 +291,34 @@ * TOOL_E_INDEX - Index to use when getting/setting the tool state * */ - #if ENABLED(SINGLENOZZLE) // One hotend, multi-extruder - #define HOTENDS 1 - #define E_STEPPERS EXTRUDERS - #define E_MANUAL EXTRUDERS - #define TOOL_E_INDEX current_block->active_extruder + #if ENABLED(SINGLENOZZLE) || ENABLED(MIXING_EXTRUDER) // One hotend, one thermistor, no XY offset + #define HOTENDS 1 #undef TEMP_SENSOR_1_AS_REDUNDANT #undef HOTEND_OFFSET_X #undef HOTEND_OFFSET_Y - #elif ENABLED(SWITCHING_EXTRUDER) // One E stepper, unified E axis, two hotends - #define HOTENDS EXTRUDERS - #define E_STEPPERS 1 - #define E_MANUAL 1 - #define TOOL_E_INDEX 0 - #ifndef HOTEND_OFFSET_Z + #else // Two hotends + #define HOTENDS EXTRUDERS + #if ENABLED(SWITCHING_NOZZLE) && !defined(HOTEND_OFFSET_Z) #define HOTEND_OFFSET_Z { 0 } #endif - #elif ENABLED(MIXING_EXTRUDER) // Multi-stepper, unified E axis, one hotend - #define HOTENDS 1 - #define E_STEPPERS MIXING_STEPPERS - #define E_MANUAL 1 - #define TOOL_E_INDEX 0 - #else // One stepper, E axis, and hotend per tool - #define HOTENDS EXTRUDERS - #define E_STEPPERS EXTRUDERS - #define E_MANUAL EXTRUDERS - #define TOOL_E_INDEX current_block->active_extruder + #endif + + #if ENABLED(SWITCHING_EXTRUDER) || ENABLED(MIXING_EXTRUDER) // Unified E axis + #if ENABLED(MIXING_EXTRUDER) + #define E_STEPPERS MIXING_STEPPERS + #else + #define E_STEPPERS 1 // One E stepper + #endif + #define E_MANUAL 1 + #define TOOL_E_INDEX 0 + #else + #define E_STEPPERS EXTRUDERS + #define E_MANUAL EXTRUDERS + #define TOOL_E_INDEX current_block->active_extruder #endif /** - * Distinct E Factors – Disable by commenting out DISTINCT_E_FACTORS + * DISTINCT_E_FACTORS affects how some E factors are accessed */ #if ENABLED(DISTINCT_E_FACTORS) && E_STEPPERS > 1 #define XYZE_N (XYZ + E_STEPPERS) diff --git a/Marlin/Conditionals_post.h b/Marlin/Conditionals_post.h index 5c34ac48b..7cf32396b 100644 --- a/Marlin/Conditionals_post.h +++ b/Marlin/Conditionals_post.h @@ -326,7 +326,7 @@ #ifndef HOTEND_OFFSET_Y #define HOTEND_OFFSET_Y { 0 } // Y offsets for each extruder #endif - #if !defined(HOTEND_OFFSET_Z) && (ENABLED(DUAL_X_CARRIAGE) || ENABLED(SWITCHING_EXTRUDER)) + #if !defined(HOTEND_OFFSET_Z) && (ENABLED(DUAL_X_CARRIAGE) || ENABLED(SWITCHING_NOZZLE)) #define HOTEND_OFFSET_Z { 0 } #endif #endif diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 10aeda5e8..774178f3d 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -137,12 +137,18 @@ //#define SINGLENOZZLE // A dual extruder that uses a single stepper motor -// Don't forget to set SSDE_SERVO_ANGLES and HOTEND_OFFSET_X/Y/Z //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 - //#define HOTEND_OFFSET_Z {0.0, 0.0} +#endif + +// A dual-nozzle that uses a servomotor to raise/lower one of the nozzles +//#define SWITCHING_NOZZLE +#if ENABLED(SWITCHING_NOZZLE) + #define SWITCHING_NOZZLE_SERVO_NR 0 + #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif /** diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index d59143d19..e6ce386ef 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -7762,7 +7762,7 @@ inline void gcode_M211() { * T * X * Y - * Z - Available with DUAL_X_CARRIAGE and SWITCHING_EXTRUDER + * Z - Available with DUAL_X_CARRIAGE and SWITCHING_NOZZLE */ inline void gcode_M218() { if (get_target_extruder_from_command(218) || target_extruder == 0) return; @@ -7770,7 +7770,7 @@ inline void gcode_M211() { if (code_seen('X')) hotend_offset[X_AXIS][target_extruder] = code_value_linear_units(); if (code_seen('Y')) hotend_offset[Y_AXIS][target_extruder] = code_value_linear_units(); - #if ENABLED(DUAL_X_CARRIAGE) || ENABLED(SWITCHING_EXTRUDER) + #if ENABLED(DUAL_X_CARRIAGE) || ENABLED(SWITCHING_NOZZLE) if (code_seen('Z')) hotend_offset[Z_AXIS][target_extruder] = code_value_linear_units(); #endif @@ -7781,7 +7781,7 @@ inline void gcode_M211() { SERIAL_ECHO(hotend_offset[X_AXIS][e]); SERIAL_CHAR(','); SERIAL_ECHO(hotend_offset[Y_AXIS][e]); - #if ENABLED(DUAL_X_CARRIAGE) || ENABLED(SWITCHING_EXTRUDER) + #if ENABLED(DUAL_X_CARRIAGE) || ENABLED(SWITCHING_NOZZLE) SERIAL_CHAR(','); SERIAL_ECHO(hotend_offset[Z_AXIS][e]); #endif @@ -9364,6 +9364,14 @@ inline void gcode_M999() { } #endif +#if ENABLED(SWITCHING_NOZZLE) + inline void move_nozzle_servo(uint8_t e) { + const int angles[2] = SWITCHING_NOZZLE_SERVO_ANGLES; + MOVE_SERVO(SWITCHING_NOZZLE_SERVO_NR, angles[e]); + safe_delay(500); + } +#endif + inline void invalid_extruder_error(const uint8_t &e) { SERIAL_ECHO_START; SERIAL_CHAR('T'); @@ -9511,7 +9519,7 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool n // No extra case for HAS_ABL in DUAL_X_CARRIAGE. Does that mean they don't work together? #else // !DUAL_X_CARRIAGE - #if ENABLED(SWITCHING_EXTRUDER) + #if ENABLED(SWITCHING_NOZZLE) // <0 if the new nozzle is higher, >0 if lower. A bigger raise when lower. const float z_diff = hotend_offset[Z_AXIS][active_extruder] - hotend_offset[Z_AXIS][tmp_extruder], z_raise = 0.3 + (z_diff > 0.0 ? z_diff : 0.0); @@ -9521,7 +9529,14 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool n planner.buffer_line_kinematic(current_position, planner.max_feedrate_mm_s[Z_AXIS], active_extruder); stepper.synchronize(); - move_extruder_servo(active_extruder); + move_nozzle_servo(active_extruder); + #endif + + #if ENABLED(SWITCHING_EXTRUDER) + #if !(ENABLED(SWITCHING_NOZZLE) && (SWITCHING_EXTRUDER_SERVO_NR == SWITCHING_NOZZLE_SERVO_NR)) + stepper.synchronize(); + move_extruder_servo(active_extruder); + #endif #endif /** @@ -9644,7 +9659,7 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool n prepare_move_to_destination(); } - #if ENABLED(SWITCHING_EXTRUDER) + #if ENABLED(SWITCHING_NOZZLE) // Move back down, if needed. (Including when the new tool is higher.) if (z_raise != z_diff) { destination[Z_AXIS] += z_diff; @@ -9672,6 +9687,11 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool n UNUSED(fr_mm_s); UNUSED(no_move); + #if ENABLED(SWITCHING_EXTRUDER) + stepper.synchronize(); + move_extruder_servo(active_extruder); + #endif + #endif // HOTENDS <= 1 SERIAL_ECHO_START; diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index 3aa307298..4d3b680fb 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -329,11 +329,16 @@ #endif /** - * Only one type of extruder allowed + * A dual nozzle x-carriage with switching servo */ -#if (ENABLED(SWITCHING_EXTRUDER) && (ENABLED(SINGLENOZZLE) || ENABLED(MIXING_EXTRUDER))) \ - || (ENABLED(SINGLENOZZLE) && ENABLED(MIXING_EXTRUDER)) - #error "Please define only one type of extruder: SINGLENOZZLE, SWITCHING_EXTRUDER, or MIXING_EXTRUDER." +#if ENABLED(SWITCHING_NOZZLE) + #if ENABLED(SINGLENOZZLE) + #error "SWITCHING_NOZZLE and SINGLENOZZLE are incompatible." + #elif EXTRUDERS < 2 + #error "SWITCHING_NOZZLE requires exactly 2 EXTRUDERS." + #elif NUM_SERVOS < 1 + #error "SWITCHING_NOZZLE requires NUM_SERVOS >= 1." + #endif #endif /** @@ -355,12 +360,14 @@ #if ENABLED(MIXING_EXTRUDER) #if EXTRUDERS > 1 #error "MIXING_EXTRUDER currently only supports one extruder." - #endif - #if MIXING_STEPPERS < 2 + #elif MIXING_STEPPERS < 2 #error "You must set MIXING_STEPPERS >= 2 for a mixing extruder." - #endif - #if ENABLED(FILAMENT_SENSOR) + #elif ENABLED(FILAMENT_SENSOR) #error "MIXING_EXTRUDER is incompatible with FILAMENT_SENSOR. Comment out this line to use it anyway." + #elif ENABLED(SWITCHING_EXTRUDER) + #error "Please select either MIXING_EXTRUDER or SWITCHING_EXTRUDER, not both." + #elif ENABLED(SINGLENOZZLE) + #error "MIXING_EXTRUDER is incompatible with SINGLENOZZLE." #endif #endif diff --git a/Marlin/configuration_store.cpp b/Marlin/configuration_store.cpp index a4d1ed279..5f063d8c0 100644 --- a/Marlin/configuration_store.cpp +++ b/Marlin/configuration_store.cpp @@ -1415,7 +1415,7 @@ void MarlinSettings::reset() { SERIAL_ECHOPAIR(" M218 T", (int)e); SERIAL_ECHOPAIR(" X", LINEAR_UNIT(hotend_offset[X_AXIS][e])); SERIAL_ECHOPAIR(" Y", LINEAR_UNIT(hotend_offset[Y_AXIS][e])); - #if ENABLED(DUAL_X_CARRIAGE) || ENABLED(SWITCHING_EXTRUDER) + #if ENABLED(DUAL_X_CARRIAGE) || ENABLED(SWITCHING_NOZZLE) SERIAL_ECHOPAIR(" Z", LINEAR_UNIT(hotend_offset[Z_AXIS][e])); #endif SERIAL_EOL; diff --git a/Marlin/example_configurations/Cartesio/Configuration.h b/Marlin/example_configurations/Cartesio/Configuration.h index 39f857d9c..0717c4c71 100644 --- a/Marlin/example_configurations/Cartesio/Configuration.h +++ b/Marlin/example_configurations/Cartesio/Configuration.h @@ -138,12 +138,18 @@ //#define SINGLENOZZLE // A dual extruder that uses a single stepper motor -// Don't forget to set SSDE_SERVO_ANGLES and HOTEND_OFFSET_X/Y/Z //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 - //#define HOTEND_OFFSET_Z {0.0, 0.0} +#endif + +// A dual-nozzle that uses a servomotor to raise/lower one of the nozzles +//#define SWITCHING_NOZZLE +#if ENABLED(SWITCHING_NOZZLE) + #define SWITCHING_NOZZLE_SERVO_NR 0 + #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif /** diff --git a/Marlin/example_configurations/Felix/Configuration.h b/Marlin/example_configurations/Felix/Configuration.h index bb74b12d1..aa49cf980 100644 --- a/Marlin/example_configurations/Felix/Configuration.h +++ b/Marlin/example_configurations/Felix/Configuration.h @@ -137,12 +137,18 @@ //#define SINGLENOZZLE // A dual extruder that uses a single stepper motor -// Don't forget to set SSDE_SERVO_ANGLES and HOTEND_OFFSET_X/Y/Z //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 - //#define HOTEND_OFFSET_Z {0.0, 0.0} +#endif + +// A dual-nozzle that uses a servomotor to raise/lower one of the nozzles +//#define SWITCHING_NOZZLE +#if ENABLED(SWITCHING_NOZZLE) + #define SWITCHING_NOZZLE_SERVO_NR 0 + #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif /** diff --git a/Marlin/example_configurations/Felix/DUAL/Configuration.h b/Marlin/example_configurations/Felix/DUAL/Configuration.h index 14fc25e83..521374bf1 100644 --- a/Marlin/example_configurations/Felix/DUAL/Configuration.h +++ b/Marlin/example_configurations/Felix/DUAL/Configuration.h @@ -137,12 +137,18 @@ //#define SINGLENOZZLE // A dual extruder that uses a single stepper motor -// Don't forget to set SSDE_SERVO_ANGLES and HOTEND_OFFSET_X/Y/Z //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 - //#define HOTEND_OFFSET_Z {0.0, 0.0} +#endif + +// A dual-nozzle that uses a servomotor to raise/lower one of the nozzles +//#define SWITCHING_NOZZLE +#if ENABLED(SWITCHING_NOZZLE) + #define SWITCHING_NOZZLE_SERVO_NR 0 + #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif /** diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h index 268afb71f..6bdc28dee 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h @@ -137,12 +137,18 @@ //#define SINGLENOZZLE // A dual extruder that uses a single stepper motor -// Don't forget to set SSDE_SERVO_ANGLES and HOTEND_OFFSET_X/Y/Z //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 - //#define HOTEND_OFFSET_Z {0.0, 0.0} +#endif + +// A dual-nozzle that uses a servomotor to raise/lower one of the nozzles +//#define SWITCHING_NOZZLE +#if ENABLED(SWITCHING_NOZZLE) + #define SWITCHING_NOZZLE_SERVO_NR 0 + #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif /** diff --git a/Marlin/example_configurations/Hephestos/Configuration.h b/Marlin/example_configurations/Hephestos/Configuration.h index 8c611552a..9db79cd5f 100644 --- a/Marlin/example_configurations/Hephestos/Configuration.h +++ b/Marlin/example_configurations/Hephestos/Configuration.h @@ -140,12 +140,18 @@ //#define SINGLENOZZLE // A dual extruder that uses a single stepper motor -// Don't forget to set SSDE_SERVO_ANGLES and HOTEND_OFFSET_X/Y/Z //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 - //#define HOTEND_OFFSET_Z {0.0, 0.0} +#endif + +// A dual-nozzle that uses a servomotor to raise/lower one of the nozzles +//#define SWITCHING_NOZZLE +#if ENABLED(SWITCHING_NOZZLE) + #define SWITCHING_NOZZLE_SERVO_NR 0 + #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif /** diff --git a/Marlin/example_configurations/Hephestos_2/Configuration.h b/Marlin/example_configurations/Hephestos_2/Configuration.h index 35f6aea29..8fbf2f8d6 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration.h @@ -137,12 +137,18 @@ //#define SINGLENOZZLE // A dual extruder that uses a single stepper motor -// Don't forget to set SSDE_SERVO_ANGLES and HOTEND_OFFSET_X/Y/Z //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 - //#define HOTEND_OFFSET_Z {0.0, 0.0} +#endif + +// A dual-nozzle that uses a servomotor to raise/lower one of the nozzles +//#define SWITCHING_NOZZLE +#if ENABLED(SWITCHING_NOZZLE) + #define SWITCHING_NOZZLE_SERVO_NR 0 + #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif /** diff --git a/Marlin/example_configurations/K8200/Configuration.h b/Marlin/example_configurations/K8200/Configuration.h index bd79a11a5..b999644c9 100644 --- a/Marlin/example_configurations/K8200/Configuration.h +++ b/Marlin/example_configurations/K8200/Configuration.h @@ -157,12 +157,18 @@ //#define SINGLENOZZLE // A dual extruder that uses a single stepper motor -// Don't forget to set SSDE_SERVO_ANGLES and HOTEND_OFFSET_X/Y/Z //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 - //#define HOTEND_OFFSET_Z {0.0, 0.0} +#endif + +// A dual-nozzle that uses a servomotor to raise/lower one of the nozzles +//#define SWITCHING_NOZZLE +#if ENABLED(SWITCHING_NOZZLE) + #define SWITCHING_NOZZLE_SERVO_NR 0 + #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif /** diff --git a/Marlin/example_configurations/K8400/Configuration.h b/Marlin/example_configurations/K8400/Configuration.h index 027ad29bc..e47c06ea0 100644 --- a/Marlin/example_configurations/K8400/Configuration.h +++ b/Marlin/example_configurations/K8400/Configuration.h @@ -137,12 +137,18 @@ //#define SINGLENOZZLE // A dual extruder that uses a single stepper motor -// Don't forget to set SSDE_SERVO_ANGLES and HOTEND_OFFSET_X/Y/Z //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 - //#define HOTEND_OFFSET_Z {0.0, 0.0} +#endif + +// A dual-nozzle that uses a servomotor to raise/lower one of the nozzles +//#define SWITCHING_NOZZLE +#if ENABLED(SWITCHING_NOZZLE) + #define SWITCHING_NOZZLE_SERVO_NR 0 + #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif /** diff --git a/Marlin/example_configurations/K8400/Dual-head/Configuration.h b/Marlin/example_configurations/K8400/Dual-head/Configuration.h index 2b7a0b3e3..4f7951064 100644 --- a/Marlin/example_configurations/K8400/Dual-head/Configuration.h +++ b/Marlin/example_configurations/K8400/Dual-head/Configuration.h @@ -137,12 +137,18 @@ //#define SINGLENOZZLE // A dual extruder that uses a single stepper motor -// Don't forget to set SSDE_SERVO_ANGLES and HOTEND_OFFSET_X/Y/Z //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 - //#define HOTEND_OFFSET_Z {0.0, 0.0} +#endif + +// A dual-nozzle that uses a servomotor to raise/lower one of the nozzles +//#define SWITCHING_NOZZLE +#if ENABLED(SWITCHING_NOZZLE) + #define SWITCHING_NOZZLE_SERVO_NR 0 + #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif /** diff --git a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h index fad021c52..e9c8c35b3 100644 --- a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h +++ b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h @@ -137,12 +137,18 @@ //#define SINGLENOZZLE // A dual extruder that uses a single stepper motor -// Don't forget to set SSDE_SERVO_ANGLES and HOTEND_OFFSET_X/Y/Z //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 - //#define HOTEND_OFFSET_Z {0.0, 0.0} +#endif + +// A dual-nozzle that uses a servomotor to raise/lower one of the nozzles +//#define SWITCHING_NOZZLE +#if ENABLED(SWITCHING_NOZZLE) + #define SWITCHING_NOZZLE_SERVO_NR 0 + #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif /** diff --git a/Marlin/example_configurations/RigidBot/Configuration.h b/Marlin/example_configurations/RigidBot/Configuration.h index b00a75d8e..ca717eebd 100644 --- a/Marlin/example_configurations/RigidBot/Configuration.h +++ b/Marlin/example_configurations/RigidBot/Configuration.h @@ -140,12 +140,18 @@ //#define SINGLENOZZLE // A dual extruder that uses a single stepper motor -// Don't forget to set SSDE_SERVO_ANGLES and HOTEND_OFFSET_X/Y/Z //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 - //#define HOTEND_OFFSET_Z {0.0, 0.0} +#endif + +// A dual-nozzle that uses a servomotor to raise/lower one of the nozzles +//#define SWITCHING_NOZZLE +#if ENABLED(SWITCHING_NOZZLE) + #define SWITCHING_NOZZLE_SERVO_NR 0 + #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif /** diff --git a/Marlin/example_configurations/SCARA/Configuration.h b/Marlin/example_configurations/SCARA/Configuration.h index d464efd3c..b0a96106c 100644 --- a/Marlin/example_configurations/SCARA/Configuration.h +++ b/Marlin/example_configurations/SCARA/Configuration.h @@ -170,12 +170,18 @@ //#define SINGLENOZZLE // A dual extruder that uses a single stepper motor -// Don't forget to set SSDE_SERVO_ANGLES and HOTEND_OFFSET_X/Y/Z //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 - //#define HOTEND_OFFSET_Z {0.0, 0.0} +#endif + +// A dual-nozzle that uses a servomotor to raise/lower one of the nozzles +//#define SWITCHING_NOZZLE +#if ENABLED(SWITCHING_NOZZLE) + #define SWITCHING_NOZZLE_SERVO_NR 0 + #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif /** diff --git a/Marlin/example_configurations/TAZ4/Configuration.h b/Marlin/example_configurations/TAZ4/Configuration.h index c31994a38..cf4b46a44 100644 --- a/Marlin/example_configurations/TAZ4/Configuration.h +++ b/Marlin/example_configurations/TAZ4/Configuration.h @@ -137,12 +137,18 @@ //#define SINGLENOZZLE // A dual extruder that uses a single stepper motor -// Don't forget to set SSDE_SERVO_ANGLES and HOTEND_OFFSET_X/Y/Z //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 - //#define HOTEND_OFFSET_Z {0.0, 0.0} +#endif + +// A dual-nozzle that uses a servomotor to raise/lower one of the nozzles +//#define SWITCHING_NOZZLE +#if ENABLED(SWITCHING_NOZZLE) + #define SWITCHING_NOZZLE_SERVO_NR 0 + #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif /** diff --git a/Marlin/example_configurations/TinyBoy2/Configuration.h b/Marlin/example_configurations/TinyBoy2/Configuration.h index 662bd133e..d92556dcc 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration.h @@ -159,12 +159,18 @@ //#define SINGLENOZZLE // A dual extruder that uses a single stepper motor -// Don't forget to set SSDE_SERVO_ANGLES and HOTEND_OFFSET_X/Y/Z //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 - //#define HOTEND_OFFSET_Z {0.0, 0.0} +#endif + +// A dual-nozzle that uses a servomotor to raise/lower one of the nozzles +//#define SWITCHING_NOZZLE +#if ENABLED(SWITCHING_NOZZLE) + #define SWITCHING_NOZZLE_SERVO_NR 0 + #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif /** diff --git a/Marlin/example_configurations/WITBOX/Configuration.h b/Marlin/example_configurations/WITBOX/Configuration.h index 25ec69ac6..073dafe00 100644 --- a/Marlin/example_configurations/WITBOX/Configuration.h +++ b/Marlin/example_configurations/WITBOX/Configuration.h @@ -140,12 +140,18 @@ //#define SINGLENOZZLE // A dual extruder that uses a single stepper motor -// Don't forget to set SSDE_SERVO_ANGLES and HOTEND_OFFSET_X/Y/Z //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 - //#define HOTEND_OFFSET_Z {0.0, 0.0} +#endif + +// A dual-nozzle that uses a servomotor to raise/lower one of the nozzles +//#define SWITCHING_NOZZLE +#if ENABLED(SWITCHING_NOZZLE) + #define SWITCHING_NOZZLE_SERVO_NR 0 + #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif /** diff --git a/Marlin/example_configurations/adafruit/ST7565/Configuration.h b/Marlin/example_configurations/adafruit/ST7565/Configuration.h index f95dfcc9c..d9bbb2b25 100644 --- a/Marlin/example_configurations/adafruit/ST7565/Configuration.h +++ b/Marlin/example_configurations/adafruit/ST7565/Configuration.h @@ -137,12 +137,18 @@ //#define SINGLENOZZLE // A dual extruder that uses a single stepper motor -// Don't forget to set SSDE_SERVO_ANGLES and HOTEND_OFFSET_X/Y/Z //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 - //#define HOTEND_OFFSET_Z {0.0, 0.0} +#endif + +// A dual-nozzle that uses a servomotor to raise/lower one of the nozzles +//#define SWITCHING_NOZZLE +#if ENABLED(SWITCHING_NOZZLE) + #define SWITCHING_NOZZLE_SERVO_NR 0 + #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif /** diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h index c92671783..1e94e31b4 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h @@ -137,12 +137,18 @@ //#define SINGLENOZZLE // A dual extruder that uses a single stepper motor -// Don't forget to set SSDE_SERVO_ANGLES and HOTEND_OFFSET_X/Y/Z //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 - //#define HOTEND_OFFSET_Z {0.0, 0.0} +#endif + +// A dual-nozzle that uses a servomotor to raise/lower one of the nozzles +//#define SWITCHING_NOZZLE +#if ENABLED(SWITCHING_NOZZLE) + #define SWITCHING_NOZZLE_SERVO_NR 0 + #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif /** diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h index 22e338003..8ec27db5b 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h @@ -137,12 +137,18 @@ //#define SINGLENOZZLE // A dual extruder that uses a single stepper motor -// Don't forget to set SSDE_SERVO_ANGLES and HOTEND_OFFSET_X/Y/Z //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 - //#define HOTEND_OFFSET_Z {0.0, 0.0} +#endif + +// A dual-nozzle that uses a servomotor to raise/lower one of the nozzles +//#define SWITCHING_NOZZLE +#if ENABLED(SWITCHING_NOZZLE) + #define SWITCHING_NOZZLE_SERVO_NR 0 + #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif /** diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index 9b810fcf3..83776fa7f 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -137,12 +137,18 @@ //#define SINGLENOZZLE // A dual extruder that uses a single stepper motor -// Don't forget to set SSDE_SERVO_ANGLES and HOTEND_OFFSET_X/Y/Z //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 - //#define HOTEND_OFFSET_Z {0.0, 0.0} +#endif + +// A dual-nozzle that uses a servomotor to raise/lower one of the nozzles +//#define SWITCHING_NOZZLE +#if ENABLED(SWITCHING_NOZZLE) + #define SWITCHING_NOZZLE_SERVO_NR 0 + #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif /** diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index 8db5f7c35..b8e7fc5ff 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -137,12 +137,18 @@ //#define SINGLENOZZLE // A dual extruder that uses a single stepper motor -// Don't forget to set SSDE_SERVO_ANGLES and HOTEND_OFFSET_X/Y/Z //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 - //#define HOTEND_OFFSET_Z {0.0, 0.0} +#endif + +// A dual-nozzle that uses a servomotor to raise/lower one of the nozzles +//#define SWITCHING_NOZZLE +#if ENABLED(SWITCHING_NOZZLE) + #define SWITCHING_NOZZLE_SERVO_NR 0 + #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif /** diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration.h b/Marlin/example_configurations/delta/kossel_pro/Configuration.h index 2eb723ff3..3e6020195 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration.h @@ -141,12 +141,18 @@ //#define SINGLENOZZLE // A dual extruder that uses a single stepper motor -// Don't forget to set SSDE_SERVO_ANGLES and HOTEND_OFFSET_X/Y/Z //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 - //#define HOTEND_OFFSET_Z {0.0, 0.0} +#endif + +// A dual-nozzle that uses a servomotor to raise/lower one of the nozzles +//#define SWITCHING_NOZZLE +#if ENABLED(SWITCHING_NOZZLE) + #define SWITCHING_NOZZLE_SERVO_NR 0 + #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif /** diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration.h b/Marlin/example_configurations/delta/kossel_xl/Configuration.h index a6d08014b..4ecc7be43 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration.h @@ -137,12 +137,18 @@ //#define SINGLENOZZLE // A dual extruder that uses a single stepper motor -// Don't forget to set SSDE_SERVO_ANGLES and HOTEND_OFFSET_X/Y/Z //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 - //#define HOTEND_OFFSET_Z {0.0, 0.0} +#endif + +// A dual-nozzle that uses a servomotor to raise/lower one of the nozzles +//#define SWITCHING_NOZZLE +#if ENABLED(SWITCHING_NOZZLE) + #define SWITCHING_NOZZLE_SERVO_NR 0 + #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif /** diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h index 1e172d5f9..627130230 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h @@ -142,12 +142,18 @@ //#define SINGLENOZZLE // A dual extruder that uses a single stepper motor -// Don't forget to set SSDE_SERVO_ANGLES and HOTEND_OFFSET_X/Y/Z //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 - //#define HOTEND_OFFSET_Z {0.0, 0.0} +#endif + +// A dual-nozzle that uses a servomotor to raise/lower one of the nozzles +//#define SWITCHING_NOZZLE +#if ENABLED(SWITCHING_NOZZLE) + #define SWITCHING_NOZZLE_SERVO_NR 0 + #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif /** diff --git a/Marlin/example_configurations/makibox/Configuration.h b/Marlin/example_configurations/makibox/Configuration.h index ea04d6101..13f4aa287 100644 --- a/Marlin/example_configurations/makibox/Configuration.h +++ b/Marlin/example_configurations/makibox/Configuration.h @@ -137,12 +137,18 @@ //#define SINGLENOZZLE // A dual extruder that uses a single stepper motor -// Don't forget to set SSDE_SERVO_ANGLES and HOTEND_OFFSET_X/Y/Z //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 - //#define HOTEND_OFFSET_Z {0.0, 0.0} +#endif + +// A dual-nozzle that uses a servomotor to raise/lower one of the nozzles +//#define SWITCHING_NOZZLE +#if ENABLED(SWITCHING_NOZZLE) + #define SWITCHING_NOZZLE_SERVO_NR 0 + #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif /** diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration.h b/Marlin/example_configurations/tvrrug/Round2/Configuration.h index ecbca415f..9701dd114 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration.h @@ -137,12 +137,18 @@ //#define SINGLENOZZLE // A dual extruder that uses a single stepper motor -// Don't forget to set SSDE_SERVO_ANGLES and HOTEND_OFFSET_X/Y/Z //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 - //#define HOTEND_OFFSET_Z {0.0, 0.0} +#endif + +// A dual-nozzle that uses a servomotor to raise/lower one of the nozzles +//#define SWITCHING_NOZZLE +#if ENABLED(SWITCHING_NOZZLE) + #define SWITCHING_NOZZLE_SERVO_NR 0 + #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif /** diff --git a/Marlin/example_configurations/wt150/Configuration.h b/Marlin/example_configurations/wt150/Configuration.h index 5d221d701..b3b334f24 100644 --- a/Marlin/example_configurations/wt150/Configuration.h +++ b/Marlin/example_configurations/wt150/Configuration.h @@ -137,12 +137,18 @@ //#define SINGLENOZZLE // A dual extruder that uses a single stepper motor -// Don't forget to set SSDE_SERVO_ANGLES and HOTEND_OFFSET_X/Y/Z //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 - //#define HOTEND_OFFSET_Z {0.0, 0.0} +#endif + +// A dual-nozzle that uses a servomotor to raise/lower one of the nozzles +//#define SWITCHING_NOZZLE +#if ENABLED(SWITCHING_NOZZLE) + #define SWITCHING_NOZZLE_SERVO_NR 0 + #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif /** diff --git a/README.md b/README.md index 730a0bdd6..c253011d4 100644 --- a/README.md +++ b/README.md @@ -62,7 +62,7 @@ Download earlier versions of Marlin on the [Releases page](https://github.com/Ma - Improve thermal management, add `WATCH_BED_TEMP_PERIOD` - Better handling of toolchange, multiple tools - Add support for two X steppers `X_DUAL_STEPPER_DRIVERS` - - Add support for `SINGLENOZZLE`, `MIXING_EXTRUDER`, and `SWITCHING_EXTRUDER` + - Add support for `SINGLENOZZLE`, `MIXING_EXTRUDER`, `SWITCHING_NOZZLE`, and `SWITCHING_EXTRUDER` - Simplified probe configuration, allow usage without bed leveling - And much more… See the [1.1.0-RC7 Change Log](https://github.com/MarlinFirmware/Marlin/releases/tag/1.1.0-RC7) for the complete list of changes. From 13a06711ad31c51032f1edf059365b7eec6a95de Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 16 May 2017 04:09:34 -0500 Subject: [PATCH 093/189] Add a Travis test for UBL + DELTA --- .travis.yml | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/.travis.yml b/.travis.yml index e29f7f6d7..20a507510 100644 --- a/.travis.yml +++ b/.travis.yml @@ -375,17 +375,17 @@ script: - use_example_configs Hephestos_2 - build_marlin # - # Delta Config (generic) + # Delta Config (generic) + ABL bilinear + PROBE_MANUALLY - restore_configs - use_example_configs delta/generic - - opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER DELTA_CALIBRATION_MENU + - opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER DELTA_CALIBRATION_MENU AUTO_BED_LEVELING_BILINEAR PROBE_MANUALLY - build_marlin # - # Delta Config (generic) + ABL + ALLEN_KEY + # Delta Config (generic) + UBL + ALLEN_KEY + OLED_PANEL_TINYBOY2 + EEPROM_SETTINGS # - use_example_configs delta/generic - opt_disable DISABLE_MIN_ENDSTOPS - - opt_enable AUTO_BED_LEVELING_BILINEAR Z_PROBE_ALLEN_KEY + - opt_enable AUTO_BED_LEVELING_UBL Z_PROBE_ALLEN_KEY EEPROM_SETTINGS EEPROM_CHITCHAT OLED_PANEL_TINYBOY2 - build_marlin # # Delta Config (FLSUN AC because it's complex) From 00d358d92dd9164eb9dc25d6b950d391fb9ac95a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 16 May 2017 04:24:22 -0500 Subject: [PATCH 094/189] Fix a PROBE_MANUALLY bug in ultralcd.cpp --- Marlin/ultralcd.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 0c2117912..6b3784bac 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -1425,10 +1425,6 @@ void kill_screen(const char* lcd_msg) { static uint8_t manual_probe_index; - #if ENABLED(PROBE_MANUALLY) - extern bool g29_in_progress; - #endif - // LCD probed points are from defaults constexpr uint8_t total_probe_points = ( #if ENABLED(AUTO_BED_LEVELING_3POINT) @@ -1645,6 +1641,10 @@ void kill_screen(const char* lcd_msg) { #if ENABLED(LCD_BED_LEVELING) || HAS_ABL + #if ENABLED(PROBE_MANUALLY) + extern bool g29_in_progress; + #endif + /** * Step 2: Continue Bed Leveling... */ From 785236998788f9573668b1c58fbd6ff15fb24cae Mon Sep 17 00:00:00 2001 From: Brian Date: Sat, 6 May 2017 21:00:56 -0400 Subject: [PATCH 095/189] Implement CRC16, develop mesh allocation table - Add crc16 utility function - Implement CRC16 for config store, remove old checksum, increment layout version - Move UBL mesh store/load to MarlinSettings; increment UBL_VERSION - Begin to lay out MAT structure, prototype functions, etc. - Rename ubl.state.eeprom_storage_slot to .storage_slot - Misc. optimization - Cleanup/standardize/improve some messages This is a work in progress! --- Marlin/Marlin_main.cpp | 21 ++-- Marlin/configuration_store.cpp | 214 ++++++++++++++++++++++++--------- Marlin/configuration_store.h | 28 ++++- Marlin/ubl.cpp | 54 +-------- Marlin/ubl.h | 14 +-- Marlin/ubl_G29.cpp | 145 ++++++++++++---------- Marlin/utility.cpp | 13 ++ Marlin/utility.h | 4 + 8 files changed, 299 insertions(+), 194 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index e6ce386ef..0d7e24929 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -8341,15 +8341,22 @@ void quickstop_stepper() { #if ENABLED(AUTO_BED_LEVELING_UBL) // L to load a mesh from the EEPROM if (code_seen('L')) { - const int8_t storage_slot = code_has_value() ? code_value_int() : ubl.state.eeprom_storage_slot; - const int16_t j = (UBL_LAST_EEPROM_INDEX - ubl.eeprom_start) / sizeof(ubl.z_values); - if (!WITHIN(storage_slot, 0, j - 1) || ubl.eeprom_start <= 0) { - SERIAL_PROTOCOLLNPGM("?EEPROM storage not available for use.\n"); + const int8_t storage_slot = code_has_value() ? code_value_int() : ubl.state.storage_slot; + const int16_t a = settings.calc_num_meshes(); + + if (!a) { + SERIAL_PROTOCOLLNPGM("?EEPROM storage not available."); + return; + } + + if (!WITHIN(storage_slot, 0, a - 1)) { + SERIAL_PROTOCOLLNPGM("?Invalid storage slot."); + SERIAL_PROTOCOLLNPAIR("?Use 0 to ", a - 1); return; } - ubl.load_mesh(storage_slot); - ubl.state.eeprom_storage_slot = storage_slot; + settings.load_mesh(storage_slot); + ubl.state.storage_slot = storage_slot; } #endif // AUTO_BED_LEVELING_UBL @@ -8377,7 +8384,7 @@ void quickstop_stepper() { if (code_seen('L') || code_seen('V')) { ubl.display_map(0); // Currently only supports one map type SERIAL_ECHOLNPAIR("UBL_MESH_VALID = ", UBL_MESH_VALID); - SERIAL_ECHOLNPAIR("eeprom_storage_slot = ", ubl.state.eeprom_storage_slot); + SERIAL_ECHOLNPAIR("ubl.state.storage_slot = ", ubl.state.storage_slot); } #endif diff --git a/Marlin/configuration_store.cpp b/Marlin/configuration_store.cpp index 5f063d8c0..6ca18b0d8 100644 --- a/Marlin/configuration_store.cpp +++ b/Marlin/configuration_store.cpp @@ -36,16 +36,16 @@ * */ -#define EEPROM_VERSION "V37" +#define EEPROM_VERSION "V38" // Change EEPROM version if these are changed: #define EEPROM_OFFSET 100 /** - * V37 EEPROM Layout: + * V38 EEPROM Layout: * * 100 Version (char x4) - * 104 EEPROM Checksum (uint16_t) + * 104 EEPROM CRC16 (uint16_t) * * 106 E_STEPPERS (uint8_t) * 107 M92 XYZE planner.axis_steps_per_mm (float x4 ... x8) @@ -90,7 +90,7 @@ * AUTO_BED_LEVELING_UBL: 6 bytes * 324 G29 A ubl.state.active (bool) * 325 G29 Z ubl.state.z_offset (float) - * 329 G29 S ubl.state.eeprom_storage_slot (int8_t) + * 329 G29 S ubl.state.storage_slot (int8_t) * * DELTA: 48 bytes * 348 M666 XYZ endstop_adj (float x3) @@ -158,6 +158,14 @@ * * 588 Minimum end-point * 1909 (588 + 36 + 9 + 288 + 988) Maximum end-point + * + * ======================================================================== + * meshes_begin (between max and min end-point, directly above) + * -- MESHES -- + * meshes_end + * -- MAT (Mesh Allocation Table) -- 128 bytes (placeholder size) + * mat_end = E2END (0xFFF) + * */ #include "configuration_store.h" @@ -230,18 +238,26 @@ void MarlinSettings::postprocess() { #if ENABLED(EEPROM_SETTINGS) + #define DUMMY_PID_VALUE 3000.0f + #define EEPROM_START() int eeprom_index = EEPROM_OFFSET + #define EEPROM_SKIP(VAR) eeprom_index += sizeof(VAR) + #define EEPROM_WRITE(VAR) write_data(eeprom_index, (uint8_t*)&VAR, sizeof(VAR), &working_crc) + #define EEPROM_READ(VAR) read_data(eeprom_index, (uint8_t*)&VAR, sizeof(VAR), &working_crc) + #define EEPROM_ASSERT(TST,ERR) if (!(TST)) do{ SERIAL_ERROR_START; SERIAL_ERRORLNPGM(ERR); eeprom_read_error = true; }while(0) + const char version[4] = EEPROM_VERSION; - uint16_t MarlinSettings::eeprom_checksum; + bool MarlinSettings::eeprom_error; - bool MarlinSettings::eeprom_write_error, - MarlinSettings::eeprom_read_error; + #if ENABLED(AUTO_BED_LEVELING_UBL) + int MarlinSettings::meshes_begin; + #endif - void MarlinSettings::write_data(int &pos, const uint8_t* value, uint16_t size) { - if (eeprom_write_error) return; + void MarlinSettings::write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc) { + if (eeprom_error) return; while (size--) { uint8_t * const p = (uint8_t * const)pos; - const uint8_t v = *value; + uint8_t v = *value; // EEPROM has only ~100,000 write cycles, // so only write bytes that have changed! if (v != eeprom_read_byte(p)) { @@ -249,32 +265,27 @@ void MarlinSettings::postprocess() { if (eeprom_read_byte(p) != v) { SERIAL_ECHO_START; SERIAL_ECHOLNPGM(MSG_ERR_EEPROM_WRITE); - eeprom_write_error = true; + eeprom_error = true; return; } } - eeprom_checksum += v; + crc16(crc, &v, 1); pos++; value++; }; } - void MarlinSettings::read_data(int &pos, uint8_t* value, uint16_t size) { + + void MarlinSettings::read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc) { + if (eeprom_error) return; do { uint8_t c = eeprom_read_byte((unsigned char*)pos); - if (!eeprom_read_error) *value = c; - eeprom_checksum += c; + *value = c; + crc16(crc, &c, 1); pos++; value++; } while (--size); } - #define DUMMY_PID_VALUE 3000.0f - #define EEPROM_START() int eeprom_index = EEPROM_OFFSET - #define EEPROM_SKIP(VAR) eeprom_index += sizeof(VAR) - #define EEPROM_WRITE(VAR) write_data(eeprom_index, (uint8_t*)&VAR, sizeof(VAR)) - #define EEPROM_READ(VAR) read_data(eeprom_index, (uint8_t*)&VAR, sizeof(VAR)) - #define EEPROM_ASSERT(TST,ERR) if (!(TST)) do{ SERIAL_ERROR_START; SERIAL_ERRORLNPGM(ERR); eeprom_read_error = true; }while(0) - /** * M500 - Store Configuration */ @@ -282,14 +293,16 @@ void MarlinSettings::postprocess() { float dummy = 0.0f; char ver[4] = "000"; + uint16_t working_crc = 0; + EEPROM_START(); - eeprom_write_error = false; + eeprom_error = false; EEPROM_WRITE(ver); // invalidate data first - EEPROM_SKIP(eeprom_checksum); // Skip the checksum slot + EEPROM_SKIP(working_crc); // Skip the checksum slot - eeprom_checksum = 0; // clear before first "real data" + working_crc = 0; // clear before first "real data" const uint8_t esteppers = COUNT(planner.axis_steps_per_mm) - XYZ; EEPROM_WRITE(esteppers); @@ -410,14 +423,14 @@ void MarlinSettings::postprocess() { #if ENABLED(AUTO_BED_LEVELING_UBL) EEPROM_WRITE(ubl.state.active); EEPROM_WRITE(ubl.state.z_offset); - EEPROM_WRITE(ubl.state.eeprom_storage_slot); + EEPROM_WRITE(ubl.state.storage_slot); #else const bool ubl_active = 0; dummy = 0.0f; - const int8_t eeprom_slot = -1; + const int8_t storage_slot = -1; EEPROM_WRITE(ubl_active); EEPROM_WRITE(dummy); - EEPROM_WRITE(eeprom_slot); + EEPROM_WRITE(storage_slot); #endif // AUTO_BED_LEVELING_UBL // 9 floats for DELTA / Z_DUAL_ENDSTOPS @@ -609,43 +622,42 @@ void MarlinSettings::postprocess() { EEPROM_WRITE(dummy); #endif - if (!eeprom_write_error) { - - const uint16_t final_checksum = eeprom_checksum, - eeprom_size = eeprom_index; + if (!eeprom_error) { + const int eeprom_size = eeprom_index; // Write the EEPROM header eeprom_index = EEPROM_OFFSET; EEPROM_WRITE(version); - EEPROM_WRITE(final_checksum); + EEPROM_WRITE(working_crc); // Report storage size SERIAL_ECHO_START; SERIAL_ECHOPAIR("Settings Stored (", eeprom_size - (EEPROM_OFFSET)); - SERIAL_ECHOLNPGM(" bytes)"); + SERIAL_ECHOPAIR(" bytes; crc ", working_crc); + SERIAL_ECHOLNPGM(")"); } #if ENABLED(UBL_SAVE_ACTIVE_ON_M500) - if (ubl.state.eeprom_storage_slot >= 0) - ubl.store_mesh(ubl.state.eeprom_storage_slot); + if (ubl.state.storage_slot >= 0) + store_mesh(ubl.state.storage_slot); #endif - return !eeprom_write_error; + return !eeprom_error; } /** * M501 - Retrieve Configuration */ bool MarlinSettings::load() { + uint16_t working_crc = 0; EEPROM_START(); - eeprom_read_error = false; // If set EEPROM_READ won't write into RAM char stored_ver[4]; EEPROM_READ(stored_ver); - uint16_t stored_checksum; - EEPROM_READ(stored_checksum); + uint16_t stored_crc; + EEPROM_READ(stored_crc); // Version has to match or defaults are used if (strncmp(version, stored_ver, 3) != 0) { @@ -662,7 +674,7 @@ void MarlinSettings::postprocess() { else { float dummy = 0; - eeprom_checksum = 0; // clear before reading first "real data" + working_crc = 0; //clear before reading first "real data" // Number of esteppers may change uint8_t esteppers; @@ -788,7 +800,7 @@ void MarlinSettings::postprocess() { #if ENABLED(AUTO_BED_LEVELING_UBL) EEPROM_READ(ubl.state.active); EEPROM_READ(ubl.state.z_offset); - EEPROM_READ(ubl.state.eeprom_storage_slot); + EEPROM_READ(ubl.state.storage_slot); #else bool dummyb; uint8_t dummyui8; @@ -960,27 +972,28 @@ void MarlinSettings::postprocess() { EEPROM_READ(dummy); #endif - if (eeprom_checksum == stored_checksum) { - if (eeprom_read_error) - reset(); - else { + if (working_crc == stored_crc) { postprocess(); SERIAL_ECHO_START; SERIAL_ECHO(version); SERIAL_ECHOPAIR(" stored settings retrieved (", eeprom_index - (EEPROM_OFFSET)); - SERIAL_ECHOLNPGM(" bytes)"); - } + SERIAL_ECHOPAIR(" bytes; crc ", working_crc); + SERIAL_ECHOLNPGM(")"); } else { SERIAL_ERROR_START; - SERIAL_ERRORLNPGM("EEPROM checksum mismatch"); + SERIAL_ERRORPGM("EEPROM checksum mismatch - (stored CRC)"); + SERIAL_ERROR(stored_crc); + SERIAL_ERRORPGM(" != "); + SERIAL_ERROR(working_crc); + SERIAL_ERRORLNPGM(" (calculated CRC)!"); reset(); } #if ENABLED(AUTO_BED_LEVELING_UBL) - ubl.eeprom_start = (eeprom_index + 32) & 0xFFF8; // Pad the end of configuration data so it - // can float up or down a little bit without - // disrupting the Unified Bed Leveling data + meshes_begin = (eeprom_index + 32) & 0xFFF8; // Pad the end of configuration data so it + // can float up or down a little bit without + // disrupting the mesh data SERIAL_ECHOPGM(" UBL "); if (!ubl.state.active) SERIAL_ECHO("not "); SERIAL_ECHOLNPGM("active!"); @@ -993,9 +1006,9 @@ void MarlinSettings::postprocess() { ubl.reset(); } - if (ubl.state.eeprom_storage_slot >= 0) { - ubl.load_mesh(ubl.state.eeprom_storage_slot); - SERIAL_ECHOPAIR("Mesh ", ubl.state.eeprom_storage_slot); + if (ubl.state.storage_slot >= 0) { + load_mesh(ubl.state.storage_slot); + SERIAL_ECHOPAIR("Mesh ", ubl.state.storage_slot); SERIAL_ECHOLNPGM(" loaded from storage."); } else { @@ -1009,9 +1022,85 @@ void MarlinSettings::postprocess() { report(); #endif - return !eeprom_read_error; + return !eeprom_error; } + + #if ENABLED(AUTO_BED_LEVELING_UBL) + + int MarlinSettings::calc_num_meshes() { + //obviously this will get more sophisticated once we've added an actual MAT + + if (meshes_begin <= 0) return 0; + + return (meshes_end - meshes_begin) / sizeof(ubl.z_values); + } + + void MarlinSettings::store_mesh(int8_t slot) { + + #if ENABLED(AUTO_BED_LEVELING_UBL) + const int a = calc_num_meshes(); + if (!WITHIN(slot, 0, a - 1)) { + SERIAL_PROTOCOLLNPGM("?Invalid slot."); + SERIAL_PROTOCOL(a); + SERIAL_PROTOCOLLNPGM(" mesh slots available."); + SERIAL_PROTOCOLLNPAIR("E2END : ", E2END); + SERIAL_PROTOCOLLNPAIR("meshes_end : ", (int)meshes_end); + SERIAL_PROTOCOLLNPAIR("slot : ", slot); + SERIAL_EOL; + return; + } + + uint16_t crc = 0; + int pos = meshes_end - (slot + 1) * sizeof(ubl.z_values); + + write_data(pos, (uint8_t *)&ubl.z_values, sizeof(ubl.z_values), &crc); + + // Write crc to MAT along with other data, or just tack on to the beginning or end + + SERIAL_PROTOCOLPAIR("Mesh saved in slot ", slot); + + #else + + // Other mesh types + + #endif + } + + void MarlinSettings::load_mesh(int8_t slot, void *into /* = 0 */) { + + #if ENABLED(AUTO_BED_LEVELING_UBL) + + const int16_t a = settings.calc_num_meshes(); + + if (!WITHIN(slot, 0, a - 1)) { + SERIAL_PROTOCOLLNPGM("?Invalid Slot."); + SERIAL_PROTOCOL(a); + SERIAL_PROTOCOLLNPGM(" mesh slots available."); + return; + } + + uint16_t crc = 0; + int pos = meshes_end - (slot + 1) * sizeof(ubl.z_values); + uint8_t * const dest = into ? (uint8_t*)into : (uint8_t*)&ubl.z_values; + read_data(pos, dest, sizeof(ubl.z_values), &crc); + + // Compare crc with crc from MAT, or read from end + + SERIAL_PROTOCOLPAIR("Mesh loaded from slot ", slot); + + #else + + // Other mesh types + + #endif + } + + //void MarlinSettings::delete_mesh() { return; } + //void MarlinSettings::defrag_meshes() { return; } + + #endif // AUTO_BED_LEVELING_UBL + #else // !EEPROM_SETTINGS bool MarlinSettings::save() { @@ -1458,7 +1547,18 @@ void MarlinSettings::reset() { #endif SERIAL_EOL; - if (!forReplay) ubl.g29_what_command(); + if (!forReplay) { + SERIAL_ECHOPGM("\nUBL is "); + ubl.state.active ? SERIAL_CHAR('A') : SERIAL_ECHOPGM("Ina"); + SERIAL_ECHOLNPAIR("ctive\n\nActive Mesh Slot: ", ubl.state.storage_slot); + + SERIAL_ECHOPGM("z_offset: "); + SERIAL_ECHO_F(ubl.state.z_offset, 6); + SERIAL_EOL; + + SERIAL_ECHOPAIR("EEPROM can hold ", calc_num_meshes()); + SERIAL_ECHOLNPGM(" meshes.\n"); + } #elif HAS_ABL diff --git a/Marlin/configuration_store.h b/Marlin/configuration_store.h index e31d20b5c..1166ed29e 100644 --- a/Marlin/configuration_store.h +++ b/Marlin/configuration_store.h @@ -34,6 +34,18 @@ class MarlinSettings { #if ENABLED(EEPROM_SETTINGS) static bool load(); + + #if ENABLED(AUTO_BED_LEVELING_UBL) // Eventually make these available if any leveling system + // That can store is enabled + FORCE_INLINE static int get_start_of_meshes() { return meshes_begin; } + FORCE_INLINE static int get_end_of_meshes() { return meshes_end; } + static int calc_num_meshes(); + static void store_mesh(int8_t slot); + static void load_mesh(int8_t slot, void *into = 0); + + //static void delete_mesh(); // necessary if we have a MAT + //static void defrag_meshes(); // " + #endif #else FORCE_INLINE static bool load() { reset(); report(); return true; } @@ -50,10 +62,18 @@ class MarlinSettings { static void postprocess(); #if ENABLED(EEPROM_SETTINGS) - static uint16_t eeprom_checksum; - static bool eeprom_read_error, eeprom_write_error; - static void write_data(int &pos, const uint8_t* value, uint16_t size); - static void read_data(int &pos, uint8_t* value, uint16_t size); + static bool eeprom_error; + + #if ENABLED(AUTO_BED_LEVELING_UBL) // Eventually make these available if any leveling system + // That can store is enabled + static int meshes_begin; + const static int mat_end = E2END; // Mesh allocation table; this may not end up being necessary + const static int meshes_end = mat_end - 128; // 128 is a placeholder for the size of the MAT + + #endif + + static void write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc); + static void read_data(int &pos, uint8_t *value, uint16_t size, uint16_t *crc); #endif }; diff --git a/Marlin/ubl.cpp b/Marlin/ubl.cpp index bff73b172..b4ee7d238 100644 --- a/Marlin/ubl.cpp +++ b/Marlin/ubl.cpp @@ -63,9 +63,6 @@ bool unified_bed_leveling::g26_debug_flag = false, unified_bed_leveling::has_control_of_lcd_panel = false; - int16_t unified_bed_leveling::eeprom_start = -1; // Please stop changing this to 8 bits in size - // It needs to hold values bigger than this. - volatile int unified_bed_leveling::encoder_diff; unified_bed_leveling::unified_bed_leveling() { @@ -73,53 +70,10 @@ reset(); } - void unified_bed_leveling::load_mesh(const int16_t slot) { - int16_t j = (UBL_LAST_EEPROM_INDEX - eeprom_start) / sizeof(z_values); - - if (slot == -1) { - SERIAL_PROTOCOLLNPGM("?No mesh saved in EEPROM. Zeroing mesh in memory.\n"); - reset(); - return; - } - - if (!WITHIN(slot, 0, j - 1) || eeprom_start <= 0) { - SERIAL_PROTOCOLLNPGM("?EEPROM storage not available to load mesh.\n"); - return; - } - - j = UBL_LAST_EEPROM_INDEX - (slot + 1) * sizeof(z_values); - eeprom_read_block((void *)&z_values, (void *)j, sizeof(z_values)); - - SERIAL_PROTOCOLPAIR("Mesh loaded from slot ", slot); - SERIAL_PROTOCOLLNPAIR(" at offset ", hex_address((void*)j)); - } - - void unified_bed_leveling::store_mesh(const int16_t slot) { - int16_t j = (UBL_LAST_EEPROM_INDEX - eeprom_start) / sizeof(z_values); - - if (!WITHIN(slot, 0, j - 1) || eeprom_start <= 0) { - SERIAL_PROTOCOLLNPGM("?EEPROM storage not available to load mesh.\n"); - SERIAL_PROTOCOL(slot); - SERIAL_PROTOCOLLNPGM(" mesh slots available.\n"); - SERIAL_PROTOCOLLNPAIR("E2END : ", E2END); - SERIAL_PROTOCOLLNPAIR("k : ", (int)UBL_LAST_EEPROM_INDEX); - SERIAL_PROTOCOLLNPAIR("j : ", j); - SERIAL_PROTOCOLLNPAIR("m : ", slot); - SERIAL_EOL; - return; - } - - j = UBL_LAST_EEPROM_INDEX - (slot + 1) * sizeof(z_values); - eeprom_write_block((const void *)&z_values, (void *)j, sizeof(z_values)); - - SERIAL_PROTOCOLPAIR("Mesh saved in slot ", slot); - SERIAL_PROTOCOLLNPAIR(" at offset ", hex_address((void*)j)); - } - void unified_bed_leveling::reset() { state.active = false; state.z_offset = 0; - state.eeprom_storage_slot = -1; + state.storage_slot = -1; ZERO(z_values); @@ -203,9 +157,9 @@ bool unified_bed_leveling::sanity_check() { uint8_t error_flag = 0; - const int j = (UBL_LAST_EEPROM_INDEX - eeprom_start) / sizeof(z_values); - if (j < 1) { - SERIAL_PROTOCOLLNPGM("?No EEPROM storage available for a mesh of this size.\n"); + const int a = settings.calc_num_meshes(); + if (a < 1) { + SERIAL_PROTOCOLLNPGM("?Insufficient EEPROM storage for a mesh of this size."); error_flag++; } diff --git a/Marlin/ubl.h b/Marlin/ubl.h index 93718d6c5..7ad191f6d 100644 --- a/Marlin/ubl.h +++ b/Marlin/ubl.h @@ -30,8 +30,9 @@ #include "planner.h" #include "math.h" #include "vector_3.h" + #include "configuration_store.h" - #define UBL_VERSION "1.00" + #define UBL_VERSION "1.01" #define UBL_OK false #define UBL_ERR true @@ -92,7 +93,7 @@ typedef struct { bool active = false; float z_offset = 0.0; - int8_t eeprom_storage_slot = -1; + int8_t storage_slot = -1; } ubl_state; class unified_bed_leveling { @@ -117,10 +118,6 @@ void display_map(const int); void reset(); void invalidate(); - void store_state(); - void load_state(); - void store_mesh(const int16_t); - void load_mesh(const int16_t); bool sanity_check(); static ubl_state state; @@ -153,9 +150,6 @@ static bool g26_debug_flag, has_control_of_lcd_panel; - static int16_t eeprom_start; // Please do no change this to 8 bits in size - // It needs to hold values bigger than this. - static volatile int encoder_diff; // Volatile because it's changed at interrupt time. unified_bed_leveling(); @@ -351,7 +345,5 @@ extern unified_bed_leveling ubl; - #define UBL_LAST_EEPROM_INDEX E2END - #endif // AUTO_BED_LEVELING_UBL #endif // UNIFIED_BED_LEVELING_H diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 065256c8d..493ee1d88 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -314,7 +314,7 @@ void __attribute__((optimize("O0"))) gcode_G29() { - if (ubl.eeprom_start < 0) { + if (!settings.calc_num_meshes()) { SERIAL_PROTOCOLLNPGM("?You need to enable your EEPROM and initialize it"); SERIAL_PROTOCOLLNPGM("with M502, M500, M501 in that order.\n"); return; @@ -419,9 +419,9 @@ } if (code_seen('P')) { - if (WITHIN(phase_value, 0, 1) && ubl.state.eeprom_storage_slot == -1) { - ubl.state.eeprom_storage_slot = 0; - SERIAL_PROTOCOLLNPGM("Default storage slot 0 selected.\n"); + if (WITHIN(phase_value, 0, 1) && ubl.state.storage_slot == -1) { + ubl.state.storage_slot = 0; + SERIAL_PROTOCOLLNPGM("Default storage slot 0 selected."); } switch (phase_value) { @@ -430,7 +430,7 @@ // Zero Mesh Data // ubl.reset(); - SERIAL_PROTOCOLLNPGM("Mesh zeroed.\n"); + SERIAL_PROTOCOLLNPGM("Mesh zeroed."); break; case 1: @@ -439,7 +439,7 @@ // if (!code_seen('C')) { ubl.invalidate(); - SERIAL_PROTOCOLLNPGM("Mesh invalidated. Probing mesh.\n"); + SERIAL_PROTOCOLLNPGM("Mesh invalidated. Probing mesh."); } if (g29_verbose_level > 1) { SERIAL_PROTOCOLPAIR("Probing Mesh Points Closest to (", x_pos); @@ -455,7 +455,7 @@ // // Manually Probe Mesh in areas that can't be reached by the probe // - SERIAL_PROTOCOLLNPGM("Manually probing unreachable mesh locations.\n"); + SERIAL_PROTOCOLLNPGM("Manually probing unreachable mesh locations."); do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); if (!x_flag && !y_flag) { /** @@ -485,7 +485,7 @@ card_thickness = code_has_value() ? code_value_float() : measure_business_card_thickness(height); if (fabs(card_thickness) > 1.5) { - SERIAL_PROTOCOLLNPGM("?Error in Business Card measurement.\n"); + SERIAL_PROTOCOLLNPGM("?Error in Business Card measurement."); return; } } @@ -561,17 +561,25 @@ // if (code_seen('L')) { // Load Current Mesh Data - storage_slot = code_has_value() ? code_value_int() : ubl.state.eeprom_storage_slot; + storage_slot = code_has_value() ? code_value_int() : ubl.state.storage_slot; - const int16_t j = (UBL_LAST_EEPROM_INDEX - ubl.eeprom_start) / sizeof(ubl.z_values); + int16_t a = settings.calc_num_meshes(); - if (!WITHIN(storage_slot, 0, j - 1) || ubl.eeprom_start <= 0) { - SERIAL_PROTOCOLLNPGM("?EEPROM storage not available for use.\n"); + if (!a) { + SERIAL_PROTOCOLLNPGM("?EEPROM storage not available."); return; } - ubl.load_mesh(storage_slot); - ubl.state.eeprom_storage_slot = storage_slot; - SERIAL_PROTOCOLLNPGM("Done.\n"); + + if (!WITHIN(storage_slot, 0, a - 1)) { + SERIAL_PROTOCOLLNPGM("?Invalid storage slot."); + SERIAL_PROTOCOLLNPAIR("?Use 0 to ", a - 1); + return; + } + + settings.load_mesh(storage_slot); + ubl.state.storage_slot = storage_slot; + + SERIAL_PROTOCOLLNPGM("Done."); } // @@ -579,7 +587,7 @@ // if (code_seen('S')) { // Store (or Save) Current Mesh Data - storage_slot = code_has_value() ? code_value_int() : ubl.state.eeprom_storage_slot; + storage_slot = code_has_value() ? code_value_int() : ubl.state.storage_slot; if (storage_slot == -1) { // Special case, we are going to 'Export' the mesh to the SERIAL_ECHOLNPGM("G29 I 999"); // host in a form it can be reconstructed on a different machine @@ -597,17 +605,23 @@ return; } - const int16_t j = (UBL_LAST_EEPROM_INDEX - ubl.eeprom_start) / sizeof(ubl.z_values); + int16_t a = settings.calc_num_meshes(); - if (!WITHIN(storage_slot, 0, j - 1) || ubl.eeprom_start <= 0) { - SERIAL_PROTOCOLLNPGM("?EEPROM storage not available for use.\n"); - SERIAL_PROTOCOLLNPAIR("?Use 0 to ", j - 1); + if (!a) { + SERIAL_PROTOCOLLNPGM("?EEPROM storage not available."); goto LEAVE; } - ubl.store_mesh(storage_slot); - ubl.state.eeprom_storage_slot = storage_slot; - SERIAL_PROTOCOLLNPGM("Done.\n"); + if (!WITHIN(storage_slot, 0, a - 1)) { + SERIAL_PROTOCOLLNPGM("?Invalid storage slot."); + SERIAL_PROTOCOLLNPAIR("?Use 0 to ", a - 1); + goto LEAVE; + } + + settings.store_mesh(storage_slot); + ubl.state.storage_slot = storage_slot; + + SERIAL_PROTOCOLLNPGM("Done."); } if (code_seen('T')) @@ -1157,8 +1171,6 @@ * good to have the extra information. Soon... we prune this to just a few items */ void unified_bed_leveling::g29_what_command() { - const uint16_t k = E2END - ubl.eeprom_start; - say_ubl_name(); SERIAL_PROTOCOLPGM("System Version " UBL_VERSION " "); if (state.active) @@ -1168,10 +1180,10 @@ SERIAL_PROTOCOLLNPGM("ctive.\n"); safe_delay(50); - if (state.eeprom_storage_slot == -1) + if (state.storage_slot == -1) SERIAL_PROTOCOLPGM("No Mesh Loaded."); else { - SERIAL_PROTOCOLPAIR("Mesh ", state.eeprom_storage_slot); + SERIAL_PROTOCOLPAIR("Mesh ", state.storage_slot); SERIAL_PROTOCOLPGM(" Loaded."); } SERIAL_EOL; @@ -1188,12 +1200,15 @@ SERIAL_PROTOCOL_F(zprobe_zoffset, 7); SERIAL_EOL; - SERIAL_PROTOCOLLNPAIR("ubl.eeprom_start=", hex_address((void*)eeprom_start)); - + SERIAL_ECHOLNPAIR("UBL_MESH_MIN_X " STRINGIFY(UBL_MESH_MIN_X) "=", UBL_MESH_MIN_X); + SERIAL_ECHOLNPAIR("UBL_MESH_MIN_Y " STRINGIFY(UBL_MESH_MIN_Y) "=", UBL_MESH_MIN_Y); + safe_delay(25); + SERIAL_ECHOLNPAIR("UBL_MESH_MAX_X " STRINGIFY(UBL_MESH_MAX_X) "=", UBL_MESH_MAX_X); + SERIAL_ECHOLNPAIR("UBL_MESH_MAX_Y " STRINGIFY(UBL_MESH_MAX_Y) "=", UBL_MESH_MAX_Y); + safe_delay(25); SERIAL_ECHOLNPAIR("GRID_MAX_POINTS_X ", GRID_MAX_POINTS_X); SERIAL_ECHOLNPAIR("GRID_MAX_POINTS_Y ", GRID_MAX_POINTS_Y); safe_delay(25); - SERIAL_ECHOLNPAIR("MESH_X_DIST ", MESH_X_DIST); SERIAL_ECHOLNPAIR("MESH_Y_DIST ", MESH_Y_DIST); safe_delay(25); @@ -1214,38 +1229,34 @@ } SERIAL_EOL; - SERIAL_PROTOCOLLNPAIR("Free EEPROM space starts at: ", hex_address((void*)eeprom_start)); - SERIAL_PROTOCOLLNPAIR("end of EEPROM: ", hex_address((void*)E2END)); - safe_delay(25); + #if HAS_KILL + SERIAL_PROTOCOLPAIR("Kill pin on :", KILL_PIN); + SERIAL_PROTOCOLLNPAIR(" state:", READ(KILL_PIN)); + #endif + SERIAL_EOL; + safe_delay(50); - SERIAL_PROTOCOLPAIR("sizeof(ubl.state) : ", (int)sizeof(state)); + SERIAL_PROTOCOLLNPAIR("ubl_state_at_invocation :", ubl_state_at_invocation); SERIAL_EOL; - SERIAL_PROTOCOLLNPAIR("z_value[][] size: ", (int)sizeof(z_values)); + SERIAL_PROTOCOLLNPAIR("ubl_state_recursion_chk :", ubl_state_recursion_chk); SERIAL_EOL; - safe_delay(25); - - SERIAL_PROTOCOLLNPAIR("EEPROM free for UBL: ", hex_address((void*)k)); - safe_delay(25); + safe_delay(50); - SERIAL_PROTOCOLPAIR("EEPROM can hold ", k / sizeof(z_values)); - SERIAL_PROTOCOLLNPGM(" meshes.\n"); - safe_delay(25); + SERIAL_PROTOCOLPAIR("Meshes go from ", hex_address((void*)settings.get_start_of_meshes())); + SERIAL_PROTOCOLLNPAIR(" to ", hex_address((void*)settings.get_end_of_meshes())); + safe_delay(50); - SERIAL_PROTOCOLPAIR("\nGRID_MAX_POINTS_X ", GRID_MAX_POINTS_X); - SERIAL_PROTOCOLPAIR("\nGRID_MAX_POINTS_Y ", GRID_MAX_POINTS_Y); - safe_delay(25); + SERIAL_PROTOCOLLNPAIR("sizeof(ubl) : ", (int)sizeof(ubl)); + SERIAL_EOL; + SERIAL_PROTOCOLLNPAIR("z_value[][] size: ", (int)sizeof(z_values)); SERIAL_EOL; - - SERIAL_ECHOPGM("UBL_MESH_MIN_X " STRINGIFY(UBL_MESH_MIN_X)); - SERIAL_ECHOLNPAIR("=", UBL_MESH_MIN_X ); - SERIAL_ECHOPGM("UBL_MESH_MIN_Y " STRINGIFY(UBL_MESH_MIN_Y)); - SERIAL_ECHOLNPAIR("=", UBL_MESH_MIN_Y ); safe_delay(25); - SERIAL_ECHOPGM("UBL_MESH_MAX_X " STRINGIFY(UBL_MESH_MAX_X)); - SERIAL_ECHOLNPAIR("=", UBL_MESH_MAX_X); - SERIAL_ECHOPGM("UBL_MESH_MAX_Y " STRINGIFY(UBL_MESH_MAX_Y)); - SERIAL_ECHOLNPAIR("=", UBL_MESH_MAX_Y); + SERIAL_PROTOCOLLNPAIR("EEPROM free for UBL: ", hex_address((void*)(settings.get_end_of_meshes() - settings.get_start_of_meshes()))); + safe_delay(50); + + SERIAL_PROTOCOLPAIR("EEPROM can hold ", settings.calc_num_meshes()); + SERIAL_PROTOCOLLNPGM(" meshes.\n"); safe_delay(25); if (!sanity_check()) { @@ -1284,27 +1295,31 @@ * use cases for the users. So we can wait and see what to do with it. */ void g29_compare_current_mesh_to_stored_mesh() { - float tmp_z_values[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y]; + int16_t a = settings.calc_num_meshes(); + + if (!a) { + SERIAL_PROTOCOLLNPGM("?EEPROM storage not available."); + return; + } if (!code_has_value()) { - SERIAL_PROTOCOLLNPGM("?Mesh # required.\n"); + SERIAL_PROTOCOLLNPGM("?Storage slot # required."); + SERIAL_PROTOCOLLNPAIR("?Use 0 to ", a - 1); return; } - storage_slot = code_value_int(); - int16_t j = (UBL_LAST_EEPROM_INDEX - ubl.eeprom_start) / sizeof(tmp_z_values); + storage_slot = code_value_int(); - if (!WITHIN(storage_slot, 0, j - 1) || ubl.eeprom_start <= 0) { - SERIAL_PROTOCOLLNPGM("?EEPROM storage not available for use.\n"); + if (!WITHIN(storage_slot, 0, a - 1)) { + SERIAL_PROTOCOLLNPGM("?Invalid storage slot."); + SERIAL_PROTOCOLLNPAIR("?Use 0 to ", a - 1); return; } - j = UBL_LAST_EEPROM_INDEX - (storage_slot + 1) * sizeof(tmp_z_values); - eeprom_read_block((void *)&tmp_z_values, (void *)j, sizeof(tmp_z_values)); + float tmp_z_values[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y]; + settings.load_mesh(storage_slot, &tmp_z_values); - SERIAL_ECHOPAIR("Subtracting Mesh ", storage_slot); - SERIAL_PROTOCOLLNPAIR(" loaded from EEPROM address ", hex_address((void*)j)); // Soon, we can remove the extra clutter of printing - // the address in the EEPROM where the Mesh is stored. + SERIAL_ECHOPAIR("Subtracting current mesh from mesh loaded from slot ", storage_slot); for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) diff --git a/Marlin/utility.cpp b/Marlin/utility.cpp index 03b336af4..43544106e 100644 --- a/Marlin/utility.cpp +++ b/Marlin/utility.cpp @@ -34,6 +34,19 @@ void safe_delay(millis_t ms) { thermalManager.manage_heater(); // This keeps us safe if too many small safe_delay() calls are made } +#if ENABLED(EEPROM_SETTINGS) + + void crc16(uint16_t *crc, const void * const data, uint16_t cnt) { + uint8_t *ptr = (uint8_t*)data; + while (cnt-- > 0) { + *crc = (uint16_t)(*crc ^ (uint16_t)(((uint16_t)*ptr++) << 8)); + for (uint8_t x = 0; x < 8; x++) + *crc = (uint16_t)((*crc & 0x8000) ? ((uint16_t)(*crc << 1) ^ 0x1021) : (*crc << 1)); + } + } + +#endif // EEPROM_SETTINGS + #if ENABLED(ULTRA_LCD) char conv[8] = { 0 }; diff --git a/Marlin/utility.h b/Marlin/utility.h index 7306b053c..f14b272fb 100644 --- a/Marlin/utility.h +++ b/Marlin/utility.h @@ -25,6 +25,10 @@ void safe_delay(millis_t ms); +#if ENABLED(EEPROM_SETTINGS) + void crc16(uint16_t *crc, const void * const data, uint16_t cnt); +#endif + #if ENABLED(ULTRA_LCD) // Convert unsigned int to string with 12 format From 7f4e4b1212a6d18b18d3d032bed718f92af942f1 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 16 May 2017 02:34:36 -0500 Subject: [PATCH 096/189] UBL name/state methods --- Marlin/Marlin_main.cpp | 10 +++---- Marlin/configuration_store.cpp | 50 +++++++++++++++++++--------------- Marlin/ubl.cpp | 10 +++++++ Marlin/ubl.h | 2 ++ Marlin/ubl_G29.cpp | 43 +++++++++-------------------- 5 files changed, 58 insertions(+), 57 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 0d7e24929..3ec817abf 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -3940,7 +3940,7 @@ void home_all_axes() { gcode_G28(true); } #if ENABLED(MESH_BED_LEVELING) // Save 130 bytes with non-duplication of PSTR - void say_not_entered() { SERIAL_PROTOCOLLNPGM(" not entered."); } + void echo_not_entered() { SERIAL_PROTOCOLLNPGM(" not entered."); } void mbl_mesh_report() { SERIAL_PROTOCOLLNPGM("Num X,Y: " STRINGIFY(GRID_MAX_POINTS_X) "," STRINGIFY(GRID_MAX_POINTS_Y)); @@ -4071,7 +4071,7 @@ void home_all_axes() { gcode_G28(true); } } } else { - SERIAL_CHAR('X'); say_not_entered(); + SERIAL_CHAR('X'); echo_not_entered(); return; } @@ -4083,7 +4083,7 @@ void home_all_axes() { gcode_G28(true); } } } else { - SERIAL_CHAR('Y'); say_not_entered(); + SERIAL_CHAR('Y'); echo_not_entered(); return; } @@ -4091,7 +4091,7 @@ void home_all_axes() { gcode_G28(true); } mbl.z_values[px][py] = code_value_linear_units(); } else { - SERIAL_CHAR('Z'); say_not_entered(); + SERIAL_CHAR('Z'); echo_not_entered(); return; } break; @@ -4101,7 +4101,7 @@ void home_all_axes() { gcode_G28(true); } mbl.z_offset = code_value_linear_units(); } else { - SERIAL_CHAR('Z'); say_not_entered(); + SERIAL_CHAR('Z'); echo_not_entered(); return; } break; diff --git a/Marlin/configuration_store.cpp b/Marlin/configuration_store.cpp index 6ca18b0d8..4ea56ff6f 100644 --- a/Marlin/configuration_store.cpp +++ b/Marlin/configuration_store.cpp @@ -425,7 +425,7 @@ void MarlinSettings::postprocess() { EEPROM_WRITE(ubl.state.z_offset); EEPROM_WRITE(ubl.state.storage_slot); #else - const bool ubl_active = 0; + const bool ubl_active = false; dummy = 0.0f; const int8_t storage_slot = -1; EEPROM_WRITE(ubl_active); @@ -991,18 +991,20 @@ void MarlinSettings::postprocess() { } #if ENABLED(AUTO_BED_LEVELING_UBL) - meshes_begin = (eeprom_index + 32) & 0xFFF8; // Pad the end of configuration data so it - // can float up or down a little bit without - // disrupting the mesh data - SERIAL_ECHOPGM(" UBL "); - if (!ubl.state.active) SERIAL_ECHO("not "); - SERIAL_ECHOLNPGM("active!"); + meshes_begin = (eeprom_index + 32) & 0xFFF8; // Pad the end of configuration data so it + // can float up or down a little bit without + // disrupting the mesh data + ubl.report_state(); if (!ubl.sanity_check()) { - SERIAL_ECHOLNPGM("\nUnified Bed Leveling system initialized.\n"); + SERIAL_EOL; + ubl.echo_name(); + SERIAL_ECHOLNPGM(" initialized.\n"); } else { - SERIAL_PROTOCOLPGM("?Unable to enable Unified Bed Leveling system.\n"); + SERIAL_PROTOCOLPGM("?Can't enable "); + ubl.echo_name(); + SERIAL_PROTOCOLLNPGM("."); ubl.reset(); } @@ -1028,6 +1030,12 @@ void MarlinSettings::postprocess() { #if ENABLED(AUTO_BED_LEVELING_UBL) + void ubl_invalid_slot(const int s) { + SERIAL_PROTOCOLLNPGM("?Invalid slot."); + SERIAL_PROTOCOL(s); + SERIAL_PROTOCOLLNPGM(" mesh slots available."); + } + int MarlinSettings::calc_num_meshes() { //obviously this will get more sophisticated once we've added an actual MAT @@ -1041,12 +1049,10 @@ void MarlinSettings::postprocess() { #if ENABLED(AUTO_BED_LEVELING_UBL) const int a = calc_num_meshes(); if (!WITHIN(slot, 0, a - 1)) { - SERIAL_PROTOCOLLNPGM("?Invalid slot."); - SERIAL_PROTOCOL(a); - SERIAL_PROTOCOLLNPGM(" mesh slots available."); - SERIAL_PROTOCOLLNPAIR("E2END : ", E2END); - SERIAL_PROTOCOLLNPAIR("meshes_end : ", (int)meshes_end); - SERIAL_PROTOCOLLNPAIR("slot : ", slot); + ubl_invalid_slot(a); + SERIAL_PROTOCOLPAIR("E2END=", E2END); + SERIAL_PROTOCOLPAIR(" meshes_end=", (int)meshes_end); + SERIAL_PROTOCOLLNPAIR(" slot=", slot); SERIAL_EOL; return; } @@ -1074,9 +1080,7 @@ void MarlinSettings::postprocess() { const int16_t a = settings.calc_num_meshes(); if (!WITHIN(slot, 0, a - 1)) { - SERIAL_PROTOCOLLNPGM("?Invalid Slot."); - SERIAL_PROTOCOL(a); - SERIAL_PROTOCOLLNPGM(" mesh slots available."); + ubl_invalid_slot(a); return; } @@ -1538,7 +1542,8 @@ void MarlinSettings::reset() { if (!forReplay) { CONFIG_ECHO_START; - SERIAL_ECHOLNPGM("Unified Bed Leveling:"); + ubl.echo_name(); + SERIAL_ECHOLNPGM(":"); } CONFIG_ECHO_START; SERIAL_ECHOPAIR(" M420 S", ubl.state.active ? 1 : 0); @@ -1548,9 +1553,10 @@ void MarlinSettings::reset() { SERIAL_EOL; if (!forReplay) { - SERIAL_ECHOPGM("\nUBL is "); - ubl.state.active ? SERIAL_CHAR('A') : SERIAL_ECHOPGM("Ina"); - SERIAL_ECHOLNPAIR("ctive\n\nActive Mesh Slot: ", ubl.state.storage_slot); + SERIAL_EOL; + ubl.report_state(); + + SERIAL_ECHOLNPAIR("\nActive Mesh Slot: ", ubl.state.storage_slot); SERIAL_ECHOPGM("z_offset: "); SERIAL_ECHO_F(ubl.state.z_offset, 6); diff --git a/Marlin/ubl.cpp b/Marlin/ubl.cpp index b4ee7d238..8ca43c5be 100644 --- a/Marlin/ubl.cpp +++ b/Marlin/ubl.cpp @@ -41,6 +41,16 @@ uint8_t ubl_cnt = 0; + void unified_bed_leveling::echo_name() { SERIAL_PROTOCOLPGM("Unified Bed Leveling"); } + + void unified_bed_leveling::report_state() { + echo_name(); + SERIAL_PROTOCOLPGM(" System v" UBL_VERSION " "); + if (!state.active) SERIAL_PROTOCOLPGM("in"); + SERIAL_PROTOCOLLNPGM("active."); + safe_delay(50); + } + static void serial_echo_xy(const int16_t x, const int16_t y) { SERIAL_CHAR('('); SERIAL_ECHO(x); diff --git a/Marlin/ubl.h b/Marlin/ubl.h index 7ad191f6d..b1a6b9f7e 100644 --- a/Marlin/ubl.h +++ b/Marlin/ubl.h @@ -103,6 +103,8 @@ public: + void echo_name(); + void report_state(); void find_mean_mesh_height(); void shift_mesh_height(); void probe_entire_mesh(const float &lx, const float &ly, const bool do_ubl_mesh_map, const bool stow_probe, bool do_furthest); diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 493ee1d88..4c14322cb 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -906,7 +906,7 @@ return current_position[Z_AXIS]; } - static void say_and_take_a_measurement() { + static void echo_and_take_a_measurement() { SERIAL_PROTOCOLLNPGM(" and take a measurement."); } @@ -922,15 +922,15 @@ SERIAL_PROTOCOLPGM("Place shim under nozzle"); LCD_MESSAGEPGM("Place shim & measure"); lcd_goto_screen(lcd_status_screen); - say_and_take_a_measurement(); + echo_and_take_a_measurement(); const float z1 = use_encoder_wheel_to_measure_point(); do_blocking_move_to_z(current_position[Z_AXIS] + SIZE_OF_LITTLE_RAISE); stepper.synchronize(); SERIAL_PROTOCOLPGM("Remove shim"); - LCD_MESSAGEPGM("Remove & measure bed"); - say_and_take_a_measurement(); + LCD_MESSAGEPGM("Remove & measure bed"); // TODO: Make translatable string + echo_and_take_a_measurement(); const float z2 = use_encoder_wheel_to_measure_point(); @@ -1031,17 +1031,6 @@ do_blocking_move_to_xy(lx, ly); } - static void say_ubl_name() { - SERIAL_PROTOCOLPGM("Unified Bed Leveling "); - } - - static void report_ubl_state() { - say_ubl_name(); - SERIAL_PROTOCOLPGM("System "); - if (!ubl.state.active) SERIAL_PROTOCOLPGM("de"); - SERIAL_PROTOCOLLNPGM("activated.\n"); - } - bool g29_parameter_parsing() { bool err_flag = false; @@ -1110,12 +1099,12 @@ SERIAL_PROTOCOLLNPGM("?Can't activate and deactivate at the same time.\n"); return UBL_ERR; } - ubl.state.active = 1; - report_ubl_state(); + ubl.state.active = true; + ubl.report_state(); } else if (code_seen('D')) { - ubl.state.active = 0; - report_ubl_state(); + ubl.state.active = false; + ubl.report_state(); } // Set global 'C' flag and its value @@ -1171,14 +1160,7 @@ * good to have the extra information. Soon... we prune this to just a few items */ void unified_bed_leveling::g29_what_command() { - say_ubl_name(); - SERIAL_PROTOCOLPGM("System Version " UBL_VERSION " "); - if (state.active) - SERIAL_PROTOCOLCHAR('A'); - else - SERIAL_PROTOCOLPGM("Ina"); - SERIAL_PROTOCOLLNPGM("ctive.\n"); - safe_delay(50); + report_state(); if (state.storage_slot == -1) SERIAL_PROTOCOLPGM("No Mesh Loaded."); @@ -1260,8 +1242,8 @@ safe_delay(25); if (!sanity_check()) { - say_ubl_name(); - SERIAL_PROTOCOLLNPGM("sanity checks passed."); + echo_name(); + SERIAL_PROTOCOLLNPGM(" sanity checks passed."); } } @@ -1319,7 +1301,8 @@ float tmp_z_values[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y]; settings.load_mesh(storage_slot, &tmp_z_values); - SERIAL_ECHOPAIR("Subtracting current mesh from mesh loaded from slot ", storage_slot); + SERIAL_PROTOCOLPAIR("Subtracting mesh in slot ", storage_slot); + SERIAL_PROTOCOLLNPGM(" from current mesh."); for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) From a3abfeac476ff7f1c4bbcebe7a2cdaf5330e1f67 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 16 May 2017 19:52:41 -0500 Subject: [PATCH 097/189] Mark strings needing translation --- Marlin/Marlin_main.cpp | 6 +++--- Marlin/ubl_G29.cpp | 24 +++++++++++++----------- 2 files changed, 16 insertions(+), 14 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 3ec817abf..c6d3c5cda 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -5120,7 +5120,7 @@ void home_all_axes() { gcode_G28(true); } SERIAL_PROTOCOLPGM("Checking... AC"); if (verbose_level == 0) SERIAL_PROTOCOLPGM(" (DRY-RUN)"); SERIAL_EOL; - LCD_MESSAGEPGM("Checking... AC"); + LCD_MESSAGEPGM("Checking... AC"); // TODO: Make translatable string SERIAL_PROTOCOLPAIR(".Height:", DELTA_HEIGHT + home_offset[Z_AXIS]); if (!do_height_only) { @@ -5340,7 +5340,7 @@ void home_all_axes() { gcode_G28(true); } SERIAL_PROTOCOL_SP(36); SERIAL_PROTOCOLPGM("rolling back."); SERIAL_EOL; - LCD_MESSAGEPGM("Calibration OK"); + LCD_MESSAGEPGM("Calibration OK"); // TODO: Make translatable string } else { // !end iterations char mess[15] = "No convergence"; @@ -5391,7 +5391,7 @@ void home_all_axes() { gcode_G28(true); } } else { SERIAL_PROTOCOLLNPGM("Calibration OK"); - LCD_MESSAGEPGM("Calibration OK"); + LCD_MESSAGEPGM("Calibration OK"); // TODO: Make translatable string SERIAL_PROTOCOLPAIR(".Height:", DELTA_HEIGHT + home_offset[Z_AXIS]); SERIAL_EOL; serialprintPGM(save_message); diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 4c14322cb..6e97d702f 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -668,7 +668,7 @@ if (ELAPSED(millis(), nxt)) { SERIAL_PROTOCOLLNPGM("\nZ-Offset Adjustment Stopped."); do_blocking_move_to_z(Z_CLEARANCE_DEPLOY_PROBE); - LCD_MESSAGEPGM("Z-Offset Stopped"); + LCD_MESSAGEPGM("Z-Offset Stopped"); // TODO: Make translatable string ubl.restore_ubl_active_state_and_leave(); goto LEAVE; } @@ -920,7 +920,7 @@ stepper.synchronize(); SERIAL_PROTOCOLPGM("Place shim under nozzle"); - LCD_MESSAGEPGM("Place shim & measure"); + LCD_MESSAGEPGM("Place shim & measure"); // TODO: Make translatable string lcd_goto_screen(lcd_status_screen); echo_and_take_a_measurement(); @@ -976,7 +976,7 @@ do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); - LCD_MESSAGEPGM("Moving to next"); + LCD_MESSAGEPGM("Moving to next"); // TODO: Make translatable string do_blocking_move_to_xy(xProbe, yProbe); do_blocking_move_to_z(z_clearance); @@ -986,8 +986,10 @@ if (do_ubl_mesh_map) ubl.display_map(map_type); // show user where we're probing - if (code_seen('B')) {LCD_MESSAGEPGM("Place shim & measure");} - else {LCD_MESSAGEPGM("Measure");} + if (code_seen('B')) + LCD_MESSAGEPGM("Place shim & measure"); // TODO: Make translatable string + else + LCD_MESSAGEPGM("Measure"); // TODO: Make translatable string while (ubl_lcd_clicked()) delay(50); // wait for user to release encoder wheel delay(50); // debounce @@ -1034,7 +1036,7 @@ bool g29_parameter_parsing() { bool err_flag = false; - LCD_MESSAGEPGM("Doing G29 UBL!"); + LCD_MESSAGEPGM("Doing G29 UBL!"); // TODO: Make translatable string lcd_quick_feedback(); ubl_constant = 0.0; @@ -1137,7 +1139,7 @@ ubl_state_recursion_chk++; if (ubl_state_recursion_chk != 1) { SERIAL_ECHOLNPGM("save_ubl_active_state_and_disabled() called multiple times in a row."); - LCD_MESSAGEPGM("save_UBL_active() error"); + LCD_MESSAGEPGM("save_UBL_active() error"); // TODO: Make translatable string lcd_quick_feedback(); return; } @@ -1148,7 +1150,7 @@ void unified_bed_leveling::restore_ubl_active_state_and_leave() { if (--ubl_state_recursion_chk) { SERIAL_ECHOLNPGM("restore_ubl_active_state_and_leave() called too many times."); - LCD_MESSAGEPGM("restore_UBL_active() error"); + LCD_MESSAGEPGM("restore_UBL_active() error"); // TODO: Make translatable string lcd_quick_feedback(); return; } @@ -1394,7 +1396,7 @@ memset(not_done, 0xFF, sizeof(not_done)); - LCD_MESSAGEPGM("Fine Tuning Mesh"); + LCD_MESSAGEPGM("Fine Tuning Mesh"); // TODO: Make translatable string do_blocking_move_to_z(Z_CLEARANCE_DEPLOY_PROBE); do_blocking_move_to_xy(lx, ly); @@ -1452,7 +1454,7 @@ lcd_return_to_status(); //SERIAL_PROTOCOLLNPGM("\nFine Tuning of Mesh Stopped."); do_blocking_move_to_z(Z_CLEARANCE_DEPLOY_PROBE); - LCD_MESSAGEPGM("Mesh Editing Stopped"); + LCD_MESSAGEPGM("Mesh Editing Stopped"); // TODO: Make translatable string while (ubl_lcd_clicked()) idle(); @@ -1479,7 +1481,7 @@ do_blocking_move_to_xy(lx, ly); - LCD_MESSAGEPGM("Done Editing Mesh"); + LCD_MESSAGEPGM("Done Editing Mesh"); // TODO: Make translatable string SERIAL_ECHOLNPGM("Done Editing Mesh"); } From 99c4900a98163c784ef210ec574fc052873e14e4 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 7 Apr 2017 13:52:05 -0500 Subject: [PATCH 098/189] SPINDLE/LASER config changes --- Marlin/Conditionals_post.h | 2 +- Marlin/Configuration.h | 4 ++ Marlin/Configuration_adv.h | 49 +++++++++++++++ Marlin/SanityCheck.h | 61 +++++++++++++++++++ .../Cartesio/Configuration.h | 4 ++ .../Cartesio/Configuration_adv.h | 49 +++++++++++++++ .../Felix/Configuration.h | 4 ++ .../Felix/Configuration_adv.h | 49 +++++++++++++++ .../Felix/DUAL/Configuration.h | 4 ++ .../FolgerTech-i3-2020/Configuration.h | 4 ++ .../FolgerTech-i3-2020/Configuration_adv.h | 53 ++++++++++++++++ .../Hephestos/Configuration.h | 4 ++ .../Hephestos/Configuration_adv.h | 49 +++++++++++++++ .../Hephestos_2/Configuration.h | 4 ++ .../Hephestos_2/Configuration_adv.h | 49 +++++++++++++++ .../K8200/Configuration.h | 4 ++ .../K8200/Configuration_adv.h | 49 +++++++++++++++ .../K8400/Configuration.h | 4 ++ .../K8400/Configuration_adv.h | 49 +++++++++++++++ .../K8400/Dual-head/Configuration.h | 4 ++ .../RepRapWorld/Megatronics/Configuration.h | 4 ++ .../RigidBot/Configuration.h | 4 ++ .../RigidBot/Configuration_adv.h | 49 +++++++++++++++ .../SCARA/Configuration.h | 4 ++ .../SCARA/Configuration_adv.h | 49 +++++++++++++++ .../TAZ4/Configuration.h | 4 ++ .../TAZ4/Configuration_adv.h | 49 +++++++++++++++ .../TinyBoy2/Configuration.h | 4 ++ .../TinyBoy2/Configuration_adv.h | 49 +++++++++++++++ .../WITBOX/Configuration.h | 4 ++ .../WITBOX/Configuration_adv.h | 49 +++++++++++++++ .../adafruit/ST7565/Configuration.h | 4 ++ .../FLSUN/auto_calibrate/Configuration.h | 4 ++ .../FLSUN/auto_calibrate/Configuration_adv.h | 49 +++++++++++++++ .../delta/FLSUN/kossel_mini/Configuration.h | 4 ++ .../FLSUN/kossel_mini/Configuration_adv.h | 49 +++++++++++++++ .../delta/generic/Configuration.h | 4 ++ .../delta/generic/Configuration_adv.h | 49 +++++++++++++++ .../delta/kossel_mini/Configuration.h | 4 ++ .../delta/kossel_mini/Configuration_adv.h | 49 +++++++++++++++ .../delta/kossel_pro/Configuration.h | 4 ++ .../delta/kossel_pro/Configuration_adv.h | 49 +++++++++++++++ .../delta/kossel_xl/Configuration.h | 4 ++ .../delta/kossel_xl/Configuration_adv.h | 49 +++++++++++++++ .../gCreate_gMax1.5+/Configuration.h | 4 ++ .../gCreate_gMax1.5+/Configuration_adv.h | 49 +++++++++++++++ .../makibox/Configuration.h | 4 ++ .../makibox/Configuration_adv.h | 49 +++++++++++++++ .../tvrrug/Round2/Configuration.h | 4 ++ .../tvrrug/Round2/Configuration_adv.h | 49 +++++++++++++++ .../wt150/Configuration.h | 4 ++ .../wt150/Configuration_adv.h | 49 +++++++++++++++ 52 files changed, 1301 insertions(+), 1 deletion(-) diff --git a/Marlin/Conditionals_post.h b/Marlin/Conditionals_post.h index 7cf32396b..c40289ea5 100644 --- a/Marlin/Conditionals_post.h +++ b/Marlin/Conditionals_post.h @@ -579,7 +579,7 @@ #define HAS_SUICIDE (PIN_EXISTS(SUICIDE)) #define HAS_PHOTOGRAPH (PIN_EXISTS(PHOTOGRAPH)) #define HAS_BUZZER (PIN_EXISTS(BEEPER) || ENABLED(LCD_USE_I2C_BUZZER)) - #define HAS_CASE_LIGHT (PIN_EXISTS(CASE_LIGHT)) + #define HAS_CASE_LIGHT (PIN_EXISTS(CASE_LIGHT) && ENABLED(CASE_LIGHT_ENABLE)) // Digital control #define HAS_MICROSTEPS (HAS_X_MICROSTEPS || HAS_Y_MICROSTEPS || HAS_Z_MICROSTEPS || HAS_E0_MICROSTEPS || HAS_E1_MICROSTEPS || HAS_E2_MICROSTEPS || HAS_E3_MICROSTEPS || HAS_E4_MICROSTEPS) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 774178f3d..529b510aa 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -129,6 +129,8 @@ // You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4) //#define MACHINE_UUID "00000000-0000-0000-0000-000000000000" +// @section extruder + // This defines the number of extruders // :[1, 2, 3, 4, 5] #define EXTRUDERS 1 @@ -172,6 +174,8 @@ //#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis //#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis +// @section machine + /** * Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN * diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index b51219dbc..131af4706 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1132,6 +1132,55 @@ //#define EXPERIMENTAL_I2CBUS #define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave +// @section extras + +/** + * Spindle & Laser control + * + * Add the M3, M4, and M5 commands to turn the spindle/laser on and off, and + * to set spindle speed, spindle direction, and laser power. + * + * SuperPid is a router/spindle speed controller used in the CNC milling community. + * Marlin can be used to turn the spindle on and off. It can also be used to set + * the spindle speed from 5,000 to 30,000 RPM. + * + * You'll need to select a pin for the ON/OFF function and optionally choose a 0-5V + * hardware PWM pin for the speed control and a pin for the rotation direction. + * + * See http://marlinfw.org/docs/configuration/laser_spindle.html for more config details. + */ +//#define SPINDLE_LASER_ENABLE +#if ENABLED(SPINDLE_LASER_ENABLE) + + #define SPINDLE_LASER_ENABLE_INVERT false // set to "true" if the on/off function is reversed + #define SPINDLE_LASER_PWM true // set to true if your controller supports setting the speed/power + #define SPINDLE_LASER_PWM_INVERT true // set to "true" if the speed/power goes up when you want it to go slower + #define SPINDLE_LASER_POWERUP_DELAY 5000 // delay in milliseconds to allow the spindle/laser to come up to speed/power + #define SPINDLE_LASER_POWERDOWN_DELAY 5000 // delay in milliseconds to allow the spindle to stop + #define SPINDLE_DIR_CHANGE true // set to true if your spindle controller supports changing spindle direction + #define SPINDLE_INVERT_DIR false + #define SPINDLE_STOP_ON_DIR_CHANGE true // set to true if Marlin should stop the spindle before changing rotation direction + + /** + * The M3 & M4 commands use the following equation to convert PWM duty cycle to speed/power + * + * SPEED/POWER = PWM duty cycle * SPEED_POWER_SLOPE + SPEED_POWER_INTERCEPT + * where PWM duty cycle varies from 0 to 255 + * + * set the following for your controller (ALL MUST BE SET) + */ + + #define SPEED_POWER_SLOPE 118.4 + #define SPEED_POWER_INTERCEPT 0 + #define SPEED_POWER_MIN 5000 + #define SPEED_POWER_MAX 30000 // SuperPID router controller 0 - 30,000 RPM + + //#define SPEED_POWER_SLOPE 0.3922 + //#define SPEED_POWER_INTERCEPT 0 + //#define SPEED_POWER_MIN 10 + //#define SPEED_POWER_MAX 100 // 0-100% +#endif + /** * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins */ diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index 4d3b680fb..9ddda7cbc 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -1134,3 +1134,64 @@ static_assert(COUNT(sanity_arr_3) >= XYZE, "DEFAULT_MAX_ACCELERATION requires 4 static_assert(COUNT(sanity_arr_1) <= XYZE_N, "DEFAULT_AXIS_STEPS_PER_UNIT has too many elements."); static_assert(COUNT(sanity_arr_2) <= XYZE_N, "DEFAULT_MAX_FEEDRATE has too many elements."); static_assert(COUNT(sanity_arr_3) <= XYZE_N, "DEFAULT_MAX_ACCELERATION has too many elements."); + +/** + * Sanity checks for Spindle / Laser + */ +#if ENABLED(SPINDLE_LASER_ENABLE) + #if !PIN_EXISTS(SPINDLE_LASER_ENABLE) + #error "SPINDLE_LASER_ENABLE requires SPINDLE_LASER_ENABLE_PIN." + #elif SPINDLE_DIR_CHANGE && !PIN_EXISTS(SPINDLE_DIR) + #error "SPINDLE_DIR_PIN not defined." + #elif ENABLED(SPINDLE_LASER_PWM) && PIN_EXISTS(SPINDLE_LASER_PWM) + #if !(WITHIN(SPINDLE_LASER_PWM_PIN, 2, 13) || WITHIN(SPINDLE_LASER_PWM_PIN, 44, 46)) + #error "SPINDLE_LASER_PWM_PIN not assigned to a PWM pin." + #elif SPINDLE_LASER_POWERUP_DELAY < 1 + #error "SPINDLE_LASER_POWERUP_DELAY must be greater than 0." + #elif SPINDLE_LASER_POWERDOWN_DELAY < 1 + #error "SPINDLE_LASER_POWERDOWN_DELAY must be greater than 0." + #elif !defined(SPINDLE_LASER_PWM_INVERT) + #error "SPINDLE_LASER_PWM_INVERT missing." + #elif !defined(SPEED_POWER_SLOPE) || !defined(SPEED_POWER_INTERCEPT) || !defined(SPEED_POWER_MIN) || !defined(SPEED_POWER_MAX) + #error "SPINDLE_LASER_PWM equation constant(s) missing." + #elif SPINDLE_LASER_PWM_PIN == 4 || WITHIN(SPINDLE_LASER_PWM_PIN, 11, 13) + #error "Counter/Timer for SPINDLE_LASER_PWM_PIN is used by a system interrupt." + #elif PIN_EXISTS(X_MAX) && X_MAX_PIN == SPINDLE_LASER_PWM_PIN + #error "SPINDLE_LASER_PWM pin is in use by X_MAX endstop." + #elif PIN_EXISTS(X_MIN) && X_MIN_PIN == SPINDLE_LASER_PWM_PIN + #error "SPINDLE_LASER_PWM pin is in use by X_MIN endstop." + #elif PIN_EXISTS(Z_STEP) && Z_STEP_PIN == SPINDLE_LASER_PWM_PIN + #error "SPINDLE_LASER_PWM pin in use by Z_STEP." + #elif NUM_SERVOS > 0 && (WITHIN(SPINDLE_LASER_PWM_PIN, 2, 3) || SPINDLE_LASER_PWM_PIN == 5) + #error "Counter/Timer for SPINDLE_LASER_PWM_PIN is used by the servo system." + #elif PIN_EXISTS(CASE_LIGHT) && SPINDLE_LASER_PWM_PIN == CASE_LIGHT_PIN + #error "SPINDLE_LASER_PWM_PIN is used by CASE_LIGHT_PIN." + #elif PIN_EXISTS(E0_AUTO_FAN) && SPINDLE_LASER_PWM_PIN == E0_AUTO_FAN_PIN + #error "SPINDLE_LASER_PWM_PIN is used by E0_AUTO_FAN_PIN." + #elif PIN_EXISTS(E1_AUTO_FAN) && SPINDLE_LASER_PWM_PIN == E1_AUTO_FAN_PIN + #error "SPINDLE_LASER_PWM_PIN is used by E1_AUTO_FAN_PIN." + #elif PIN_EXISTS(E2_AUTO_FAN) && SPINDLE_LASER_PWM_PIN == E2_AUTO_FAN_PIN + #error "SPINDLE_LASER_PWM_PIN is used by E2_AUTO_FAN_PIN." + #elif PIN_EXISTS(E3_AUTO_FAN) && SPINDLE_LASER_PWM_PIN == E3_AUTO_FAN_PIN + #error "SPINDLE_LASER_PWM_PIN is used by E3_AUTO_FAN_PIN." + #elif PIN_EXISTS(E4_AUTO_FAN) && SPINDLE_LASER_PWM_PIN == E4_AUTO_FAN_PIN + #error "SPINDLE_LASER_PWM_PIN is used by E4_AUTO_FAN_PIN." + #elif PIN_EXISTS(FAN) && SPINDLE_LASER_PWM_PIN == FAN_PIN + #error "SPINDLE_LASER_PWM_PIN is used FAN_PIN." + #elif PIN_EXISTS(FAN1) && SPINDLE_LASER_PWM_PIN == FAN1_PIN + #error "SPINDLE_LASER_PWM_PIN is used FAN1_PIN." + #elif PIN_EXISTS(FAN2) && SPINDLE_LASER_PWM_PIN == FAN2_PIN + #error "SPINDLE_LASER_PWM_PIN is used FAN2_PIN." + #elif PIN_EXISTS(CONTROLLERFAN) && SPINDLE_LASER_PWM_PIN == CONTROLLERFAN_PIN + #error "SPINDLE_LASER_PWM_PIN is used by CONTROLLERFAN_PIN." + #elif PIN_EXISTS(MOTOR_CURRENT_PWM_XY) && SPINDLE_LASER_PWM_PIN == MOTOR_CURRENT_PWM_XY_PIN + #error "SPINDLE_LASER_PWM_PIN is used by MOTOR_CURRENT_PWM_XY." + #elif PIN_EXISTS(MOTOR_CURRENT_PWM_Z) && SPINDLE_LASER_PWM_PIN == MOTOR_CURRENT_PWM_Z_PIN + #error "SPINDLE_LASER_PWM_PIN is used by MOTOR_CURRENT_PWM_Z." + #elif PIN_EXISTS(MOTOR_CURRENT_PWM_E) && SPINDLE_LASER_PWM_PIN == MOTOR_CURRENT_PWM_E_PIN + #error "SPINDLE_LASER_PWM_PIN is used by MOTOR_CURRENT_PWM_E." + #elif PIN_EXISTS(CASE_LIGHT) && SPINDLE_LASER_PWM_PIN == CASE_LIGHT_PIN + #error "SPINDLE_LASER_PWM_PIN is used by CASE_LIGHT." + #endif + #endif +#endif // SPINDLE_LASER_ENABLE diff --git a/Marlin/example_configurations/Cartesio/Configuration.h b/Marlin/example_configurations/Cartesio/Configuration.h index 0717c4c71..dc247b68f 100644 --- a/Marlin/example_configurations/Cartesio/Configuration.h +++ b/Marlin/example_configurations/Cartesio/Configuration.h @@ -130,6 +130,8 @@ // You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4) //#define MACHINE_UUID "00000000-0000-0000-0000-000000000000" +// @section extruder + // This defines the number of extruders // :[1, 2, 3, 4, 5] #define EXTRUDERS 3 @@ -173,6 +175,8 @@ //#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis //#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis +// @section machine + /** * Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN * diff --git a/Marlin/example_configurations/Cartesio/Configuration_adv.h b/Marlin/example_configurations/Cartesio/Configuration_adv.h index c26dfb816..372d3fff5 100644 --- a/Marlin/example_configurations/Cartesio/Configuration_adv.h +++ b/Marlin/example_configurations/Cartesio/Configuration_adv.h @@ -1125,6 +1125,55 @@ //#define EXPERIMENTAL_I2CBUS #define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave +// @section extras + +/** + * Spindle & Laser control + * + * Add the M3, M4, and M5 commands to turn the spindle/laser on and off, and + * to set spindle speed, spindle direction, and laser power. + * + * SuperPid is a router/spindle speed controller used in the CNC milling community. + * Marlin can be used to turn the spindle on and off. It can also be used to set + * the spindle speed from 5,000 to 30,000 RPM. + * + * You'll need to select a pin for the ON/OFF function and optionally choose a 0-5V + * hardware PWM pin for the speed control and a pin for the rotation direction. + * + * See http://marlinfw.org/docs/configuration/laser_spindle.html for more config details. + */ +//#define SPINDLE_LASER_ENABLE +#if ENABLED(SPINDLE_LASER_ENABLE) + + #define SPINDLE_LASER_ENABLE_INVERT false // set to "true" if the on/off function is reversed + #define SPINDLE_LASER_PWM true // set to true if your controller supports setting the speed/power + #define SPINDLE_LASER_PWM_INVERT true // set to "true" if the speed/power goes up when you want it to go slower + #define SPINDLE_LASER_POWERUP_DELAY 5000 // delay in milliseconds to allow the spindle/laser to come up to speed/power + #define SPINDLE_LASER_POWERDOWN_DELAY 5000 // delay in milliseconds to allow the spindle to stop + #define SPINDLE_DIR_CHANGE true // set to true if your spindle controller supports changing spindle direction + #define SPINDLE_INVERT_DIR false + #define SPINDLE_STOP_ON_DIR_CHANGE true // set to true if Marlin should stop the spindle before changing rotation direction + + /** + * The M3 & M4 commands use the following equation to convert PWM duty cycle to speed/power + * + * SPEED/POWER = PWM duty cycle * SPEED_POWER_SLOPE + SPEED_POWER_INTERCEPT + * where PWM duty cycle varies from 0 to 255 + * + * set the following for your controller (ALL MUST BE SET) + */ + + #define SPEED_POWER_SLOPE 118.4 + #define SPEED_POWER_INTERCEPT 0 + #define SPEED_POWER_MIN 5000 + #define SPEED_POWER_MAX 30000 // SuperPID router controller 0 - 30,000 RPM + + //#define SPEED_POWER_SLOPE 0.3922 + //#define SPEED_POWER_INTERCEPT 0 + //#define SPEED_POWER_MIN 10 + //#define SPEED_POWER_MAX 100 // 0-100% +#endif + /** * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins */ diff --git a/Marlin/example_configurations/Felix/Configuration.h b/Marlin/example_configurations/Felix/Configuration.h index aa49cf980..55cee75a7 100644 --- a/Marlin/example_configurations/Felix/Configuration.h +++ b/Marlin/example_configurations/Felix/Configuration.h @@ -129,6 +129,8 @@ // You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4) //#define MACHINE_UUID "00000000-0000-0000-0000-000000000000" +// @section extruder + // This defines the number of extruders // :[1, 2, 3, 4, 5] #define EXTRUDERS 1 @@ -172,6 +174,8 @@ //#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis //#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis +// @section machine + /** * Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN * diff --git a/Marlin/example_configurations/Felix/Configuration_adv.h b/Marlin/example_configurations/Felix/Configuration_adv.h index 176fd2ab2..3dabf65d4 100644 --- a/Marlin/example_configurations/Felix/Configuration_adv.h +++ b/Marlin/example_configurations/Felix/Configuration_adv.h @@ -1125,6 +1125,55 @@ //#define EXPERIMENTAL_I2CBUS #define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave +// @section extras + +/** + * Spindle & Laser control + * + * Add the M3, M4, and M5 commands to turn the spindle/laser on and off, and + * to set spindle speed, spindle direction, and laser power. + * + * SuperPid is a router/spindle speed controller used in the CNC milling community. + * Marlin can be used to turn the spindle on and off. It can also be used to set + * the spindle speed from 5,000 to 30,000 RPM. + * + * You'll need to select a pin for the ON/OFF function and optionally choose a 0-5V + * hardware PWM pin for the speed control and a pin for the rotation direction. + * + * See http://marlinfw.org/docs/configuration/laser_spindle.html for more config details. + */ +//#define SPINDLE_LASER_ENABLE +#if ENABLED(SPINDLE_LASER_ENABLE) + + #define SPINDLE_LASER_ENABLE_INVERT false // set to "true" if the on/off function is reversed + #define SPINDLE_LASER_PWM true // set to true if your controller supports setting the speed/power + #define SPINDLE_LASER_PWM_INVERT true // set to "true" if the speed/power goes up when you want it to go slower + #define SPINDLE_LASER_POWERUP_DELAY 5000 // delay in milliseconds to allow the spindle/laser to come up to speed/power + #define SPINDLE_LASER_POWERDOWN_DELAY 5000 // delay in milliseconds to allow the spindle to stop + #define SPINDLE_DIR_CHANGE true // set to true if your spindle controller supports changing spindle direction + #define SPINDLE_INVERT_DIR false + #define SPINDLE_STOP_ON_DIR_CHANGE true // set to true if Marlin should stop the spindle before changing rotation direction + + /** + * The M3 & M4 commands use the following equation to convert PWM duty cycle to speed/power + * + * SPEED/POWER = PWM duty cycle * SPEED_POWER_SLOPE + SPEED_POWER_INTERCEPT + * where PWM duty cycle varies from 0 to 255 + * + * set the following for your controller (ALL MUST BE SET) + */ + + #define SPEED_POWER_SLOPE 118.4 + #define SPEED_POWER_INTERCEPT 0 + #define SPEED_POWER_MIN 5000 + #define SPEED_POWER_MAX 30000 // SuperPID router controller 0 - 30,000 RPM + + //#define SPEED_POWER_SLOPE 0.3922 + //#define SPEED_POWER_INTERCEPT 0 + //#define SPEED_POWER_MIN 10 + //#define SPEED_POWER_MAX 100 // 0-100% +#endif + /** * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins */ diff --git a/Marlin/example_configurations/Felix/DUAL/Configuration.h b/Marlin/example_configurations/Felix/DUAL/Configuration.h index 521374bf1..6c967aeff 100644 --- a/Marlin/example_configurations/Felix/DUAL/Configuration.h +++ b/Marlin/example_configurations/Felix/DUAL/Configuration.h @@ -129,6 +129,8 @@ // You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4) //#define MACHINE_UUID "00000000-0000-0000-0000-000000000000" +// @section extruder + // This defines the number of extruders // :[1, 2, 3, 4, 5] #define EXTRUDERS 2 @@ -172,6 +174,8 @@ //#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis //#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis +// @section machine + /** * Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN * diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h index 6bdc28dee..c6e7d8774 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h @@ -129,6 +129,8 @@ // You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4) //#define MACHINE_UUID "00000000-0000-0000-0000-000000000000" +// @section extruder + // This defines the number of extruders // :[1, 2, 3, 4, 5] #define EXTRUDERS 1 @@ -172,6 +174,8 @@ //#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis //#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis +// @section machine + /** * Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN * diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h index 62025ff15..c003216e0 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h @@ -1132,11 +1132,64 @@ //#define EXPERIMENTAL_I2CBUS #define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave +// @section extras + +/** + * Spindle & Laser control + * + * Add the M3, M4, and M5 commands to turn the spindle/laser on and off, and + * to set spindle speed, spindle direction, and laser power. + * + * SuperPid is a router/spindle speed controller used in the CNC milling community. + * Marlin can be used to turn the spindle on and off. It can also be used to set + * the spindle speed from 5,000 to 30,000 RPM. + * + * You'll need to select a pin for the ON/OFF function and optionally choose a 0-5V + * hardware PWM pin for the speed control and a pin for the rotation direction. + * + * See http://marlinfw.org/docs/configuration/laser_spindle.html for more config details. + */ +//#define SPINDLE_LASER_ENABLE +#if ENABLED(SPINDLE_LASER_ENABLE) + + #define SPINDLE_LASER_ENABLE_INVERT false // set to "true" if the on/off function is reversed + #define SPINDLE_LASER_PWM true // set to true if your controller supports setting the speed/power + #define SPINDLE_LASER_PWM_INVERT true // set to "true" if the speed/power goes up when you want it to go slower + #define SPINDLE_LASER_POWERUP_DELAY 5000 // delay in milliseconds to allow the spindle/laser to come up to speed/power + #define SPINDLE_LASER_POWERDOWN_DELAY 5000 // delay in milliseconds to allow the spindle to stop + #define SPINDLE_DIR_CHANGE true // set to true if your spindle controller supports changing spindle direction + #define SPINDLE_INVERT_DIR false + #define SPINDLE_STOP_ON_DIR_CHANGE true // set to true if Marlin should stop the spindle before changing rotation direction + + /** + * The M3 & M4 commands use the following equation to convert PWM duty cycle to speed/power + * + * SPEED/POWER = PWM duty cycle * SPEED_POWER_SLOPE + SPEED_POWER_INTERCEPT + * where PWM duty cycle varies from 0 to 255 + * + * set the following for your controller (ALL MUST BE SET) + */ + + #define SPEED_POWER_SLOPE 118.4 + #define SPEED_POWER_INTERCEPT 0 + #define SPEED_POWER_MIN 5000 + #define SPEED_POWER_MAX 30000 // SuperPID router controller 0 - 30,000 RPM + + //#define SPEED_POWER_SLOPE 0.3922 + //#define SPEED_POWER_INTERCEPT 0 + //#define SPEED_POWER_MIN 10 + //#define SPEED_POWER_MAX 100 // 0-100% +#endif + +// @section debug + /** * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins */ #define PINS_DEBUGGING +// @section extras + /** * Auto-report temperatures with M155 S */ diff --git a/Marlin/example_configurations/Hephestos/Configuration.h b/Marlin/example_configurations/Hephestos/Configuration.h index 9db79cd5f..21395ffe0 100644 --- a/Marlin/example_configurations/Hephestos/Configuration.h +++ b/Marlin/example_configurations/Hephestos/Configuration.h @@ -132,6 +132,8 @@ // You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4) //#define MACHINE_UUID "00000000-0000-0000-0000-000000000000" +// @section extruder + // This defines the number of extruders // :[1, 2, 3, 4, 5] #define EXTRUDERS 1 @@ -175,6 +177,8 @@ //#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis //#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis +// @section machine + /** * Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN * diff --git a/Marlin/example_configurations/Hephestos/Configuration_adv.h b/Marlin/example_configurations/Hephestos/Configuration_adv.h index 798d74177..903b1ab79 100644 --- a/Marlin/example_configurations/Hephestos/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos/Configuration_adv.h @@ -1125,6 +1125,55 @@ //#define EXPERIMENTAL_I2CBUS #define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave +// @section extras + +/** + * Spindle & Laser control + * + * Add the M3, M4, and M5 commands to turn the spindle/laser on and off, and + * to set spindle speed, spindle direction, and laser power. + * + * SuperPid is a router/spindle speed controller used in the CNC milling community. + * Marlin can be used to turn the spindle on and off. It can also be used to set + * the spindle speed from 5,000 to 30,000 RPM. + * + * You'll need to select a pin for the ON/OFF function and optionally choose a 0-5V + * hardware PWM pin for the speed control and a pin for the rotation direction. + * + * See http://marlinfw.org/docs/configuration/laser_spindle.html for more config details. + */ +//#define SPINDLE_LASER_ENABLE +#if ENABLED(SPINDLE_LASER_ENABLE) + + #define SPINDLE_LASER_ENABLE_INVERT false // set to "true" if the on/off function is reversed + #define SPINDLE_LASER_PWM true // set to true if your controller supports setting the speed/power + #define SPINDLE_LASER_PWM_INVERT true // set to "true" if the speed/power goes up when you want it to go slower + #define SPINDLE_LASER_POWERUP_DELAY 5000 // delay in milliseconds to allow the spindle/laser to come up to speed/power + #define SPINDLE_LASER_POWERDOWN_DELAY 5000 // delay in milliseconds to allow the spindle to stop + #define SPINDLE_DIR_CHANGE true // set to true if your spindle controller supports changing spindle direction + #define SPINDLE_INVERT_DIR false + #define SPINDLE_STOP_ON_DIR_CHANGE true // set to true if Marlin should stop the spindle before changing rotation direction + + /** + * The M3 & M4 commands use the following equation to convert PWM duty cycle to speed/power + * + * SPEED/POWER = PWM duty cycle * SPEED_POWER_SLOPE + SPEED_POWER_INTERCEPT + * where PWM duty cycle varies from 0 to 255 + * + * set the following for your controller (ALL MUST BE SET) + */ + + #define SPEED_POWER_SLOPE 118.4 + #define SPEED_POWER_INTERCEPT 0 + #define SPEED_POWER_MIN 5000 + #define SPEED_POWER_MAX 30000 // SuperPID router controller 0 - 30,000 RPM + + //#define SPEED_POWER_SLOPE 0.3922 + //#define SPEED_POWER_INTERCEPT 0 + //#define SPEED_POWER_MIN 10 + //#define SPEED_POWER_MAX 100 // 0-100% +#endif + /** * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins */ diff --git a/Marlin/example_configurations/Hephestos_2/Configuration.h b/Marlin/example_configurations/Hephestos_2/Configuration.h index 8fbf2f8d6..48623dcd3 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration.h @@ -129,6 +129,8 @@ // You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4) #define MACHINE_UUID "8d083632-40c5-4649-85b8-43d9ae6c5d55" // BQ Hephestos 2 standard config +// @section extruder + // This defines the number of extruders // :[1, 2, 3, 4, 5] #define EXTRUDERS 1 @@ -172,6 +174,8 @@ //#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis //#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis +// @section machine + /** * Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN * diff --git a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h index a0c063576..fd07d62e8 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h @@ -1109,6 +1109,55 @@ //#define EXPERIMENTAL_I2CBUS #define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave +// @section extras + +/** + * Spindle & Laser control + * + * Add the M3, M4, and M5 commands to turn the spindle/laser on and off, and + * to set spindle speed, spindle direction, and laser power. + * + * SuperPid is a router/spindle speed controller used in the CNC milling community. + * Marlin can be used to turn the spindle on and off. It can also be used to set + * the spindle speed from 5,000 to 30,000 RPM. + * + * You'll need to select a pin for the ON/OFF function and optionally choose a 0-5V + * hardware PWM pin for the speed control and a pin for the rotation direction. + * + * See http://marlinfw.org/docs/configuration/laser_spindle.html for more config details. + */ +//#define SPINDLE_LASER_ENABLE +#if ENABLED(SPINDLE_LASER_ENABLE) + + #define SPINDLE_LASER_ENABLE_INVERT false // set to "true" if the on/off function is reversed + #define SPINDLE_LASER_PWM true // set to true if your controller supports setting the speed/power + #define SPINDLE_LASER_PWM_INVERT true // set to "true" if the speed/power goes up when you want it to go slower + #define SPINDLE_LASER_POWERUP_DELAY 5000 // delay in milliseconds to allow the spindle/laser to come up to speed/power + #define SPINDLE_LASER_POWERDOWN_DELAY 5000 // delay in milliseconds to allow the spindle to stop + #define SPINDLE_DIR_CHANGE true // set to true if your spindle controller supports changing spindle direction + #define SPINDLE_INVERT_DIR false + #define SPINDLE_STOP_ON_DIR_CHANGE true // set to true if Marlin should stop the spindle before changing rotation direction + + /** + * The M3 & M4 commands use the following equation to convert PWM duty cycle to speed/power + * + * SPEED/POWER = PWM duty cycle * SPEED_POWER_SLOPE + SPEED_POWER_INTERCEPT + * where PWM duty cycle varies from 0 to 255 + * + * set the following for your controller (ALL MUST BE SET) + */ + + #define SPEED_POWER_SLOPE 118.4 + #define SPEED_POWER_INTERCEPT 0 + #define SPEED_POWER_MIN 5000 + #define SPEED_POWER_MAX 30000 // SuperPID router controller 0 - 30,000 RPM + + //#define SPEED_POWER_SLOPE 0.3922 + //#define SPEED_POWER_INTERCEPT 0 + //#define SPEED_POWER_MIN 10 + //#define SPEED_POWER_MAX 100 // 0-100% +#endif + /** * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins */ diff --git a/Marlin/example_configurations/K8200/Configuration.h b/Marlin/example_configurations/K8200/Configuration.h index b999644c9..799a405ca 100644 --- a/Marlin/example_configurations/K8200/Configuration.h +++ b/Marlin/example_configurations/K8200/Configuration.h @@ -149,6 +149,8 @@ #define MACHINE_UUID "92f72de1-c211-452e-9f2b-61ef88a4751e" // K8200 standard config without VM8201 (Display) #endif +// @section extruder + // This defines the number of extruders // :[1, 2, 3, 4, 5] #define EXTRUDERS 1 @@ -192,6 +194,8 @@ //#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis //#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis +// @section machine + /** * Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN * diff --git a/Marlin/example_configurations/K8200/Configuration_adv.h b/Marlin/example_configurations/K8200/Configuration_adv.h index 7f5268d93..7ae8a9394 100644 --- a/Marlin/example_configurations/K8200/Configuration_adv.h +++ b/Marlin/example_configurations/K8200/Configuration_adv.h @@ -1138,6 +1138,55 @@ //#define EXPERIMENTAL_I2CBUS #define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave +// @section extras + +/** + * Spindle & Laser control + * + * Add the M3, M4, and M5 commands to turn the spindle/laser on and off, and + * to set spindle speed, spindle direction, and laser power. + * + * SuperPid is a router/spindle speed controller used in the CNC milling community. + * Marlin can be used to turn the spindle on and off. It can also be used to set + * the spindle speed from 5,000 to 30,000 RPM. + * + * You'll need to select a pin for the ON/OFF function and optionally choose a 0-5V + * hardware PWM pin for the speed control and a pin for the rotation direction. + * + * See http://marlinfw.org/docs/configuration/laser_spindle.html for more config details. + */ +//#define SPINDLE_LASER_ENABLE +#if ENABLED(SPINDLE_LASER_ENABLE) + + #define SPINDLE_LASER_ENABLE_INVERT false // set to "true" if the on/off function is reversed + #define SPINDLE_LASER_PWM true // set to true if your controller supports setting the speed/power + #define SPINDLE_LASER_PWM_INVERT true // set to "true" if the speed/power goes up when you want it to go slower + #define SPINDLE_LASER_POWERUP_DELAY 5000 // delay in milliseconds to allow the spindle/laser to come up to speed/power + #define SPINDLE_LASER_POWERDOWN_DELAY 5000 // delay in milliseconds to allow the spindle to stop + #define SPINDLE_DIR_CHANGE true // set to true if your spindle controller supports changing spindle direction + #define SPINDLE_INVERT_DIR false + #define SPINDLE_STOP_ON_DIR_CHANGE true // set to true if Marlin should stop the spindle before changing rotation direction + + /** + * The M3 & M4 commands use the following equation to convert PWM duty cycle to speed/power + * + * SPEED/POWER = PWM duty cycle * SPEED_POWER_SLOPE + SPEED_POWER_INTERCEPT + * where PWM duty cycle varies from 0 to 255 + * + * set the following for your controller (ALL MUST BE SET) + */ + + #define SPEED_POWER_SLOPE 118.4 + #define SPEED_POWER_INTERCEPT 0 + #define SPEED_POWER_MIN 5000 + #define SPEED_POWER_MAX 30000 // SuperPID router controller 0 - 30,000 RPM + + //#define SPEED_POWER_SLOPE 0.3922 + //#define SPEED_POWER_INTERCEPT 0 + //#define SPEED_POWER_MIN 10 + //#define SPEED_POWER_MAX 100 // 0-100% +#endif + /** * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins */ diff --git a/Marlin/example_configurations/K8400/Configuration.h b/Marlin/example_configurations/K8400/Configuration.h index e47c06ea0..f356ebd86 100644 --- a/Marlin/example_configurations/K8400/Configuration.h +++ b/Marlin/example_configurations/K8400/Configuration.h @@ -129,6 +129,8 @@ // You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4) //#define MACHINE_UUID "00000000-0000-0000-0000-000000000000" +// @section extruder + // This defines the number of extruders // :[1, 2, 3, 4, 5] #define EXTRUDERS 1 @@ -172,6 +174,8 @@ //#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis //#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis +// @section machine + /** * Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN * diff --git a/Marlin/example_configurations/K8400/Configuration_adv.h b/Marlin/example_configurations/K8400/Configuration_adv.h index 9ef3258f1..03e130a40 100644 --- a/Marlin/example_configurations/K8400/Configuration_adv.h +++ b/Marlin/example_configurations/K8400/Configuration_adv.h @@ -1125,6 +1125,55 @@ //#define EXPERIMENTAL_I2CBUS #define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave +// @section extras + +/** + * Spindle & Laser control + * + * Add the M3, M4, and M5 commands to turn the spindle/laser on and off, and + * to set spindle speed, spindle direction, and laser power. + * + * SuperPid is a router/spindle speed controller used in the CNC milling community. + * Marlin can be used to turn the spindle on and off. It can also be used to set + * the spindle speed from 5,000 to 30,000 RPM. + * + * You'll need to select a pin for the ON/OFF function and optionally choose a 0-5V + * hardware PWM pin for the speed control and a pin for the rotation direction. + * + * See http://marlinfw.org/docs/configuration/laser_spindle.html for more config details. + */ +//#define SPINDLE_LASER_ENABLE +#if ENABLED(SPINDLE_LASER_ENABLE) + + #define SPINDLE_LASER_ENABLE_INVERT false // set to "true" if the on/off function is reversed + #define SPINDLE_LASER_PWM true // set to true if your controller supports setting the speed/power + #define SPINDLE_LASER_PWM_INVERT true // set to "true" if the speed/power goes up when you want it to go slower + #define SPINDLE_LASER_POWERUP_DELAY 5000 // delay in milliseconds to allow the spindle/laser to come up to speed/power + #define SPINDLE_LASER_POWERDOWN_DELAY 5000 // delay in milliseconds to allow the spindle to stop + #define SPINDLE_DIR_CHANGE true // set to true if your spindle controller supports changing spindle direction + #define SPINDLE_INVERT_DIR false + #define SPINDLE_STOP_ON_DIR_CHANGE true // set to true if Marlin should stop the spindle before changing rotation direction + + /** + * The M3 & M4 commands use the following equation to convert PWM duty cycle to speed/power + * + * SPEED/POWER = PWM duty cycle * SPEED_POWER_SLOPE + SPEED_POWER_INTERCEPT + * where PWM duty cycle varies from 0 to 255 + * + * set the following for your controller (ALL MUST BE SET) + */ + + #define SPEED_POWER_SLOPE 118.4 + #define SPEED_POWER_INTERCEPT 0 + #define SPEED_POWER_MIN 5000 + #define SPEED_POWER_MAX 30000 // SuperPID router controller 0 - 30,000 RPM + + //#define SPEED_POWER_SLOPE 0.3922 + //#define SPEED_POWER_INTERCEPT 0 + //#define SPEED_POWER_MIN 10 + //#define SPEED_POWER_MAX 100 // 0-100% +#endif + /** * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins */ diff --git a/Marlin/example_configurations/K8400/Dual-head/Configuration.h b/Marlin/example_configurations/K8400/Dual-head/Configuration.h index 4f7951064..ddf10b4ef 100644 --- a/Marlin/example_configurations/K8400/Dual-head/Configuration.h +++ b/Marlin/example_configurations/K8400/Dual-head/Configuration.h @@ -129,6 +129,8 @@ // You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4) //#define MACHINE_UUID "00000000-0000-0000-0000-000000000000" +// @section extruder + // This defines the number of extruders // :[1, 2, 3, 4, 5] #define EXTRUDERS 2 @@ -172,6 +174,8 @@ //#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis //#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis +// @section machine + /** * Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN * diff --git a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h index e9c8c35b3..7b4b0e4b8 100644 --- a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h +++ b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h @@ -129,6 +129,8 @@ // You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4) //#define MACHINE_UUID "00000000-0000-0000-0000-000000000000" +// @section extruder + // This defines the number of extruders // :[1, 2, 3, 4, 5] #define EXTRUDERS 1 @@ -172,6 +174,8 @@ //#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis //#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis +// @section machine + /** * Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN * diff --git a/Marlin/example_configurations/RigidBot/Configuration.h b/Marlin/example_configurations/RigidBot/Configuration.h index ca717eebd..476f5caa8 100644 --- a/Marlin/example_configurations/RigidBot/Configuration.h +++ b/Marlin/example_configurations/RigidBot/Configuration.h @@ -132,6 +132,8 @@ // You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4) //#define MACHINE_UUID "00000000-0000-0000-0000-000000000000" +// @section extruder + // This defines the number of extruders // :[1, 2, 3, 4, 5] #define EXTRUDERS 1 // Single extruder. Set to 2 for dual extruders @@ -175,6 +177,8 @@ #define HOTEND_OFFSET_X {0.0, 36.00} // (in mm) for each extruder, offset of the hotend on the X axis #define HOTEND_OFFSET_Y {0.0, 0.00} // (in mm) for each extruder, offset of the hotend on the Y axis +// @section machine + /** * Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN * diff --git a/Marlin/example_configurations/RigidBot/Configuration_adv.h b/Marlin/example_configurations/RigidBot/Configuration_adv.h index 3d6483b26..4b82cbe35 100644 --- a/Marlin/example_configurations/RigidBot/Configuration_adv.h +++ b/Marlin/example_configurations/RigidBot/Configuration_adv.h @@ -1125,6 +1125,55 @@ //#define EXPERIMENTAL_I2CBUS #define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave +// @section extras + +/** + * Spindle & Laser control + * + * Add the M3, M4, and M5 commands to turn the spindle/laser on and off, and + * to set spindle speed, spindle direction, and laser power. + * + * SuperPid is a router/spindle speed controller used in the CNC milling community. + * Marlin can be used to turn the spindle on and off. It can also be used to set + * the spindle speed from 5,000 to 30,000 RPM. + * + * You'll need to select a pin for the ON/OFF function and optionally choose a 0-5V + * hardware PWM pin for the speed control and a pin for the rotation direction. + * + * See http://marlinfw.org/docs/configuration/laser_spindle.html for more config details. + */ +//#define SPINDLE_LASER_ENABLE +#if ENABLED(SPINDLE_LASER_ENABLE) + + #define SPINDLE_LASER_ENABLE_INVERT false // set to "true" if the on/off function is reversed + #define SPINDLE_LASER_PWM true // set to true if your controller supports setting the speed/power + #define SPINDLE_LASER_PWM_INVERT true // set to "true" if the speed/power goes up when you want it to go slower + #define SPINDLE_LASER_POWERUP_DELAY 5000 // delay in milliseconds to allow the spindle/laser to come up to speed/power + #define SPINDLE_LASER_POWERDOWN_DELAY 5000 // delay in milliseconds to allow the spindle to stop + #define SPINDLE_DIR_CHANGE true // set to true if your spindle controller supports changing spindle direction + #define SPINDLE_INVERT_DIR false + #define SPINDLE_STOP_ON_DIR_CHANGE true // set to true if Marlin should stop the spindle before changing rotation direction + + /** + * The M3 & M4 commands use the following equation to convert PWM duty cycle to speed/power + * + * SPEED/POWER = PWM duty cycle * SPEED_POWER_SLOPE + SPEED_POWER_INTERCEPT + * where PWM duty cycle varies from 0 to 255 + * + * set the following for your controller (ALL MUST BE SET) + */ + + #define SPEED_POWER_SLOPE 118.4 + #define SPEED_POWER_INTERCEPT 0 + #define SPEED_POWER_MIN 5000 + #define SPEED_POWER_MAX 30000 // SuperPID router controller 0 - 30,000 RPM + + //#define SPEED_POWER_SLOPE 0.3922 + //#define SPEED_POWER_INTERCEPT 0 + //#define SPEED_POWER_MIN 10 + //#define SPEED_POWER_MAX 100 // 0-100% +#endif + /** * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins */ diff --git a/Marlin/example_configurations/SCARA/Configuration.h b/Marlin/example_configurations/SCARA/Configuration.h index b0a96106c..a1f59cbcb 100644 --- a/Marlin/example_configurations/SCARA/Configuration.h +++ b/Marlin/example_configurations/SCARA/Configuration.h @@ -162,6 +162,8 @@ // You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4) //#define MACHINE_UUID "00000000-0000-0000-0000-000000000000" +// @section extruder + // This defines the number of extruders // :[1, 2, 3, 4, 5] #define EXTRUDERS 1 @@ -205,6 +207,8 @@ //#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis //#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis +// @section machine + /** * Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN * diff --git a/Marlin/example_configurations/SCARA/Configuration_adv.h b/Marlin/example_configurations/SCARA/Configuration_adv.h index 9f6d22b2d..2ace54433 100644 --- a/Marlin/example_configurations/SCARA/Configuration_adv.h +++ b/Marlin/example_configurations/SCARA/Configuration_adv.h @@ -1125,6 +1125,55 @@ //#define EXPERIMENTAL_I2CBUS #define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave +// @section extras + +/** + * Spindle & Laser control + * + * Add the M3, M4, and M5 commands to turn the spindle/laser on and off, and + * to set spindle speed, spindle direction, and laser power. + * + * SuperPid is a router/spindle speed controller used in the CNC milling community. + * Marlin can be used to turn the spindle on and off. It can also be used to set + * the spindle speed from 5,000 to 30,000 RPM. + * + * You'll need to select a pin for the ON/OFF function and optionally choose a 0-5V + * hardware PWM pin for the speed control and a pin for the rotation direction. + * + * See http://marlinfw.org/docs/configuration/laser_spindle.html for more config details. + */ +//#define SPINDLE_LASER_ENABLE +#if ENABLED(SPINDLE_LASER_ENABLE) + + #define SPINDLE_LASER_ENABLE_INVERT false // set to "true" if the on/off function is reversed + #define SPINDLE_LASER_PWM true // set to true if your controller supports setting the speed/power + #define SPINDLE_LASER_PWM_INVERT true // set to "true" if the speed/power goes up when you want it to go slower + #define SPINDLE_LASER_POWERUP_DELAY 5000 // delay in milliseconds to allow the spindle/laser to come up to speed/power + #define SPINDLE_LASER_POWERDOWN_DELAY 5000 // delay in milliseconds to allow the spindle to stop + #define SPINDLE_DIR_CHANGE true // set to true if your spindle controller supports changing spindle direction + #define SPINDLE_INVERT_DIR false + #define SPINDLE_STOP_ON_DIR_CHANGE true // set to true if Marlin should stop the spindle before changing rotation direction + + /** + * The M3 & M4 commands use the following equation to convert PWM duty cycle to speed/power + * + * SPEED/POWER = PWM duty cycle * SPEED_POWER_SLOPE + SPEED_POWER_INTERCEPT + * where PWM duty cycle varies from 0 to 255 + * + * set the following for your controller (ALL MUST BE SET) + */ + + #define SPEED_POWER_SLOPE 118.4 + #define SPEED_POWER_INTERCEPT 0 + #define SPEED_POWER_MIN 5000 + #define SPEED_POWER_MAX 30000 // SuperPID router controller 0 - 30,000 RPM + + //#define SPEED_POWER_SLOPE 0.3922 + //#define SPEED_POWER_INTERCEPT 0 + //#define SPEED_POWER_MIN 10 + //#define SPEED_POWER_MAX 100 // 0-100% +#endif + /** * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins */ diff --git a/Marlin/example_configurations/TAZ4/Configuration.h b/Marlin/example_configurations/TAZ4/Configuration.h index cf4b46a44..c5af5592a 100644 --- a/Marlin/example_configurations/TAZ4/Configuration.h +++ b/Marlin/example_configurations/TAZ4/Configuration.h @@ -129,6 +129,8 @@ // You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4) //#define MACHINE_UUID "00000000-0000-0000-0000-000000000000" +// @section extruder + // This defines the number of extruders // :[1, 2, 3, 4, 5] #define EXTRUDERS 1 @@ -172,6 +174,8 @@ //#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis //#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis +// @section machine + /** * Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN * diff --git a/Marlin/example_configurations/TAZ4/Configuration_adv.h b/Marlin/example_configurations/TAZ4/Configuration_adv.h index 8c510aab9..ab8ddc908 100644 --- a/Marlin/example_configurations/TAZ4/Configuration_adv.h +++ b/Marlin/example_configurations/TAZ4/Configuration_adv.h @@ -1125,6 +1125,55 @@ //#define EXPERIMENTAL_I2CBUS #define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave +// @section extras + +/** + * Spindle & Laser control + * + * Add the M3, M4, and M5 commands to turn the spindle/laser on and off, and + * to set spindle speed, spindle direction, and laser power. + * + * SuperPid is a router/spindle speed controller used in the CNC milling community. + * Marlin can be used to turn the spindle on and off. It can also be used to set + * the spindle speed from 5,000 to 30,000 RPM. + * + * You'll need to select a pin for the ON/OFF function and optionally choose a 0-5V + * hardware PWM pin for the speed control and a pin for the rotation direction. + * + * See http://marlinfw.org/docs/configuration/laser_spindle.html for more config details. + */ +//#define SPINDLE_LASER_ENABLE +#if ENABLED(SPINDLE_LASER_ENABLE) + + #define SPINDLE_LASER_ENABLE_INVERT false // set to "true" if the on/off function is reversed + #define SPINDLE_LASER_PWM true // set to true if your controller supports setting the speed/power + #define SPINDLE_LASER_PWM_INVERT true // set to "true" if the speed/power goes up when you want it to go slower + #define SPINDLE_LASER_POWERUP_DELAY 5000 // delay in milliseconds to allow the spindle/laser to come up to speed/power + #define SPINDLE_LASER_POWERDOWN_DELAY 5000 // delay in milliseconds to allow the spindle to stop + #define SPINDLE_DIR_CHANGE true // set to true if your spindle controller supports changing spindle direction + #define SPINDLE_INVERT_DIR false + #define SPINDLE_STOP_ON_DIR_CHANGE true // set to true if Marlin should stop the spindle before changing rotation direction + + /** + * The M3 & M4 commands use the following equation to convert PWM duty cycle to speed/power + * + * SPEED/POWER = PWM duty cycle * SPEED_POWER_SLOPE + SPEED_POWER_INTERCEPT + * where PWM duty cycle varies from 0 to 255 + * + * set the following for your controller (ALL MUST BE SET) + */ + + #define SPEED_POWER_SLOPE 118.4 + #define SPEED_POWER_INTERCEPT 0 + #define SPEED_POWER_MIN 5000 + #define SPEED_POWER_MAX 30000 // SuperPID router controller 0 - 30,000 RPM + + //#define SPEED_POWER_SLOPE 0.3922 + //#define SPEED_POWER_INTERCEPT 0 + //#define SPEED_POWER_MIN 10 + //#define SPEED_POWER_MAX 100 // 0-100% +#endif + /** * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins */ diff --git a/Marlin/example_configurations/TinyBoy2/Configuration.h b/Marlin/example_configurations/TinyBoy2/Configuration.h index d92556dcc..b93b90d0d 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration.h @@ -151,6 +151,8 @@ // You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4) //#define MACHINE_UUID "00000000-0000-0000-0000-000000000000" +// @section extruder + // This defines the number of extruders // :[1, 2, 3, 4, 5] #define EXTRUDERS 1 @@ -194,6 +196,8 @@ //#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis //#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis +// @section machine + /** * Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN * diff --git a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h index ee78175bc..7e714b359 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h @@ -1128,6 +1128,55 @@ //#define EXPERIMENTAL_I2CBUS #define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave +// @section extras + +/** + * Spindle & Laser control + * + * Add the M3, M4, and M5 commands to turn the spindle/laser on and off, and + * to set spindle speed, spindle direction, and laser power. + * + * SuperPid is a router/spindle speed controller used in the CNC milling community. + * Marlin can be used to turn the spindle on and off. It can also be used to set + * the spindle speed from 5,000 to 30,000 RPM. + * + * You'll need to select a pin for the ON/OFF function and optionally choose a 0-5V + * hardware PWM pin for the speed control and a pin for the rotation direction. + * + * See http://marlinfw.org/docs/configuration/laser_spindle.html for more config details. + */ +//#define SPINDLE_LASER_ENABLE +#if ENABLED(SPINDLE_LASER_ENABLE) + + #define SPINDLE_LASER_ENABLE_INVERT false // set to "true" if the on/off function is reversed + #define SPINDLE_LASER_PWM true // set to true if your controller supports setting the speed/power + #define SPINDLE_LASER_PWM_INVERT true // set to "true" if the speed/power goes up when you want it to go slower + #define SPINDLE_LASER_POWERUP_DELAY 5000 // delay in milliseconds to allow the spindle/laser to come up to speed/power + #define SPINDLE_LASER_POWERDOWN_DELAY 5000 // delay in milliseconds to allow the spindle to stop + #define SPINDLE_DIR_CHANGE true // set to true if your spindle controller supports changing spindle direction + #define SPINDLE_INVERT_DIR false + #define SPINDLE_STOP_ON_DIR_CHANGE true // set to true if Marlin should stop the spindle before changing rotation direction + + /** + * The M3 & M4 commands use the following equation to convert PWM duty cycle to speed/power + * + * SPEED/POWER = PWM duty cycle * SPEED_POWER_SLOPE + SPEED_POWER_INTERCEPT + * where PWM duty cycle varies from 0 to 255 + * + * set the following for your controller (ALL MUST BE SET) + */ + + #define SPEED_POWER_SLOPE 118.4 + #define SPEED_POWER_INTERCEPT 0 + #define SPEED_POWER_MIN 5000 + #define SPEED_POWER_MAX 30000 // SuperPID router controller 0 - 30,000 RPM + + //#define SPEED_POWER_SLOPE 0.3922 + //#define SPEED_POWER_INTERCEPT 0 + //#define SPEED_POWER_MIN 10 + //#define SPEED_POWER_MAX 100 // 0-100% +#endif + /** * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins */ diff --git a/Marlin/example_configurations/WITBOX/Configuration.h b/Marlin/example_configurations/WITBOX/Configuration.h index 073dafe00..3dcf34e70 100644 --- a/Marlin/example_configurations/WITBOX/Configuration.h +++ b/Marlin/example_configurations/WITBOX/Configuration.h @@ -132,6 +132,8 @@ // You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4) //#define MACHINE_UUID "00000000-0000-0000-0000-000000000000" +// @section extruder + // This defines the number of extruders // :[1, 2, 3, 4, 5] #define EXTRUDERS 1 @@ -175,6 +177,8 @@ //#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis //#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis +// @section machine + /** * Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN * diff --git a/Marlin/example_configurations/WITBOX/Configuration_adv.h b/Marlin/example_configurations/WITBOX/Configuration_adv.h index 798d74177..903b1ab79 100644 --- a/Marlin/example_configurations/WITBOX/Configuration_adv.h +++ b/Marlin/example_configurations/WITBOX/Configuration_adv.h @@ -1125,6 +1125,55 @@ //#define EXPERIMENTAL_I2CBUS #define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave +// @section extras + +/** + * Spindle & Laser control + * + * Add the M3, M4, and M5 commands to turn the spindle/laser on and off, and + * to set spindle speed, spindle direction, and laser power. + * + * SuperPid is a router/spindle speed controller used in the CNC milling community. + * Marlin can be used to turn the spindle on and off. It can also be used to set + * the spindle speed from 5,000 to 30,000 RPM. + * + * You'll need to select a pin for the ON/OFF function and optionally choose a 0-5V + * hardware PWM pin for the speed control and a pin for the rotation direction. + * + * See http://marlinfw.org/docs/configuration/laser_spindle.html for more config details. + */ +//#define SPINDLE_LASER_ENABLE +#if ENABLED(SPINDLE_LASER_ENABLE) + + #define SPINDLE_LASER_ENABLE_INVERT false // set to "true" if the on/off function is reversed + #define SPINDLE_LASER_PWM true // set to true if your controller supports setting the speed/power + #define SPINDLE_LASER_PWM_INVERT true // set to "true" if the speed/power goes up when you want it to go slower + #define SPINDLE_LASER_POWERUP_DELAY 5000 // delay in milliseconds to allow the spindle/laser to come up to speed/power + #define SPINDLE_LASER_POWERDOWN_DELAY 5000 // delay in milliseconds to allow the spindle to stop + #define SPINDLE_DIR_CHANGE true // set to true if your spindle controller supports changing spindle direction + #define SPINDLE_INVERT_DIR false + #define SPINDLE_STOP_ON_DIR_CHANGE true // set to true if Marlin should stop the spindle before changing rotation direction + + /** + * The M3 & M4 commands use the following equation to convert PWM duty cycle to speed/power + * + * SPEED/POWER = PWM duty cycle * SPEED_POWER_SLOPE + SPEED_POWER_INTERCEPT + * where PWM duty cycle varies from 0 to 255 + * + * set the following for your controller (ALL MUST BE SET) + */ + + #define SPEED_POWER_SLOPE 118.4 + #define SPEED_POWER_INTERCEPT 0 + #define SPEED_POWER_MIN 5000 + #define SPEED_POWER_MAX 30000 // SuperPID router controller 0 - 30,000 RPM + + //#define SPEED_POWER_SLOPE 0.3922 + //#define SPEED_POWER_INTERCEPT 0 + //#define SPEED_POWER_MIN 10 + //#define SPEED_POWER_MAX 100 // 0-100% +#endif + /** * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins */ diff --git a/Marlin/example_configurations/adafruit/ST7565/Configuration.h b/Marlin/example_configurations/adafruit/ST7565/Configuration.h index d9bbb2b25..3b9f667d8 100644 --- a/Marlin/example_configurations/adafruit/ST7565/Configuration.h +++ b/Marlin/example_configurations/adafruit/ST7565/Configuration.h @@ -129,6 +129,8 @@ // You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4) //#define MACHINE_UUID "00000000-0000-0000-0000-000000000000" +// @section extruder + // This defines the number of extruders // :[1, 2, 3, 4, 5] #define EXTRUDERS 1 @@ -172,6 +174,8 @@ //#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis //#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis +// @section machine + /** * Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN * diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h index 1e94e31b4..2c31e0226 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h @@ -129,6 +129,8 @@ // You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4) //#define MACHINE_UUID "00000000-0000-0000-0000-000000000000" +// @section extruder + // This defines the number of extruders // :[1, 2, 3, 4, 5] #define EXTRUDERS 1 @@ -172,6 +174,8 @@ //#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis //#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis +// @section machine + /** * Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN * diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h index 010a1989d..3f1f4db53 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h @@ -1130,6 +1130,55 @@ //#define EXPERIMENTAL_I2CBUS #define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave +// @section extras + +/** + * Spindle & Laser control + * + * Add the M3, M4, and M5 commands to turn the spindle/laser on and off, and + * to set spindle speed, spindle direction, and laser power. + * + * SuperPid is a router/spindle speed controller used in the CNC milling community. + * Marlin can be used to turn the spindle on and off. It can also be used to set + * the spindle speed from 5,000 to 30,000 RPM. + * + * You'll need to select a pin for the ON/OFF function and optionally choose a 0-5V + * hardware PWM pin for the speed control and a pin for the rotation direction. + * + * See http://marlinfw.org/docs/configuration/laser_spindle.html for more config details. + */ +//#define SPINDLE_LASER_ENABLE +#if ENABLED(SPINDLE_LASER_ENABLE) + + #define SPINDLE_LASER_ENABLE_INVERT false // set to "true" if the on/off function is reversed + #define SPINDLE_LASER_PWM true // set to true if your controller supports setting the speed/power + #define SPINDLE_LASER_PWM_INVERT true // set to "true" if the speed/power goes up when you want it to go slower + #define SPINDLE_LASER_POWERUP_DELAY 5000 // delay in milliseconds to allow the spindle/laser to come up to speed/power + #define SPINDLE_LASER_POWERDOWN_DELAY 5000 // delay in milliseconds to allow the spindle to stop + #define SPINDLE_DIR_CHANGE true // set to true if your spindle controller supports changing spindle direction + #define SPINDLE_INVERT_DIR false + #define SPINDLE_STOP_ON_DIR_CHANGE true // set to true if Marlin should stop the spindle before changing rotation direction + + /** + * The M3 & M4 commands use the following equation to convert PWM duty cycle to speed/power + * + * SPEED/POWER = PWM duty cycle * SPEED_POWER_SLOPE + SPEED_POWER_INTERCEPT + * where PWM duty cycle varies from 0 to 255 + * + * set the following for your controller (ALL MUST BE SET) + */ + + #define SPEED_POWER_SLOPE 118.4 + #define SPEED_POWER_INTERCEPT 0 + #define SPEED_POWER_MIN 5000 + #define SPEED_POWER_MAX 30000 // SuperPID router controller 0 - 30,000 RPM + + //#define SPEED_POWER_SLOPE 0.3922 + //#define SPEED_POWER_INTERCEPT 0 + //#define SPEED_POWER_MIN 10 + //#define SPEED_POWER_MAX 100 // 0-100% +#endif + /** * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins */ diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h index 8ec27db5b..ce585c1af 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h @@ -129,6 +129,8 @@ // You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4) //#define MACHINE_UUID "00000000-0000-0000-0000-000000000000" +// @section extruder + // This defines the number of extruders // :[1, 2, 3, 4, 5] #define EXTRUDERS 1 @@ -172,6 +174,8 @@ //#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis //#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis +// @section machine + /** * Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN * diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h index b3f183a31..4234c831a 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h @@ -1129,6 +1129,55 @@ //#define EXPERIMENTAL_I2CBUS #define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave +// @section extras + +/** + * Spindle & Laser control + * + * Add the M3, M4, and M5 commands to turn the spindle/laser on and off, and + * to set spindle speed, spindle direction, and laser power. + * + * SuperPid is a router/spindle speed controller used in the CNC milling community. + * Marlin can be used to turn the spindle on and off. It can also be used to set + * the spindle speed from 5,000 to 30,000 RPM. + * + * You'll need to select a pin for the ON/OFF function and optionally choose a 0-5V + * hardware PWM pin for the speed control and a pin for the rotation direction. + * + * See http://marlinfw.org/docs/configuration/laser_spindle.html for more config details. + */ +//#define SPINDLE_LASER_ENABLE +#if ENABLED(SPINDLE_LASER_ENABLE) + + #define SPINDLE_LASER_ENABLE_INVERT false // set to "true" if the on/off function is reversed + #define SPINDLE_LASER_PWM true // set to true if your controller supports setting the speed/power + #define SPINDLE_LASER_PWM_INVERT true // set to "true" if the speed/power goes up when you want it to go slower + #define SPINDLE_LASER_POWERUP_DELAY 5000 // delay in milliseconds to allow the spindle/laser to come up to speed/power + #define SPINDLE_LASER_POWERDOWN_DELAY 5000 // delay in milliseconds to allow the spindle to stop + #define SPINDLE_DIR_CHANGE true // set to true if your spindle controller supports changing spindle direction + #define SPINDLE_INVERT_DIR false + #define SPINDLE_STOP_ON_DIR_CHANGE true // set to true if Marlin should stop the spindle before changing rotation direction + + /** + * The M3 & M4 commands use the following equation to convert PWM duty cycle to speed/power + * + * SPEED/POWER = PWM duty cycle * SPEED_POWER_SLOPE + SPEED_POWER_INTERCEPT + * where PWM duty cycle varies from 0 to 255 + * + * set the following for your controller (ALL MUST BE SET) + */ + + #define SPEED_POWER_SLOPE 118.4 + #define SPEED_POWER_INTERCEPT 0 + #define SPEED_POWER_MIN 5000 + #define SPEED_POWER_MAX 30000 // SuperPID router controller 0 - 30,000 RPM + + //#define SPEED_POWER_SLOPE 0.3922 + //#define SPEED_POWER_INTERCEPT 0 + //#define SPEED_POWER_MIN 10 + //#define SPEED_POWER_MAX 100 // 0-100% +#endif + /** * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins */ diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index 83776fa7f..0b942adba 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -129,6 +129,8 @@ // You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4) //#define MACHINE_UUID "00000000-0000-0000-0000-000000000000" +// @section extruder + // This defines the number of extruders // :[1, 2, 3, 4, 5] #define EXTRUDERS 1 @@ -172,6 +174,8 @@ //#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis //#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis +// @section machine + /** * Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN * diff --git a/Marlin/example_configurations/delta/generic/Configuration_adv.h b/Marlin/example_configurations/delta/generic/Configuration_adv.h index deb74b6d6..295b82b0d 100644 --- a/Marlin/example_configurations/delta/generic/Configuration_adv.h +++ b/Marlin/example_configurations/delta/generic/Configuration_adv.h @@ -1127,6 +1127,55 @@ //#define EXPERIMENTAL_I2CBUS #define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave +// @section extras + +/** + * Spindle & Laser control + * + * Add the M3, M4, and M5 commands to turn the spindle/laser on and off, and + * to set spindle speed, spindle direction, and laser power. + * + * SuperPid is a router/spindle speed controller used in the CNC milling community. + * Marlin can be used to turn the spindle on and off. It can also be used to set + * the spindle speed from 5,000 to 30,000 RPM. + * + * You'll need to select a pin for the ON/OFF function and optionally choose a 0-5V + * hardware PWM pin for the speed control and a pin for the rotation direction. + * + * See http://marlinfw.org/docs/configuration/laser_spindle.html for more config details. + */ +//#define SPINDLE_LASER_ENABLE +#if ENABLED(SPINDLE_LASER_ENABLE) + + #define SPINDLE_LASER_ENABLE_INVERT false // set to "true" if the on/off function is reversed + #define SPINDLE_LASER_PWM true // set to true if your controller supports setting the speed/power + #define SPINDLE_LASER_PWM_INVERT true // set to "true" if the speed/power goes up when you want it to go slower + #define SPINDLE_LASER_POWERUP_DELAY 5000 // delay in milliseconds to allow the spindle/laser to come up to speed/power + #define SPINDLE_LASER_POWERDOWN_DELAY 5000 // delay in milliseconds to allow the spindle to stop + #define SPINDLE_DIR_CHANGE true // set to true if your spindle controller supports changing spindle direction + #define SPINDLE_INVERT_DIR false + #define SPINDLE_STOP_ON_DIR_CHANGE true // set to true if Marlin should stop the spindle before changing rotation direction + + /** + * The M3 & M4 commands use the following equation to convert PWM duty cycle to speed/power + * + * SPEED/POWER = PWM duty cycle * SPEED_POWER_SLOPE + SPEED_POWER_INTERCEPT + * where PWM duty cycle varies from 0 to 255 + * + * set the following for your controller (ALL MUST BE SET) + */ + + #define SPEED_POWER_SLOPE 118.4 + #define SPEED_POWER_INTERCEPT 0 + #define SPEED_POWER_MIN 5000 + #define SPEED_POWER_MAX 30000 // SuperPID router controller 0 - 30,000 RPM + + //#define SPEED_POWER_SLOPE 0.3922 + //#define SPEED_POWER_INTERCEPT 0 + //#define SPEED_POWER_MIN 10 + //#define SPEED_POWER_MAX 100 // 0-100% +#endif + /** * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins */ diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index b8e7fc5ff..3c9fff7d6 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -129,6 +129,8 @@ // You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4) //#define MACHINE_UUID "00000000-0000-0000-0000-000000000000" +// @section extruder + // This defines the number of extruders // :[1, 2, 3, 4, 5] #define EXTRUDERS 1 @@ -172,6 +174,8 @@ //#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis //#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis +// @section machine + /** * Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN * diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h index deb74b6d6..295b82b0d 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h @@ -1127,6 +1127,55 @@ //#define EXPERIMENTAL_I2CBUS #define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave +// @section extras + +/** + * Spindle & Laser control + * + * Add the M3, M4, and M5 commands to turn the spindle/laser on and off, and + * to set spindle speed, spindle direction, and laser power. + * + * SuperPid is a router/spindle speed controller used in the CNC milling community. + * Marlin can be used to turn the spindle on and off. It can also be used to set + * the spindle speed from 5,000 to 30,000 RPM. + * + * You'll need to select a pin for the ON/OFF function and optionally choose a 0-5V + * hardware PWM pin for the speed control and a pin for the rotation direction. + * + * See http://marlinfw.org/docs/configuration/laser_spindle.html for more config details. + */ +//#define SPINDLE_LASER_ENABLE +#if ENABLED(SPINDLE_LASER_ENABLE) + + #define SPINDLE_LASER_ENABLE_INVERT false // set to "true" if the on/off function is reversed + #define SPINDLE_LASER_PWM true // set to true if your controller supports setting the speed/power + #define SPINDLE_LASER_PWM_INVERT true // set to "true" if the speed/power goes up when you want it to go slower + #define SPINDLE_LASER_POWERUP_DELAY 5000 // delay in milliseconds to allow the spindle/laser to come up to speed/power + #define SPINDLE_LASER_POWERDOWN_DELAY 5000 // delay in milliseconds to allow the spindle to stop + #define SPINDLE_DIR_CHANGE true // set to true if your spindle controller supports changing spindle direction + #define SPINDLE_INVERT_DIR false + #define SPINDLE_STOP_ON_DIR_CHANGE true // set to true if Marlin should stop the spindle before changing rotation direction + + /** + * The M3 & M4 commands use the following equation to convert PWM duty cycle to speed/power + * + * SPEED/POWER = PWM duty cycle * SPEED_POWER_SLOPE + SPEED_POWER_INTERCEPT + * where PWM duty cycle varies from 0 to 255 + * + * set the following for your controller (ALL MUST BE SET) + */ + + #define SPEED_POWER_SLOPE 118.4 + #define SPEED_POWER_INTERCEPT 0 + #define SPEED_POWER_MIN 5000 + #define SPEED_POWER_MAX 30000 // SuperPID router controller 0 - 30,000 RPM + + //#define SPEED_POWER_SLOPE 0.3922 + //#define SPEED_POWER_INTERCEPT 0 + //#define SPEED_POWER_MIN 10 + //#define SPEED_POWER_MAX 100 // 0-100% +#endif + /** * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins */ diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration.h b/Marlin/example_configurations/delta/kossel_pro/Configuration.h index 3e6020195..6e672402a 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration.h @@ -133,6 +133,8 @@ // You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4) //#define MACHINE_UUID "00000000-0000-0000-0000-000000000000" +// @section extruder + // This defines the number of extruders // :[1, 2, 3, 4, 5] #define EXTRUDERS 1 @@ -176,6 +178,8 @@ //#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis //#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis +// @section machine + /** * Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN * diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h index 8bb8f312a..dc0a77bdb 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h @@ -1132,6 +1132,55 @@ //#define EXPERIMENTAL_I2CBUS #define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave +// @section extras + +/** + * Spindle & Laser control + * + * Add the M3, M4, and M5 commands to turn the spindle/laser on and off, and + * to set spindle speed, spindle direction, and laser power. + * + * SuperPid is a router/spindle speed controller used in the CNC milling community. + * Marlin can be used to turn the spindle on and off. It can also be used to set + * the spindle speed from 5,000 to 30,000 RPM. + * + * You'll need to select a pin for the ON/OFF function and optionally choose a 0-5V + * hardware PWM pin for the speed control and a pin for the rotation direction. + * + * See http://marlinfw.org/docs/configuration/laser_spindle.html for more config details. + */ +//#define SPINDLE_LASER_ENABLE +#if ENABLED(SPINDLE_LASER_ENABLE) + + #define SPINDLE_LASER_ENABLE_INVERT false // set to "true" if the on/off function is reversed + #define SPINDLE_LASER_PWM true // set to true if your controller supports setting the speed/power + #define SPINDLE_LASER_PWM_INVERT true // set to "true" if the speed/power goes up when you want it to go slower + #define SPINDLE_LASER_POWERUP_DELAY 5000 // delay in milliseconds to allow the spindle/laser to come up to speed/power + #define SPINDLE_LASER_POWERDOWN_DELAY 5000 // delay in milliseconds to allow the spindle to stop + #define SPINDLE_DIR_CHANGE true // set to true if your spindle controller supports changing spindle direction + #define SPINDLE_INVERT_DIR false + #define SPINDLE_STOP_ON_DIR_CHANGE true // set to true if Marlin should stop the spindle before changing rotation direction + + /** + * The M3 & M4 commands use the following equation to convert PWM duty cycle to speed/power + * + * SPEED/POWER = PWM duty cycle * SPEED_POWER_SLOPE + SPEED_POWER_INTERCEPT + * where PWM duty cycle varies from 0 to 255 + * + * set the following for your controller (ALL MUST BE SET) + */ + + #define SPEED_POWER_SLOPE 118.4 + #define SPEED_POWER_INTERCEPT 0 + #define SPEED_POWER_MIN 5000 + #define SPEED_POWER_MAX 30000 // SuperPID router controller 0 - 30,000 RPM + + //#define SPEED_POWER_SLOPE 0.3922 + //#define SPEED_POWER_INTERCEPT 0 + //#define SPEED_POWER_MIN 10 + //#define SPEED_POWER_MAX 100 // 0-100% +#endif + /** * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins */ diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration.h b/Marlin/example_configurations/delta/kossel_xl/Configuration.h index 4ecc7be43..62f9bafb5 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration.h @@ -129,6 +129,8 @@ // You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4) //#define MACHINE_UUID "00000000-0000-0000-0000-000000000000" +// @section extruder + // This defines the number of extruders // :[1, 2, 3, 4, 5] #define EXTRUDERS 1 @@ -172,6 +174,8 @@ //#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis //#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis +// @section machine + /** * Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN * diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h index aad4304e5..5f73c52f2 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h @@ -1127,6 +1127,55 @@ //#define EXPERIMENTAL_I2CBUS #define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave +// @section extras + +/** + * Spindle & Laser control + * + * Add the M3, M4, and M5 commands to turn the spindle/laser on and off, and + * to set spindle speed, spindle direction, and laser power. + * + * SuperPid is a router/spindle speed controller used in the CNC milling community. + * Marlin can be used to turn the spindle on and off. It can also be used to set + * the spindle speed from 5,000 to 30,000 RPM. + * + * You'll need to select a pin for the ON/OFF function and optionally choose a 0-5V + * hardware PWM pin for the speed control and a pin for the rotation direction. + * + * See http://marlinfw.org/docs/configuration/laser_spindle.html for more config details. + */ +//#define SPINDLE_LASER_ENABLE +#if ENABLED(SPINDLE_LASER_ENABLE) + + #define SPINDLE_LASER_ENABLE_INVERT false // set to "true" if the on/off function is reversed + #define SPINDLE_LASER_PWM true // set to true if your controller supports setting the speed/power + #define SPINDLE_LASER_PWM_INVERT true // set to "true" if the speed/power goes up when you want it to go slower + #define SPINDLE_LASER_POWERUP_DELAY 5000 // delay in milliseconds to allow the spindle/laser to come up to speed/power + #define SPINDLE_LASER_POWERDOWN_DELAY 5000 // delay in milliseconds to allow the spindle to stop + #define SPINDLE_DIR_CHANGE true // set to true if your spindle controller supports changing spindle direction + #define SPINDLE_INVERT_DIR false + #define SPINDLE_STOP_ON_DIR_CHANGE true // set to true if Marlin should stop the spindle before changing rotation direction + + /** + * The M3 & M4 commands use the following equation to convert PWM duty cycle to speed/power + * + * SPEED/POWER = PWM duty cycle * SPEED_POWER_SLOPE + SPEED_POWER_INTERCEPT + * where PWM duty cycle varies from 0 to 255 + * + * set the following for your controller (ALL MUST BE SET) + */ + + #define SPEED_POWER_SLOPE 118.4 + #define SPEED_POWER_INTERCEPT 0 + #define SPEED_POWER_MIN 5000 + #define SPEED_POWER_MAX 30000 // SuperPID router controller 0 - 30,000 RPM + + //#define SPEED_POWER_SLOPE 0.3922 + //#define SPEED_POWER_INTERCEPT 0 + //#define SPEED_POWER_MIN 10 + //#define SPEED_POWER_MAX 100 // 0-100% +#endif + /** * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins */ diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h index 627130230..776b9e9dd 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h @@ -134,6 +134,8 @@ // You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4) //#define MACHINE_UUID "00000000-0000-0000-0000-000000000000" +// @section extruder + // This defines the number of extruders // :[1, 2, 3, 4, 5] #define EXTRUDERS 1 @@ -177,6 +179,8 @@ //#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis //#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis +// @section machine + /** * Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN * diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h index 52bc16cbc..1bf2b69c5 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h @@ -1132,6 +1132,55 @@ //#define EXPERIMENTAL_I2CBUS #define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave +// @section extras + +/** + * Spindle & Laser control + * + * Add the M3, M4, and M5 commands to turn the spindle/laser on and off, and + * to set spindle speed, spindle direction, and laser power. + * + * SuperPid is a router/spindle speed controller used in the CNC milling community. + * Marlin can be used to turn the spindle on and off. It can also be used to set + * the spindle speed from 5,000 to 30,000 RPM. + * + * You'll need to select a pin for the ON/OFF function and optionally choose a 0-5V + * hardware PWM pin for the speed control and a pin for the rotation direction. + * + * See http://marlinfw.org/docs/configuration/laser_spindle.html for more config details. + */ +//#define SPINDLE_LASER_ENABLE +#if ENABLED(SPINDLE_LASER_ENABLE) + + #define SPINDLE_LASER_ENABLE_INVERT false // set to "true" if the on/off function is reversed + #define SPINDLE_LASER_PWM true // set to true if your controller supports setting the speed/power + #define SPINDLE_LASER_PWM_INVERT true // set to "true" if the speed/power goes up when you want it to go slower + #define SPINDLE_LASER_POWERUP_DELAY 5000 // delay in milliseconds to allow the spindle/laser to come up to speed/power + #define SPINDLE_LASER_POWERDOWN_DELAY 5000 // delay in milliseconds to allow the spindle to stop + #define SPINDLE_DIR_CHANGE true // set to true if your spindle controller supports changing spindle direction + #define SPINDLE_INVERT_DIR false + #define SPINDLE_STOP_ON_DIR_CHANGE true // set to true if Marlin should stop the spindle before changing rotation direction + + /** + * The M3 & M4 commands use the following equation to convert PWM duty cycle to speed/power + * + * SPEED/POWER = PWM duty cycle * SPEED_POWER_SLOPE + SPEED_POWER_INTERCEPT + * where PWM duty cycle varies from 0 to 255 + * + * set the following for your controller (ALL MUST BE SET) + */ + + #define SPEED_POWER_SLOPE 118.4 + #define SPEED_POWER_INTERCEPT 0 + #define SPEED_POWER_MIN 5000 + #define SPEED_POWER_MAX 30000 // SuperPID router controller 0 - 30,000 RPM + + //#define SPEED_POWER_SLOPE 0.3922 + //#define SPEED_POWER_INTERCEPT 0 + //#define SPEED_POWER_MIN 10 + //#define SPEED_POWER_MAX 100 // 0-100% +#endif + /** * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins */ diff --git a/Marlin/example_configurations/makibox/Configuration.h b/Marlin/example_configurations/makibox/Configuration.h index 13f4aa287..56cec59aa 100644 --- a/Marlin/example_configurations/makibox/Configuration.h +++ b/Marlin/example_configurations/makibox/Configuration.h @@ -129,6 +129,8 @@ // You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4) //#define MACHINE_UUID "00000000-0000-0000-0000-000000000000" +// @section extruder + // This defines the number of extruders // :[1, 2, 3, 4, 5] #define EXTRUDERS 1 @@ -172,6 +174,8 @@ //#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis //#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis +// @section machine + /** * Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN * diff --git a/Marlin/example_configurations/makibox/Configuration_adv.h b/Marlin/example_configurations/makibox/Configuration_adv.h index c8c38d60f..9050fc676 100644 --- a/Marlin/example_configurations/makibox/Configuration_adv.h +++ b/Marlin/example_configurations/makibox/Configuration_adv.h @@ -1125,6 +1125,55 @@ //#define EXPERIMENTAL_I2CBUS #define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave +// @section extras + +/** + * Spindle & Laser control + * + * Add the M3, M4, and M5 commands to turn the spindle/laser on and off, and + * to set spindle speed, spindle direction, and laser power. + * + * SuperPid is a router/spindle speed controller used in the CNC milling community. + * Marlin can be used to turn the spindle on and off. It can also be used to set + * the spindle speed from 5,000 to 30,000 RPM. + * + * You'll need to select a pin for the ON/OFF function and optionally choose a 0-5V + * hardware PWM pin for the speed control and a pin for the rotation direction. + * + * See http://marlinfw.org/docs/configuration/laser_spindle.html for more config details. + */ +//#define SPINDLE_LASER_ENABLE +#if ENABLED(SPINDLE_LASER_ENABLE) + + #define SPINDLE_LASER_ENABLE_INVERT false // set to "true" if the on/off function is reversed + #define SPINDLE_LASER_PWM true // set to true if your controller supports setting the speed/power + #define SPINDLE_LASER_PWM_INVERT true // set to "true" if the speed/power goes up when you want it to go slower + #define SPINDLE_LASER_POWERUP_DELAY 5000 // delay in milliseconds to allow the spindle/laser to come up to speed/power + #define SPINDLE_LASER_POWERDOWN_DELAY 5000 // delay in milliseconds to allow the spindle to stop + #define SPINDLE_DIR_CHANGE true // set to true if your spindle controller supports changing spindle direction + #define SPINDLE_INVERT_DIR false + #define SPINDLE_STOP_ON_DIR_CHANGE true // set to true if Marlin should stop the spindle before changing rotation direction + + /** + * The M3 & M4 commands use the following equation to convert PWM duty cycle to speed/power + * + * SPEED/POWER = PWM duty cycle * SPEED_POWER_SLOPE + SPEED_POWER_INTERCEPT + * where PWM duty cycle varies from 0 to 255 + * + * set the following for your controller (ALL MUST BE SET) + */ + + #define SPEED_POWER_SLOPE 118.4 + #define SPEED_POWER_INTERCEPT 0 + #define SPEED_POWER_MIN 5000 + #define SPEED_POWER_MAX 30000 // SuperPID router controller 0 - 30,000 RPM + + //#define SPEED_POWER_SLOPE 0.3922 + //#define SPEED_POWER_INTERCEPT 0 + //#define SPEED_POWER_MIN 10 + //#define SPEED_POWER_MAX 100 // 0-100% +#endif + /** * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins */ diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration.h b/Marlin/example_configurations/tvrrug/Round2/Configuration.h index 9701dd114..53d75f1f6 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration.h @@ -129,6 +129,8 @@ // You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4) //#define MACHINE_UUID "00000000-0000-0000-0000-000000000000" +// @section extruder + // This defines the number of extruders // :[1, 2, 3, 4, 5] #define EXTRUDERS 1 @@ -172,6 +174,8 @@ //#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis //#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis +// @section machine + /** * Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN * diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h index daf9e0d7d..f3022c7b2 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h @@ -1125,6 +1125,55 @@ //#define EXPERIMENTAL_I2CBUS #define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave +// @section extras + +/** + * Spindle & Laser control + * + * Add the M3, M4, and M5 commands to turn the spindle/laser on and off, and + * to set spindle speed, spindle direction, and laser power. + * + * SuperPid is a router/spindle speed controller used in the CNC milling community. + * Marlin can be used to turn the spindle on and off. It can also be used to set + * the spindle speed from 5,000 to 30,000 RPM. + * + * You'll need to select a pin for the ON/OFF function and optionally choose a 0-5V + * hardware PWM pin for the speed control and a pin for the rotation direction. + * + * See http://marlinfw.org/docs/configuration/laser_spindle.html for more config details. + */ +//#define SPINDLE_LASER_ENABLE +#if ENABLED(SPINDLE_LASER_ENABLE) + + #define SPINDLE_LASER_ENABLE_INVERT false // set to "true" if the on/off function is reversed + #define SPINDLE_LASER_PWM true // set to true if your controller supports setting the speed/power + #define SPINDLE_LASER_PWM_INVERT true // set to "true" if the speed/power goes up when you want it to go slower + #define SPINDLE_LASER_POWERUP_DELAY 5000 // delay in milliseconds to allow the spindle/laser to come up to speed/power + #define SPINDLE_LASER_POWERDOWN_DELAY 5000 // delay in milliseconds to allow the spindle to stop + #define SPINDLE_DIR_CHANGE true // set to true if your spindle controller supports changing spindle direction + #define SPINDLE_INVERT_DIR false + #define SPINDLE_STOP_ON_DIR_CHANGE true // set to true if Marlin should stop the spindle before changing rotation direction + + /** + * The M3 & M4 commands use the following equation to convert PWM duty cycle to speed/power + * + * SPEED/POWER = PWM duty cycle * SPEED_POWER_SLOPE + SPEED_POWER_INTERCEPT + * where PWM duty cycle varies from 0 to 255 + * + * set the following for your controller (ALL MUST BE SET) + */ + + #define SPEED_POWER_SLOPE 118.4 + #define SPEED_POWER_INTERCEPT 0 + #define SPEED_POWER_MIN 5000 + #define SPEED_POWER_MAX 30000 // SuperPID router controller 0 - 30,000 RPM + + //#define SPEED_POWER_SLOPE 0.3922 + //#define SPEED_POWER_INTERCEPT 0 + //#define SPEED_POWER_MIN 10 + //#define SPEED_POWER_MAX 100 // 0-100% +#endif + /** * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins */ diff --git a/Marlin/example_configurations/wt150/Configuration.h b/Marlin/example_configurations/wt150/Configuration.h index b3b334f24..2c1e4cfb6 100644 --- a/Marlin/example_configurations/wt150/Configuration.h +++ b/Marlin/example_configurations/wt150/Configuration.h @@ -129,6 +129,8 @@ // You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4) //#define MACHINE_UUID "5f0bb7a3-0e14-428c-812b-15ab0d3ecc71" +// @section extruder + // This defines the number of extruders // :[1, 2, 3, 4, 5] #define EXTRUDERS 1 @@ -172,6 +174,8 @@ //#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis //#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis +// @section machine + /** * Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN * diff --git a/Marlin/example_configurations/wt150/Configuration_adv.h b/Marlin/example_configurations/wt150/Configuration_adv.h index 81d5028b2..d5d595201 100644 --- a/Marlin/example_configurations/wt150/Configuration_adv.h +++ b/Marlin/example_configurations/wt150/Configuration_adv.h @@ -1128,6 +1128,55 @@ //#define EXPERIMENTAL_I2CBUS #define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave +// @section extras + +/** + * Spindle & Laser control + * + * Add the M3, M4, and M5 commands to turn the spindle/laser on and off, and + * to set spindle speed, spindle direction, and laser power. + * + * SuperPid is a router/spindle speed controller used in the CNC milling community. + * Marlin can be used to turn the spindle on and off. It can also be used to set + * the spindle speed from 5,000 to 30,000 RPM. + * + * You'll need to select a pin for the ON/OFF function and optionally choose a 0-5V + * hardware PWM pin for the speed control and a pin for the rotation direction. + * + * See http://marlinfw.org/docs/configuration/laser_spindle.html for more config details. + */ +//#define SPINDLE_LASER_ENABLE +#if ENABLED(SPINDLE_LASER_ENABLE) + + #define SPINDLE_LASER_ENABLE_INVERT false // set to "true" if the on/off function is reversed + #define SPINDLE_LASER_PWM true // set to true if your controller supports setting the speed/power + #define SPINDLE_LASER_PWM_INVERT true // set to "true" if the speed/power goes up when you want it to go slower + #define SPINDLE_LASER_POWERUP_DELAY 5000 // delay in milliseconds to allow the spindle/laser to come up to speed/power + #define SPINDLE_LASER_POWERDOWN_DELAY 5000 // delay in milliseconds to allow the spindle to stop + #define SPINDLE_DIR_CHANGE true // set to true if your spindle controller supports changing spindle direction + #define SPINDLE_INVERT_DIR false + #define SPINDLE_STOP_ON_DIR_CHANGE true // set to true if Marlin should stop the spindle before changing rotation direction + + /** + * The M3 & M4 commands use the following equation to convert PWM duty cycle to speed/power + * + * SPEED/POWER = PWM duty cycle * SPEED_POWER_SLOPE + SPEED_POWER_INTERCEPT + * where PWM duty cycle varies from 0 to 255 + * + * set the following for your controller (ALL MUST BE SET) + */ + + #define SPEED_POWER_SLOPE 118.4 + #define SPEED_POWER_INTERCEPT 0 + #define SPEED_POWER_MIN 5000 + #define SPEED_POWER_MAX 30000 // SuperPID router controller 0 - 30,000 RPM + + //#define SPEED_POWER_SLOPE 0.3922 + //#define SPEED_POWER_INTERCEPT 0 + //#define SPEED_POWER_MIN 10 + //#define SPEED_POWER_MAX 100 // 0-100% +#endif + /** * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins */ From ffe0e2d19aea47b9f51937cc40a9bcaa3a370e1d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 7 Apr 2017 13:52:21 -0500 Subject: [PATCH 099/189] SPINDLE/LASER pins changes --- Marlin/pinsDebug_list.h | 4 +- Marlin/pins_3DRAG.h | 57 +++++++++ Marlin/pins_AZTEEG_X3.h | 35 ++++++ Marlin/pins_AZTEEG_X3_PRO.h | 38 ++++++ Marlin/pins_BAM_DICE_DUE.h | 7 ++ Marlin/pins_BQ_ZUM_MEGA_3D.h | 12 ++ Marlin/pins_BRAINWAVE.h | 34 +++++ Marlin/pins_BRAINWAVE_PRO.h | 60 ++++++++- Marlin/pins_FELIX2.h | 7 ++ Marlin/pins_GEN3_MONOLITHIC.h | 26 ++++ Marlin/pins_GEN3_PLUS.h | 27 +++- Marlin/pins_GEN6.h | 35 ++++++ Marlin/pins_GEN6_DELUXE.h | 26 ++++ Marlin/pins_GEN7_12.h | 52 +++++++- Marlin/pins_GEN7_13.h | 25 ++++ Marlin/pins_GEN7_14.h | 49 ++++++-- Marlin/pins_GEN7_CUSTOM.h | 37 +++++- Marlin/pins_K8400.h | 5 + Marlin/pins_MEGACONTROLLER.h | 8 ++ Marlin/pins_MEGATRONICS.h | 8 ++ Marlin/pins_MEGATRONICS_2.h | 12 +- Marlin/pins_MEGATRONICS_3.h | 27 ++++ Marlin/pins_MIGHTYBOARD_REVE.h | 31 ++++- Marlin/pins_MINIRAMBO.h | 10 ++ Marlin/pins_MINITRONICS.h | 23 ++++ Marlin/pins_MKS_BASE.h | 13 +- Marlin/pins_OMCA.h | 25 ++++ Marlin/pins_OMCA_A.h | 27 +++- Marlin/pins_RAMBO.h | 8 ++ Marlin/pins_RAMPS.h | 26 ++++ Marlin/pins_RAMPS_OLD.h | 8 ++ Marlin/pins_RIGIDBOARD.h | 18 +-- Marlin/pins_RUMBA.h | 12 +- Marlin/pins_SANGUINOLOLU_11.h | 98 +++++++++++++-- Marlin/pins_SAV_MKI.h | 16 ++- Marlin/pins_SETHI.h | 25 ++++ Marlin/pins_TEENSY2.h | 8 ++ Marlin/pins_TEENSYLU.h | 163 ++++++++++++++++-------- Marlin/pins_ULTIMAIN_2.h | 21 ++++ Marlin/pins_ULTIMAKER.h | 16 +++ Marlin/pins_ULTIMAKER_OLD.h | 220 ++++++++++++++++++++++++++++++--- 41 files changed, 1248 insertions(+), 111 deletions(-) diff --git a/Marlin/pinsDebug_list.h b/Marlin/pinsDebug_list.h index 758c332dc..dfdd41104 100644 --- a/Marlin/pinsDebug_list.h +++ b/Marlin/pinsDebug_list.h @@ -515,8 +515,8 @@ #if PIN_EXISTS(SPINDLE_LASER_ENABLE) REPORT_NAME_DIGITAL(SPINDLE_LASER_ENABLE_PIN, __LINE__ ) #endif -#if PIN_EXISTS(SPINDLE_SPEED_LASER_POWER) - REPORT_NAME_DIGITAL(SPINDLE_SPEED_LASER_POWER_PIN, __LINE__ ) +#if PIN_EXISTS(SPINDLE_LASER_PWM) + REPORT_NAME_DIGITAL(SPINDLE_LASER_PWM_PIN, __LINE__ ) #endif #if PIN_EXISTS(SR_CLK) REPORT_NAME_DIGITAL(SR_CLK_PIN, __LINE__ ) diff --git a/Marlin/pins_3DRAG.h b/Marlin/pins_3DRAG.h index 9eaf2c9f6..feadea4e3 100644 --- a/Marlin/pins_3DRAG.h +++ b/Marlin/pins_3DRAG.h @@ -43,6 +43,8 @@ #define RAMPS_D9_PIN 8 #define MOSFET_D_PIN 12 +#define CASE_LIGHT_PIN -1 // MUST BE HARDWARE PWM but one is not available on expansion header + #include "pins_RAMPS.h" // @@ -104,3 +106,58 @@ #define BEEPER_PIN 33 #endif // ULTRA_LCD && NEWPANEL + +/** + * M3/M4/M5 - Spindle/Laser Control + * + * If you want to control the speed of your spindle then you'll have + * have to sacrifce the Extruder and pull some signals off the Z stepper + * driver socket. + * + * The following assumes: + * - the Z stepper driver socket is empty + * - the extruder driver socket has a driver board plugged into it + * - the Z stepper wires are attached the the extruder connector + * + * If you want to keep the extruder AND don't have a LCD display then + * you can still control the power on/off and spindle direction. + * + * Where to get spindle signals + * + * stepper signal socket name socket name + * ------- + * SPINDLE_LASER_ENABLE_PIN /ENABLE O| |O VMOT + * MS1 O| |O GND + * MS2 O| |O 2B + * MS3 O| |O 2A + * /RESET O| |O 1A + * /SLEEP O| |O 1B + * SPINDLE_LASER_PWM_PIN STEP O| |O VDD + * SPINDLE_DIR_PIN DIR O| |O GND + * ------- + * + * Note: Socket names vary from vendor to vendor + */ +#undef SPINDLE_LASER_PWM_PIN // Definitions in pins_RAMPS.h are not good with 3DRAG +#undef SPINDLE_LASER_ENABLE_PIN +#undef SPINDLE_DIR_PIN + +#if ENABLED(SPINDLE_LASER_ENABLE) + #if !EXTRUDERS + #undef E0_DIR_PIN + #undef E0_ENABLE_PIN + #undef E0_STEP_PIN + #undef Z_DIR_PIN + #undef Z_ENABLE_PIN + #undef Z_STEP_PIN + #define Z_DIR_PIN 28 + #define Z_ENABLE_PIN 24 + #define Z_STEP_PIN 26 + #define SPINDLE_LASER_PWM_PIN 46 // MUST BE HARDWARE PWM + #define SPINDLE_LASER_ENABLE_PIN 62 // Pin should have a pullup! + #define SPINDLE_DIR_PIN 48 + #elif !(ENABLED(ULTRA_LCD) && ENABLED(NEWPANEL)) // use expansion header if no LCD in use + #define SPINDLE_LASER_ENABLE_PIN 16 // Pin should have a pullup/pulldown! + #define SPINDLE_DIR_PIN 17 + #endif +#endif diff --git a/Marlin/pins_AZTEEG_X3.h b/Marlin/pins_AZTEEG_X3.h index 364697d60..430a9fa42 100644 --- a/Marlin/pins_AZTEEG_X3.h +++ b/Marlin/pins_AZTEEG_X3.h @@ -24,12 +24,20 @@ * AZTEEG_X3 Arduino Mega with RAMPS v1.4 pin assignments */ +#ifndef __AVR_ATmega2560__ + #error "Oops! Make sure you have 'Arduino Mega 2560' selected from the 'Tools -> Boards' menu." +#endif + #if HOTENDS > 2 || E_STEPPERS > 2 #error "Azteeg X3 supports up to 2 hotends / E-steppers. Comment out this line to continue." #endif #define BOARD_NAME "Azteeg X3" +#if !PIN_EXISTS(CASE_LIGHT) // doesn't already exist so OK to change the definition coming + #define OK_TO_CHANGE_CASE_LIGHT // in from from the include file +#endif + #include "pins_RAMPS_13.h" // @@ -63,3 +71,30 @@ #define STAT_LED_BLUE_PIN 11 #endif + +// +// Misc +// +#if ENABLED(OK_TO_CHANGE_CASE_LIGHT) && STAT_LED_RED_PIN == 6 + #undef STAT_LED_RED_PIN + #undef CASE_LIGHT_PIN + #define CASE_LIGHT_PIN 6 // open collector FET driver +#endif + +// +// M3/M4/M5 - Spindle/Laser Control +// +#undef SPINDLE_LASER_PWM_PIN // Definitions in pins_RAMPS.h are no good with the AzteegX3 board +#undef SPINDLE_LASER_ENABLE_PIN +#undef SPINDLE_DIR_PIN + +#if ENABLED(SPINDLE_LASER_ENABLE) + #undef SDA // use EXP3 header + #undef SCL + #if SERVO0_PIN == 7 + #undef SERVO0_PIN + #def SERVO0_PIN 11 + #define SPINDLE_LASER_PWM_PIN 7 // MUST BE HARDWARE PWM + #define SPINDLE_LASER_ENABLE_PIN 20 // Pin should have a pullup! + #define SPINDLE_DIR_PIN 21 +#endif diff --git a/Marlin/pins_AZTEEG_X3_PRO.h b/Marlin/pins_AZTEEG_X3_PRO.h index 41df3be5b..7701f8b68 100644 --- a/Marlin/pins_AZTEEG_X3_PRO.h +++ b/Marlin/pins_AZTEEG_X3_PRO.h @@ -30,8 +30,16 @@ #define BOARD_NAME "Azteeg X3 Pro" +#if !PIN_EXISTS(CASE_LIGHT) // doesn't already exist so OK to change the definition coming + #define OK_TO_CHANGE_CASE_LIGHT // in from from the include file +#endif + #include "pins_RAMPS.h" +#ifndef __AVR_ATmega2560__ + #error "Oops! Make sure you have 'Arduino Mega 2560' selected from the 'Tools -> Boards' menu." +#endif + // // Servos // @@ -126,7 +134,37 @@ #if ENABLED(VIKI2) || ENABLED(miniVIKI) #undef SD_DETECT_PIN #define SD_DETECT_PIN 49 // For easy adapter board + #undef BEEPER_PIN + #define BEEPER_PIN 12 // 33 isn't physically available to the LCD display #else #define STAT_LED_RED_PIN 32 #define STAT_LED_BLUE_PIN 35 #endif + +// +// Misc. Functions +// +#undef DOGLCD_A0 // steal pin 44 for the case light +#define DOGLCD_A0 57 +#if ENABLED(OK_TO_CHANGE_CASE_LIGHT) + #undef CASE_LIGHT_PIN + #define CASE_LIGHT_PIN 44 // must have a hardware PWM +#endif + +// +// M3/M4/M5 - Spindle/Laser Control +// +#undef SPINDLE_LASER_PWM_PIN // Definitions in pins_RAMPS.h are no good with the AzteegX3 board +#undef SPINDLE_LASER_ENABLE_PIN +#undef SPINDLE_DIR_PIN + +#if ENABLED(SPINDLE_LASER_ENABLE) // use EXP2 header + #if ENABLED(VIKI2) || ENABLED(miniVIKI) + #undef BTN_EN2 + #define BTN_EN2 31 // need 7 for the spindle speed PWM + #endif + #define SPINDLE_LASER_PWM_PIN 7 // must have a hardware PWM + #define SPINDLE_LASER_ENABLE_PIN 20 // Pin should have a pullup! + #define SPINDLE_DIR_PIN 21 +#endif + diff --git a/Marlin/pins_BAM_DICE_DUE.h b/Marlin/pins_BAM_DICE_DUE.h index 0da4f08c4..2b34cddd8 100644 --- a/Marlin/pins_BAM_DICE_DUE.h +++ b/Marlin/pins_BAM_DICE_DUE.h @@ -30,6 +30,13 @@ #define BOARD_NAME "2PrintBeta Due" +// +// M3/M4/M5 - Spindle/Laser Control +// +#define SPINDLE_LASER_ENABLE_PIN 66 // Pin should have a pullup/pulldown! +#define SPINDLE_DIR_PIN 67 +#define SPINDLE_LASER_PWM_PIN 44 // MUST BE HARDWARE PWM + #include "pins_RAMPS.h" // diff --git a/Marlin/pins_BQ_ZUM_MEGA_3D.h b/Marlin/pins_BQ_ZUM_MEGA_3D.h index 402c1cb2f..84722f11c 100644 --- a/Marlin/pins_BQ_ZUM_MEGA_3D.h +++ b/Marlin/pins_BQ_ZUM_MEGA_3D.h @@ -46,6 +46,18 @@ #define ORIG_E2_AUTO_FAN_PIN 6 #define ORIG_E3_AUTO_FAN_PIN 6 +// +// Misc. Functions +// +#define CASE_LIGHT_PIN 44 // MUST BE HARDWARE PWM + +// +// M3/M4/M5 - Spindle/Laser Control +// +#define SPINDLE_LASER_ENABLE_PIN 40 // Pin should have a pullup/pulldown! +#define SPINDLE_LASER_PWM_PIN 44 // MUST BE HARDWARE PWM +#define SPINDLE_DIR_PIN 42 + #include "pins_RAMPS_13.h" // diff --git a/Marlin/pins_BRAINWAVE.h b/Marlin/pins_BRAINWAVE.h index ba9d04099..0d17cac10 100644 --- a/Marlin/pins_BRAINWAVE.h +++ b/Marlin/pins_BRAINWAVE.h @@ -27,6 +27,40 @@ * https://github.com/unrepentantgeek/brainwave-arduino */ +/** + * Rev B 16 JAN 2017 + * + * Added pointer to a currently available Arduino IDE extension that will + * allow this board to use the latest Marlin software + */ + +/** + * Marlin_AT90USB - https://github.com/Bob-the-Kuhn/Marlin_AT90USB + * This is the only known IDE extension that is compatible with the pin definitions + * in this file, Adrduino 1.6.12 and the latest mainstream Marlin software. + * + * "Marlin_AT90USB" makes PWM0A available rather than the usual PWM1C. These PWMs share + * the same physical pin. Marlin uses TIMER1 to generate interrupts and sets it up such + * that PWM1A, PWM1B & PWM1C can not be used. + * + * Installation: + * + * 1. In the Arduino IDE, under Files -> Preferences paste the following URL + * https://rawgit.com/Bob-the-Kuhn/Marlin_AT90USB/master/package_MARLIN_AT90USB_index.json + * 2. Under Tools -> Board -> Boards manager, scroll to the bottom, click on MARLIN_AT90USB + * and then click on "Install" + * 3. Select "AT90USB646_STANDARD" from the 'Tools -> Boards' menu. + */ + +/** + * To burn the bootloader that comes with Marlin_AT90USB: + * + * 1. Connect your programmer to the board. + * 2. In Arduino IDE select "AT90USB646_STANDARD" and then select the programmer. + * 3. In Arduino IDE click on "burn bootloader". Don't worry about the "verify failed at 1F000" error message. + * 4. The programmer is no longer needed. Remove it. + */ + #ifndef __AVR_AT90USB646__ #error "Oops! Make sure you have 'Brainwave' selected from the 'Tools -> Boards' menu." #endif diff --git a/Marlin/pins_BRAINWAVE_PRO.h b/Marlin/pins_BRAINWAVE_PRO.h index b353581f0..1884d3cb1 100644 --- a/Marlin/pins_BRAINWAVE_PRO.h +++ b/Marlin/pins_BRAINWAVE_PRO.h @@ -27,14 +27,70 @@ * https://github.com/unrepentantgeek/brainwave-arduino */ +/** + * Rev B 16 JAN 2017 + * + * Added pointers to currently available Arduino IDE extensions that will + * allow this board to use the latest Marlin software + */ + +/** + * There are three Arduino IDE extensions that are compatible with this board + * and with the mainstream Marlin software. All have been used with Arduino 1.6.12 + * + * Teensyduino - http://www.pjrc.com/teensy/teensyduino.html + * Select Teensy++ 2.0 in Arduino IDE from the 'Tools -> Boards' menu + * + * Installation instructions are at the above URL. Don't bother loading the + * libraries - they are not used with the Marlin software. + * + * Printrboard - https://github.com/scwimbush/Printrboard-HID-Arduino-IDE-Support + * This is basically Teensyduino but with a bootloader that can handle image sizes + * larger than 64K. + * + * Installation: + * + * 1. Go to the above URL, click on the "Clone or Download" button and then + * click on "Download ZIP" button. + * 2. Unzip the file, find the "printrboard" directory and then copy it to the + * hardware directory in Arduino. The Arduino hardware directory will probably + * be located in a path similar to this: C:\Program Files (x86)\Arduino\hardware. + * 3. Restart Arduino. + * 4. Select "Printrboard" from the 'Tools -> Boards' menu. + * + * Marlin_AT90USB - https://github.com/Bob-the-Kuhn/Marlin_AT90USB + * Uses the bootloader from Printerboard above. + * + * "Marlin_AT90USB" makes PWM0A available rather than the usual PWM1C. These PWMs share + * the same physical pin. Marlin uses TIMER1 to generate interrupts and sets it up such + * that PWM1A, PWM1B & PWM1C can not be used. + * + * Installation: + * + * 1. In the Arduino IDE, under Files -> Preferences paste the following URL + * https://rawgit.com/Bob-the-Kuhn/Marlin_AT90USB/master/package_MARLIN_AT90USB_index.json + * 2. Under Tools -> Board -> Boards manager, scroll to the bottom, click on MARLIN_AT90USB + * and then click on "Install" + * 3. Select "AT90USB1286_TEENSYPP" from the 'Tools -> Boards' menu. + */ + +/** + * To burn the bootloader that comes with Printrboard and Marlin_AT90USB: + * + * 1. Connect your programmer to the board. + * 2. In the Arduino IDE select "Printrboard" or "AT90USB1286_TEENSYPP" and then select the programmer. + * 3. In the Arduino IDE click on "burn bootloader". Don't worry about the "verify failed at 1F000" error message. + * 4. The programmer is no longer needed. Remove it. + */ + #ifndef __AVR_AT90USB1286__ - #error "Oops! Make sure you have 'Brainwave Pro' selected from the 'Tools -> Boards' menu." + #error "Oops! Make sure you have 'Teensy++ 2.0', 'AT90USB1286_TEENSYPP', or 'Printrboard' selected from the 'Tools -> Boards' menu." #endif #include "fastio.h" #if DISABLED(AT90USBxx_TEENSYPP_ASSIGNMENTS) // use Teensyduino Teensy++2.0 pin assignments instead of Marlin alphabetical. - #error "Uncomment #define AT90USBxx_TEENSYPP_ASSIGNMENTS in fastio.h for this config" + #error "Uncomment '#define AT90USBxx_TEENSYPP_ASSIGNMENTS' in fastio.h for this config" #endif #define BOARD_NAME "Brainwave Pro" diff --git a/Marlin/pins_FELIX2.h b/Marlin/pins_FELIX2.h index 28894fe97..5d6765c84 100644 --- a/Marlin/pins_FELIX2.h +++ b/Marlin/pins_FELIX2.h @@ -54,3 +54,10 @@ #define SD_DETECT_PIN 6 #endif // NEWPANEL && ULTRA_LCD + +// +// M3/M4/M5 - Spindle/Laser Control +// +#undef SPINDLE_LASER_PWM_PIN // Definitions in pins_RAMPS.h are not valid with this board +#undef SPINDLE_LASER_ENABLE_PIN +#undef SPINDLE_DIR_PIN diff --git a/Marlin/pins_GEN3_MONOLITHIC.h b/Marlin/pins_GEN3_MONOLITHIC.h index e7a5dfb0d..dae4046fd 100644 --- a/Marlin/pins_GEN3_MONOLITHIC.h +++ b/Marlin/pins_GEN3_MONOLITHIC.h @@ -24,6 +24,31 @@ * Gen3 Monolithic Electronics pin assignments */ +/** + * Rev B 26 DEC 2016 + * + * added pointer to a current Arduino IDE extension + * + */ + +/** + * A useable Arduino IDE extension (board manager) can be found at + * https://github.com/Lauszus/Sanguino + * + * This extension has been tested on Arduino 1.6.12 & 1.8.0 + * + * Here's the JSON path: + * https://raw.githubusercontent.com/Lauszus/Sanguino/master/package_lauszus_sanguino_index.json + * + * When installing select 1.0.2 + * + * Installation instructions can be found at https://learn.sparkfun.com/pages/CustomBoardsArduino + * Just use the above JSON URL instead of Sparkfun's JSON. + * + * Once installed select the Sanguino board and then select the CPU. + * + */ + #ifndef __AVR_ATmega644P__ #error "Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu." #endif @@ -73,3 +98,4 @@ #define PS_ON_PIN 14 // Alex, does this work on the card? // Alex extras from Gen3+ + diff --git a/Marlin/pins_GEN3_PLUS.h b/Marlin/pins_GEN3_PLUS.h index b5236d87e..85c47305b 100644 --- a/Marlin/pins_GEN3_PLUS.h +++ b/Marlin/pins_GEN3_PLUS.h @@ -24,6 +24,32 @@ * Gen3+ pin assignments */ +/** + * Rev B 26 DEC 2016 + * + * added pointer to a current Arduino IDE extension + * + */ + +/** + * A useable Arduino IDE extension (board manager) can be found at + * https://github.com/Lauszus/Sanguino + * + * This extension has been tested on Arduino 1.6.12 & 1.8.0 + * + * Here's the JSON path: + * https://raw.githubusercontent.com/Lauszus/Sanguino/master/package_lauszus_sanguino_index.json + * + * When installing select 1.0.2 + * + * Installation instructions can be found at https://learn.sparkfun.com/pages/CustomBoardsArduino + * Just use the above JSON URL instead of Sparkfun's JSON. + * + * Once installed select the SANGUINO board and then select the CPU. + * + */ + + #if !defined(__AVR_ATmega644P__) && !defined(__AVR_ATmega1284P__) #error "Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu." #endif @@ -73,4 +99,3 @@ // #define SDSS 4 #define PS_ON_PIN 14 - diff --git a/Marlin/pins_GEN6.h b/Marlin/pins_GEN6.h index 9d1e1bcf1..10a285790 100644 --- a/Marlin/pins_GEN6.h +++ b/Marlin/pins_GEN6.h @@ -24,6 +24,33 @@ * Gen6 pin assignments */ + /** + * Rev B 26 DEC 2016 + * + * 1) added pointer to a current Arduino IDE extension + * 2) added support for M3, M4 & M5 spindle control commands + * 3) added case light pin definition + * + */ + +/** + * A useable Arduino IDE extension (board manager) can be found at + * https://github.com/Lauszus/Sanguino + * + * This extension has been tested on Arduino 1.6.12 & 1.8.0 + * + * Here's the JSON path: + * https://raw.githubusercontent.com/Lauszus/Sanguino/master/package_lauszus_sanguino_index.json + * + * When installing select 1.0.2 + * + * Installation instructions can be found at https://learn.sparkfun.com/pages/CustomBoardsArduino + * Just use the above JSON URL instead of Sparkfun's JSON. + * + * Once installed select the Sanguino board and then select the CPU. + * + */ + #ifndef __AVR_ATmega644P__ #ifndef __AVR_ATmega1284P__ #error "Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu." @@ -80,7 +107,15 @@ // #define SDSS 17 #define DEBUG_PIN 0 +#define CASE_LIGHT_PIN 16 // MUST BE HARDWARE PWM // RS485 pins #define TX_ENABLE_PIN 12 #define RX_ENABLE_PIN 13 + +// +// M3/M4/M5 - Spindle/Laser Control +// +#define SPINDLE_LASER_ENABLE_PIN 5 // Pin should have a pullup/pulldown! +#define SPINDLE_LASER_PWM_PIN 16 // MUST BE HARDWARE PWM +#define SPINDLE_DIR_PIN 6 diff --git a/Marlin/pins_GEN6_DELUXE.h b/Marlin/pins_GEN6_DELUXE.h index b1a1037ed..583406866 100644 --- a/Marlin/pins_GEN6_DELUXE.h +++ b/Marlin/pins_GEN6_DELUXE.h @@ -24,6 +24,32 @@ * Gen6 Deluxe pin assignments */ +/** + * Rev B 26 DEC 2016 + * + * added pointer to a current Arduino IDE extension + * + */ + +/** + * A useable Arduino IDE extension (board manager) can be found at + * https://github.com/Lauszus/Sanguino + * + * This extension has been tested on Arduino 1.6.12 & 1.8.0 + * + * Here's the JSON path: + * https://raw.githubusercontent.com/Lauszus/Sanguino/master/package_lauszus_sanguino_index.json + * + * When installing select 1.0.2 + * + * Installation instructions can be found at https://learn.sparkfun.com/pages/CustomBoardsArduino + * Just use the above JSON URL instead of Sparkfun's JSON. + * + * Once installed select the SANGUINO board and then select the CPU. + * + */ + + #define BOARD_NAME "Gen6 Deluxe" #include "pins_GEN6.h" diff --git a/Marlin/pins_GEN7_12.h b/Marlin/pins_GEN7_12.h index 53edb3281..b0f178ff3 100644 --- a/Marlin/pins_GEN7_12.h +++ b/Marlin/pins_GEN7_12.h @@ -24,8 +24,35 @@ * Gen7 v1.1, v1.2, v1.3 pin assignments */ + /** + * Rev B 26 DEC 2016 + * + * 1) added pointer to a current Arduino IDE extension + * 2) added support for M3, M4 & M5 spindle control commands + * 3) added case light pin definition + * + */ + +/** + * A useable Arduino IDE extension (board manager) can be found at + * https://github.com/Lauszus/Sanguino + * + * This extension has been tested on Arduino 1.6.12 & 1.8.0 + * + * Here's the JSON path: + * https://raw.githubusercontent.com/Lauszus/Sanguino/master/package_lauszus_sanguino_index.json + * + * When installing select 1.0.2 + * + * Installation instructions can be found at https://learn.sparkfun.com/pages/CustomBoardsArduino + * Just use the above JSON URL instead of Sparkfun's JSON. + * + * Once installed select the Sanguino board and then select the CPU. + * + */ + #if !defined(__AVR_ATmega644P__) && !defined(__AVR_ATmega644__) && !defined(__AVR_ATmega1284P__) - #error "Oops! Make sure you have 'Gen7' selected from the 'Tools -> Boards' menu." + #error "Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu." #endif #ifndef BOARD_NAME @@ -39,10 +66,13 @@ // // Limit Switches // -#define X_STOP_PIN 7 -#define Y_STOP_PIN 5 +#define X_MIN_PIN 7 +#define Y_MIN_PIN 5 #define Z_MIN_PIN 1 #define Z_MAX_PIN 0 +#define Y_MAX_PIN 2 +#define X_MAX_PIN 6 + // // Z Probe (when not Z_MIN_PIN) @@ -91,6 +121,12 @@ // #define PS_ON_PIN 15 +#if GEN7_VERSION < 13 + #define CASE_LIGHT_PIN 16 // MUST BE HARDWARE PWM +#else // Gen7 v1.3 removed the I2C connector & signals so need to get PWM off the PC power supply header + #define CASE_LIGHT_PIN 15 // MUST BE HARDWARE PWM +#endif + // All these generations of Gen7 supply thermistor power // via PS_ON, so ignore bad thermistor readings #define BOGUS_TEMPERATURE_FAILSAFE_OVERRIDE @@ -101,3 +137,13 @@ #define TX_ENABLE_PIN 12 #define RX_ENABLE_PIN 13 +// +// M3/M4/M5 - Spindle/Laser Control +// +#define SPINDLE_LASER_ENABLE_PIN 10 // Pin should have a pullup/pulldown! +#define SPINDLE_DIR_PIN 11 +#if GEN7_VERSION < 13 + #define SPINDLE_LASER_PWM_PIN 16 // MUST BE HARDWARE PWM +#else // Gen7 v1.3 removed the I2C connector & signals so need to get PWM off the PC power supply header + #define SPINDLE_LASER_PWM_PIN 15 // MUST BE HARDWARE PWM +#endif diff --git a/Marlin/pins_GEN7_13.h b/Marlin/pins_GEN7_13.h index 2365ae8be..03ea131f4 100644 --- a/Marlin/pins_GEN7_13.h +++ b/Marlin/pins_GEN7_13.h @@ -24,6 +24,31 @@ * Gen7 v1.3 pin assignments */ + /** + * Rev B 26 DEC 2016 + * + * added pointer to a current Arduino IDE extension + * + */ + +/** + * A useable Arduino IDE extension (board manager) can be found at + * https://github.com/Lauszus/Sanguino + * + * This extension has been tested on Arduino 1.6.12 & 1.8.0 + * + * Here's the JSON path: + * https://raw.githubusercontent.com/Lauszus/Sanguino/master/package_lauszus_sanguino_index.json + * + * When installing select 1.0.2 + * + * Installation instructions can be found at https://learn.sparkfun.com/pages/CustomBoardsArduino + * Just use the above JSON URL instead of Sparkfun's JSON. + * + * Once installed select the Sanguino board and then select the CPU. + * + */ + #define BOARD_NAME "Gen7 v1.3" #define GEN7_VERSION 13 // v1.3 diff --git a/Marlin/pins_GEN7_14.h b/Marlin/pins_GEN7_14.h index d200137b4..9d4e16af3 100644 --- a/Marlin/pins_GEN7_14.h +++ b/Marlin/pins_GEN7_14.h @@ -24,8 +24,35 @@ * Gen7 v1.4 pin assignments */ +/** + * Rev B 26 DEC 2016 + * + * 1) added pointer to a current Arduino IDE extension + * 2) added support for M3, M4 & M5 spindle control commands + * 3) added case light pin definition + * + */ + +/** + * A useable Arduino IDE extension (board manager) can be found at + * https://github.com/Lauszus/Sanguino + * + * This extension has been tested on Arduino 1.6.12 & 1.8.0 + * + * Here's the JSON path: + * https://raw.githubusercontent.com/Lauszus/Sanguino/master/package_lauszus_sanguino_index.json + * + * When installing select 1.0.2 + * + * Installation instructions can be found at https://learn.sparkfun.com/pages/CustomBoardsArduino + * Just use the above JSON URL instead of Sparkfun's JSON. + * + * Once installed select the Sanguino board and then select the CPU. + * + */ + #if !defined(__AVR_ATmega644P__) && !defined(__AVR_ATmega644__) && !defined(__AVR_ATmega1284P__) - #error "Oops! Make sure you have 'Gen7' selected from the 'Tools -> Boards' menu." + #error "Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu." #endif #define BOARD_NAME "Gen7 v1.4" @@ -67,17 +94,25 @@ // // Heaters // -#define HEATER_0_PIN 4 -#define HEATER_BED_PIN 3 +#define HEATER_0_PIN 4 +#define HEATER_BED_PIN 3 // // Misc. Functions // -#define PS_ON_PIN 15 +#define PS_ON_PIN 15 +#define CASE_LIGHT_PIN 15 // MUST BE HARDWARE PWM // A pin for debugging -#define DEBUG_PIN 0 +#define DEBUG_PIN 0 // RS485 pins -#define TX_ENABLE_PIN 12 -#define RX_ENABLE_PIN 13 +#define TX_ENABLE_PIN 12 +#define RX_ENABLE_PIN 13 + +// +// M3/M4/M5 - Spindle/Laser Control +// +#define SPINDLE_LASER_ENABLE_PIN 20 // Pin should have a pullup/pulldown! +#define SPINDLE_LASER_PWM_PIN 16 // MUST BE HARDWARE PWM +#define SPINDLE_DIR_PIN 21 diff --git a/Marlin/pins_GEN7_CUSTOM.h b/Marlin/pins_GEN7_CUSTOM.h index 81809d61a..9b83df9ae 100644 --- a/Marlin/pins_GEN7_CUSTOM.h +++ b/Marlin/pins_GEN7_CUSTOM.h @@ -27,8 +27,35 @@ * Please review the pins and adjust them for your needs. */ +/** + * Rev B 26 DEC 2016 + * + * 1) added pointer to a current Arduino IDE extension + * 2) added support for M3, M4 & M5 spindle control commands + * 3) added case light pin definition + * + */ + +/** + * A useable Arduino IDE extension (board manager) can be found at + * https://github.com/Lauszus/Sanguino + * + * This extension has been tested on Arduino 1.6.12 & 1.8.0 + * + * Here's the JSON path: + * https://raw.githubusercontent.com/Lauszus/Sanguino/master/package_lauszus_sanguino_index.json + * + * When installing select 1.0.2 + * + * Installation instructions can be found at https://learn.sparkfun.com/pages/CustomBoardsArduino + * Just use the above JSON URL instead of Sparkfun's JSON. + * + * Once installed select the Sanguino board and then select the CPU. + * + */ + #if !defined(__AVR_ATmega644P__) && !defined(__AVR_ATmega644__) && !defined(__AVR_ATmega1284P__) - #error "Oops! Make sure you have 'Gen7' selected from the 'Tools -> Boards' menu." + #error "Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu." #endif #define BOARD_NAME "Gen7 Custom" @@ -76,6 +103,7 @@ // #define SDSS 31 // SCL pin of I2C header || CS Pin for SD Card support #define PS_ON_PIN 19 +#define CASE_LIGHT_PIN 15 // MUST BE HARDWARE PWM // A pin for debugging #define DEBUG_PIN -1 @@ -101,3 +129,10 @@ // RS485 pins //#define TX_ENABLE_PIN 12 //#define RX_ENABLE_PIN 13 + +// +// M3/M4/M5 - Spindle/Laser Control +// +#define SPINDLE_LASER_ENABLE_PIN 5 // Pin should have a pullup/pulldown! +#define SPINDLE_LASER_PWM_PIN 16 // MUST BE HARDWARE PWM +#define SPINDLE_DIR_PIN 6 diff --git a/Marlin/pins_K8400.h b/Marlin/pins_K8400.h index 1ef8049c1..3e2cd4b21 100644 --- a/Marlin/pins_K8400.h +++ b/Marlin/pins_K8400.h @@ -66,3 +66,8 @@ #undef PS_ON_PIN #undef KILL_PIN #undef SD_DETECT_PIN + +#if Z_STEP_PIN == 26 + #undef Z_STEP_PIN + #define Z_STEP_PIN 32 +#endif diff --git a/Marlin/pins_MEGACONTROLLER.h b/Marlin/pins_MEGACONTROLLER.h index c81f3547b..c4a10705a 100644 --- a/Marlin/pins_MEGACONTROLLER.h +++ b/Marlin/pins_MEGACONTROLLER.h @@ -127,6 +127,7 @@ // #define SDSS 53 #define LED_PIN 13 +#define CASE_LIGHT_PIN 2 // // LCD / Controller @@ -152,3 +153,10 @@ #define SD_DETECT_PIN 49 #endif // MINIPANEL + +// +// M3/M4/M5 - Spindle/Laser Control +// +#define SPINDLE_LASER_PWM_PIN 6 // MUST BE HARDWARE PWM +#define SPINDLE_LASER_ENABLE_PIN 7 // Pin should have a pullup! +#define SPINDLE_DIR_PIN 8 diff --git a/Marlin/pins_MEGATRONICS.h b/Marlin/pins_MEGATRONICS.h index 5b8d41f4f..ba97fa255 100644 --- a/Marlin/pins_MEGATRONICS.h +++ b/Marlin/pins_MEGATRONICS.h @@ -97,6 +97,7 @@ #define SDSS 53 #define LED_PIN 13 #define PS_ON_PIN 12 +#define CASE_LIGHT_PIN 2 // // LCD / Controller @@ -120,3 +121,10 @@ #define SD_DETECT_PIN -1 // RAMPS doesn't use this #endif // ULTRA_LCD && NEWPANEL + +// +// M3/M4/M5 - Spindle/Laser Control +// +#define SPINDLE_LASER_PWM_PIN 3 // MUST BE HARDWARE PWM +#define SPINDLE_LASER_ENABLE_PIN 4 // Pin should have a pullup! +#define SPINDLE_DIR_PIN 11 diff --git a/Marlin/pins_MEGATRONICS_2.h b/Marlin/pins_MEGATRONICS_2.h index be3ed4cf4..0cbb76945 100644 --- a/Marlin/pins_MEGATRONICS_2.h +++ b/Marlin/pins_MEGATRONICS_2.h @@ -71,8 +71,8 @@ #define E1_DIR_PIN 39 #define E1_ENABLE_PIN 28 -#define E2_STEP_PIN 23 -#define E2_DIR_PIN 24 +#define E2_STEP_PIN 23 // ? schematic says 24 +#define E2_DIR_PIN 24 // ? schematic says 23 #define E2_ENABLE_PIN 22 // @@ -112,6 +112,7 @@ #define SDSS 53 #define LED_PIN 13 #define PS_ON_PIN 12 +#define CASE_LIGHT_PIN 2 // // LCD / Controller @@ -129,3 +130,10 @@ #define BTN_EN1 61 #define BTN_EN2 59 #define BTN_ENC 43 + +// +// M3/M4/M5 - Spindle/Laser Control +// +#define SPINDLE_LASER_PWM_PIN 3 // MUST BE HARDWARE PWM +#define SPINDLE_LASER_ENABLE_PIN 16 // Pin should have a pullup! +#define SPINDLE_DIR_PIN 11 diff --git a/Marlin/pins_MEGATRONICS_3.h b/Marlin/pins_MEGATRONICS_3.h index 419f80ba5..aa6c40374 100644 --- a/Marlin/pins_MEGATRONICS_3.h +++ b/Marlin/pins_MEGATRONICS_3.h @@ -28,6 +28,8 @@ #error "Oops! Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu." #endif +#define MEGATRONICS_31 + #if ENABLED(MEGATRONICS_31) #define BOARD_NAME "Megatronics v3.1" #else @@ -129,6 +131,7 @@ #define SDSS 53 #define LED_PIN 13 #define PS_ON_PIN 12 +#define CASE_LIGHT_PIN 45 // try the keypad connector // // LCD / Controller @@ -164,3 +167,27 @@ #endif #endif + +// +// M3/M4/M5 - Spindle/Laser Control +// +#if DISABLED(REPRAPWORLD_KEYPAD) // try to use the keypad connector first + #define SPINDLE_LASER_PWM_PIN 44 // MUST BE HARDWARE PWM + #define SPINDLE_LASER_ENABLE_PIN 43 // Pin should have a pullup! + #define SPINDLE_DIR_PIN 42 +#elif EXTRUDERS <= 2 + // try to hijack the last extruder so that we can get the PWM signal off the Y breakout + // move all the Y signals to the E2 extruder socket - makes dual Y steppers harder + #undef Y_ENABLE_PIN + #undef Y_STEP_PIN + #undef Y_DIR_PIN + #undef E2_STEP_PIN + #undef E2_ENABLE_PIN + #undef E2_DIR_PIN + #define Y_ENABLE_PIN 23 + #define Y_STEP_PIN 22 + #define Y_DIR_PIN 60 + #define SPINDLE_LASER_PWM_PIN 4 // MUST BE HARDWARE PWM + #define SPINDLE_LASER_ENABLE_PIN 17 // Pin should have a pullup! + #define SPINDLE_DIR_PIN 5 +#endif diff --git a/Marlin/pins_MIGHTYBOARD_REVE.h b/Marlin/pins_MIGHTYBOARD_REVE.h index 933486177..bd13a379d 100644 --- a/Marlin/pins_MIGHTYBOARD_REVE.h +++ b/Marlin/pins_MIGHTYBOARD_REVE.h @@ -41,6 +41,17 @@ * */ +/** + * Rev B 2 JAN 2017 + * + * Added pin definitions for: + * M3, M4 & M5 spindle control commands + * case light + * + * Corrected pin assignment for MOSFET_B_PIN pin. Changed it from 9 to 11. The port + * number (B5) agrees with the schematic but B5 is assigned to logical pin 11. + */ + #if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__) #error "Oops! Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu." #endif @@ -140,7 +151,7 @@ // With no heated bed, an additional 24V fan is possible. // #define MOSFET_A_PIN 6 // H3 -#define MOSFET_B_PIN 11 // B5 +#define MOSFET_B_PIN 11 // B5 - Rev A of this file had this pin assigned to 9 #define MOSFET_C_PIN 45 // L4 #define MOSFET_D_PIN 44 // L5 @@ -193,11 +204,11 @@ #define LED_PIN 13 // B7 #define CUTOFF_RESET_PIN 16 // H1 #define CUTOFF_TEST_PIN 17 // H0 +#define CASE_LIGHT_PIN 44 // L5 MUST BE HARDWARE PWM // // LCD / Controller // - #ifdef REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER #define LCD_PINS_RS 33 // C4, LCD-STROBE @@ -246,7 +257,6 @@ #endif - // // SD Card // @@ -255,7 +265,20 @@ #define MAX_PIN THERMO_SCK_PIN -//check if all pins are defined in mega/pins_arduino.h +// +// M3/M4/M5 - Spindle/Laser Control +// +#define SPINDLE_LASER_ENABLE_PIN 66 // K4 Pin should have a pullup! +#define SPINDLE_LASER_PWM_PIN 8 // H5 MUST BE HARDWARE PWM +#define SPINDLE_DIR_PIN 67 // K5 + + + + + + + +// Check if all pins are defined in mega/pins_arduino.h #include static_assert(NUM_DIGITAL_PINS > MAX_PIN, "add missing pins to [arduino dir]/hardware/arduino/avr/variants/mega/pins_arduino.h based on fastio.h" "to digital_pin_to_port_PGM, digital_pin_to_bit_mask_PGM, digital_pin_to_timer_PGM, NUM_DIGITAL_PINS, see below"); diff --git a/Marlin/pins_MINIRAMBO.h b/Marlin/pins_MINIRAMBO.h index 551926a5f..de3c6b08a 100644 --- a/Marlin/pins_MINIRAMBO.h +++ b/Marlin/pins_MINIRAMBO.h @@ -111,6 +111,7 @@ // #define SDSS 53 #define LED_PIN 13 +#define CASE_LIGHT_PIN 9 // // LCD / Controller @@ -140,3 +141,12 @@ #endif // NEWPANEL #endif // ULTRA_LCD + +// +// M3/M4/M5 - Spindle/Laser Control +// + +// use P1 connector for spindle pins +#define SPINDLE_LASER_PWM_PIN 9 // MUST BE HARDWARE PWM +#define SPINDLE_LASER_ENABLE_PIN 18 // Pin should have a pullup! +#define SPINDLE_DIR_PIN 19 diff --git a/Marlin/pins_MINITRONICS.h b/Marlin/pins_MINITRONICS.h index d9a03c41f..43f63ab23 100644 --- a/Marlin/pins_MINITRONICS.h +++ b/Marlin/pins_MINITRONICS.h @@ -24,6 +24,13 @@ * Minitronics v1.0/1.1 pin assignments */ +/** + * Rev B 2 JAN 2017 + * + * Added pin definitions for M3, M4 & M5 spindle control commands + * + */ + #ifndef __AVR_ATmega1281__ #error "Oops! Make sure you have 'Minitronics' selected from the 'Tools -> Boards' menu." #endif @@ -123,3 +130,19 @@ #define SD_DETECT_PIN -1 // Minitronics doesn't use this #endif + +// +// M3/M4/M5 - Spindle/Laser Control +// +#if ENABLED(SPINDLE_LASER_ENABLE) // assumes we're only doing CNC work (no 3D printing) + #undef HEATER_BED_PIN + #undef TEMP_BED_PIN // need to free up some pins but also need to + #undef TEMP_0_PIN // re-assign them (to unused pins) because Marlin + #undef TEMP_1_PIN // requires the presence of certain pins or else it + #define HEATER_BED_PIN 4 // won't compile + #define TEMP_BED_PIN 50 + #define TEMP_0_PIN 51 + #define SPINDLE_LASER_ENABLE_PIN 52 // using A6 because it already has a pull up on it + #define SPINDLE_LASER_PWM_PIN 3 // WARNING - LED & resistor pull up to +12/+24V stepper voltage + #define SPINDLE_DIR_PIN 53 +#endif diff --git a/Marlin/pins_MKS_BASE.h b/Marlin/pins_MKS_BASE.h index 12bf8b749..dcf9b90f2 100644 --- a/Marlin/pins_MKS_BASE.h +++ b/Marlin/pins_MKS_BASE.h @@ -22,6 +22,8 @@ /** * MKS BASE 1.0 – Arduino Mega2560 with RAMPS v1.4 pin assignments + * + * Rev B - Override pin definitions for CASE_LIGHT and M3/M4/M5 spindle control */ #if HOTENDS > 2 || E_STEPPERS > 2 @@ -36,4 +38,13 @@ // Power outputs EFBF or EFBE #define MOSFET_D_PIN 7 -#include "pins_RAMPS.h" \ No newline at end of file +#define CASE_LIGHT_PIN 2 + +// +// M3/M4/M5 - Spindle/Laser Control +// +#define SPINDLE_LASER_PWM_PIN 2 // MUST BE HARDWARE PWM +#define SPINDLE_LASER_ENABLE_PIN 15 // Pin should have a pullup! +#define SPINDLE_DIR_PIN 19 + +#include "pins_RAMPS.h" diff --git a/Marlin/pins_OMCA.h b/Marlin/pins_OMCA.h index 545c8646f..8715efcd4 100644 --- a/Marlin/pins_OMCA.h +++ b/Marlin/pins_OMCA.h @@ -51,6 +51,31 @@ * REF http://sanguino.cc/hardware */ +/** + * Rev B 26 DEC 2016 + * + * added pointer to a current Arduino IDE extension + * + */ + +/** + * A useable Arduino IDE extension (board manager) can be found at + * https://github.com/Lauszus/Sanguino + * + * This extension has been tested on Arduino 1.6.12 & 1.8.0 + * + * Here's the JSON path: + * https://raw.githubusercontent.com/Lauszus/Sanguino/master/package_lauszus_sanguino_index.json + * + * When installing select 1.0.2 + * + * Installation instructions can be found at https://learn.sparkfun.com/pages/CustomBoardsArduino + * Just use the above JSON URL instead of Sparkfun's JSON. + * + * Once installed select the Sanguino board and then select the CPU. + * + */ + #if !defined(__AVR_ATmega644P__) && !defined(__AVR_ATmega644__) #error "Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu. (Final OMCA board)" #endif diff --git a/Marlin/pins_OMCA_A.h b/Marlin/pins_OMCA_A.h index d325a648d..3686973c9 100644 --- a/Marlin/pins_OMCA_A.h +++ b/Marlin/pins_OMCA_A.h @@ -50,8 +50,33 @@ * */ +/** + * Rev B 26 DEC 2016 + * + * added pointer to a current Arduino IDE extension + * + */ + +/** + * A useable Arduino IDE extension (board manager) can be found at + * https://github.com/Lauszus/Sanguino + * + * This extension has been tested on Arduino 1.6.12 & 1.8.0 + * + * Here's the JSON path: + * https://raw.githubusercontent.com/Lauszus/Sanguino/master/package_lauszus_sanguino_index.json + * + * When installing select 1.0.2 + * + * Installation instructions can be found at https://learn.sparkfun.com/pages/CustomBoardsArduino + * Just use the above JSON URL instead of Sparkfun's JSON. + * + * Once installed select the Sanguino board and then select the CPU. + * + */ + #ifndef __AVR_ATmega644__ - #error "Oops! Make sure you have 'SanguinoA' selected from the 'Tools -> Boards' menu." + #error "Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu." #endif #define BOARD_NAME "Alpha OMCA" diff --git a/Marlin/pins_RAMBO.h b/Marlin/pins_RAMBO.h index e4df16677..c99cd7923 100644 --- a/Marlin/pins_RAMBO.h +++ b/Marlin/pins_RAMBO.h @@ -137,6 +137,7 @@ #define LED_PIN 13 #define FILWIDTH_PIN 3 // Analog Input #define PS_ON_PIN 4 +#define CASE_LIGHT_PIN 46 // // LCD / Controller @@ -208,3 +209,10 @@ #endif // !NEWPANEL #endif // ULTRA_LCD + +// +// M3/M4/M5 - Spindle/Laser Control +// +#define SPINDLE_LASER_PWM_PIN 45 // MUST BE HARDWARE PWM +#define SPINDLE_LASER_ENABLE_PIN 31 // Pin should have a pullup! +#define SPINDLE_DIR_PIN 32 diff --git a/Marlin/pins_RAMPS.h b/Marlin/pins_RAMPS.h index 767e99085..9bd1a252c 100644 --- a/Marlin/pins_RAMPS.h +++ b/Marlin/pins_RAMPS.h @@ -204,6 +204,16 @@ #define PS_ON_PIN 12 +#if !PIN_EXISTS(CASE_LIGHT) && !defined(SPINDLE_LASER_ENABLE_PIN) + #undef CASE_LIGHT_PIN + #if !defined(NUM_SERVOS) || NUM_SERVOS == 0 // try to use servo connector first + #define CASE_LIGHT_PIN 6 // MUST BE HARDWARE PWM + #elif !(ENABLED(ULTRA_LCD) && ENABLED(NEWPANEL) \ + && (ENABLED(PANEL_ONE) || ENABLED(VIKI2) || ENABLED(miniVIKI) || ENABLED(MINIPANEL) || ENABLED(REPRAPWORLD_KEYPAD))) // try to use AUX 2 + #define CASE_LIGHT_PIN 44 // MUST BE HARDWARE PWM + #endif +#endif + // // LCD / Controller // @@ -361,3 +371,19 @@ #endif // NEWPANEL #endif // ULTRA_LCD + +// +// M3/M4/M5 - Spindle/Laser Control +// +#if ENABLED(SPINDLE_LASER_ENABLE) && !PIN_EXISTS(SPINDLE_LASER_ENABLE_PIN) + #if !defined(NUM_SERVOS) || NUM_SERVOS == 0 // try to use servo connector first + #define SPINDLE_LASER_ENABLE_PIN 4 // Pin should have a pullup/pulldown! + #define SPINDLE_LASER_PWM_PIN 6 // MUST BE HARDWARE PWM + #define SPINDLE_DIR_PIN 5 + #elif !(ENABLED(ULTRA_LCD) && ENABLED(NEWPANEL) \ + && (ENABLED(PANEL_ONE) || ENABLED(VIKI2) || ENABLED(miniVIKI) || ENABLED(MINIPANEL) || ENABLED(REPRAPWORLD_KEYPAD))) // try to use AUX 2 + #define SPINDLE_LASER_ENABLE_PIN 40 // Pin should have a pullup/pulldown! + #define SPINDLE_LASER_PWM_PIN 44 // MUST BE HARDWARE PWM + #define SPINDLE_DIR_PIN 65 + #endif +#endif diff --git a/Marlin/pins_RAMPS_OLD.h b/Marlin/pins_RAMPS_OLD.h index 29812bbdf..870f2fbd1 100644 --- a/Marlin/pins_RAMPS_OLD.h +++ b/Marlin/pins_RAMPS_OLD.h @@ -101,3 +101,11 @@ #define SDPOWER 48 #define SDSS 53 #define LED_PIN 13 +#define CASE_LIGHT_PIN 45 // MUST BE HARDWARE PWM + +// +// M3/M4/M5 - Spindle/Laser Control +// +#define SPINDLE_LASER_ENABLE_PIN 41 // Pin should have a pullup/pulldown! +#define SPINDLE_LASER_PWM_PIN 45 // MUST BE HARDWARE PWM +#define SPINDLE_DIR_PIN 43 diff --git a/Marlin/pins_RIGIDBOARD.h b/Marlin/pins_RIGIDBOARD.h index 0e48caf73..5bd06e40e 100644 --- a/Marlin/pins_RIGIDBOARD.h +++ b/Marlin/pins_RIGIDBOARD.h @@ -82,16 +82,16 @@ // // Heaters / Fans // -#undef HEATER_BED_PIN +#undef HEATER_BED_PIN #define HEATER_BED_PIN 10 -#undef FAN_PIN +#undef FAN_PIN #define FAN_PIN 8 // Same as RAMPS_13_EEF // // Misc. Functions // -#undef PS_ON_PIN +#undef PS_ON_PIN #define PS_ON_PIN -1 // @@ -110,24 +110,24 @@ #define BTN_RT 32 // 'R' button - #undef BTN_ENC + #undef BTN_ENC #define BTN_ENC 31 // Disable encoder - #undef BTN_EN1 + #undef BTN_EN1 #define BTN_EN1 -1 - #undef BTN_EN2 + #undef BTN_EN2 #define BTN_EN2 -1 - #undef SD_DETECT_PIN + #undef SD_DETECT_PIN #define SD_DETECT_PIN 22 #elif ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) - #undef SD_DETECT_PIN + #undef SD_DETECT_PIN #define SD_DETECT_PIN 22 - #undef KILL_PIN + #undef KILL_PIN #define KILL_PIN 32 #endif diff --git a/Marlin/pins_RUMBA.h b/Marlin/pins_RUMBA.h index 376197c55..23a9c3ad1 100644 --- a/Marlin/pins_RUMBA.h +++ b/Marlin/pins_RUMBA.h @@ -100,7 +100,7 @@ #endif #if TEMP_SENSOR_2 == -1 - #define TEMP_2_PIN 7 // Analog Input (connector *K3* on RUMBA thermocouple ADD ON is used <-- this can't be used when TEMP_SENSOR_BED is defined as thermocouple) + #define TEMP_2_PIN 7 // Analog Input (connector *K3* on RUMBA thermocouple ADD ON is used <-- this can not be used when TEMP_SENSOR_BED is defined as thermocouple) #else #define TEMP_2_PIN 13 // Analog Input (default connector for thermistor *T2* on rumba board is used) #endif @@ -109,7 +109,7 @@ //#define TEMP_X_PIN 12 // Analog Input (default connector for thermistor *T3* on rumba board is used) #if TEMP_SENSOR_BED == -1 - #define TEMP_BED_PIN 7 // Analog Input (connector *K3* on RUMBA thermocouple ADD ON is used <-- this can't be used when TEMP_SENSOR_2 is defined as thermocouple) + #define TEMP_BED_PIN 7 // Analog Input (connector *K3* on RUMBA thermocouple ADD ON is used <-- this can not be used when TEMP_SENSOR_2 is defined as thermocouple) #else #define TEMP_BED_PIN 11 // Analog Input (default connector for thermistor *THB* on rumba board is used) #endif @@ -133,6 +133,7 @@ #define LED_PIN 13 #define PS_ON_PIN 45 #define KILL_PIN 46 +#define CASE_LIGHT_PIN 45 // // LCD / Controller @@ -148,3 +149,10 @@ #define BTN_EN1 11 #define BTN_EN2 12 #define BTN_ENC 43 + +// +// M3/M4/M5 - Spindle/Laser Control +// +#define SPINDLE_LASER_PWM_PIN 4 // MUST BE HARDWARE PWM +#define SPINDLE_LASER_ENABLE_PIN 14 // Pin should have a pullup! +#define SPINDLE_DIR_PIN 15 diff --git a/Marlin/pins_SANGUINOLOLU_11.h b/Marlin/pins_SANGUINOLOLU_11.h index 62d92b61e..6bac9d7a8 100644 --- a/Marlin/pins_SANGUINOLOLU_11.h +++ b/Marlin/pins_SANGUINOLOLU_11.h @@ -24,6 +24,33 @@ * Sanguinololu board pin assignments */ +/** + * Rev B 26 DEC 2016 + * + * 1) added pointer to a current Arduino IDE extension + * 2) added support for M3, M4 & M5 spindle control commands + * 3) added case light pin definition + * + */ + +/** + * A useable Arduino IDE extension (board manager) can be found at + * https://github.com/Lauszus/Sanguino + * + * This extension has been tested on Arduino 1.6.12 & 1.8.0 + * + * Here's the JSON path: + * https://raw.githubusercontent.com/Lauszus/Sanguino/master/package_lauszus_sanguino_index.json + * + * When installing select 1.0.2 + * + * Installation instructions can be found at https://learn.sparkfun.com/pages/CustomBoardsArduino + * Just use the above JSON URL instead of Sparkfun's JSON. + * + * Once installed select the Sanguino board and then select the CPU. + * + */ + #if !defined(__AVR_ATmega644P__) && !defined(__AVR_ATmega1284P__) #error "Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu." #endif @@ -96,19 +123,26 @@ // // Misc. Functions // + /** - * On some broken versions of the Sanguino libraries the pin definitions are wrong, - * which then needs SDSS as pin 24. But you should upgrade your Sanguino libraries! See #368. + * In some versions of the Sanguino libraries the pin + * definitions are wrong, with SDSS = 24 and LED_PIN = 28 (Melzi). + * If you encounter issues with these pins, upgrade your + * Sanguino libraries! See #368. */ //#define SDSS 24 #define SDSS 31 #if IS_MELZI - #define LED_PIN 27 // On some broken versions of the Sanguino libraries the pin definitions are wrong, so LED_PIN needs to be 28. But you should upgrade your Sanguino libraries! See #368. + #define LED_PIN 27 #elif MB(STB_11) #define LCD_BACKLIGHT_PIN 17 // LCD backlight LED #endif +#if DISABLED(SPINDLE_LASER_ENABLE) && ENABLED(SANGUINOLOLU_V_1_2) && !(ENABLED(ULTRA_LCD) && ENABLED(NEWPANEL)) // try to use IO Header + #define CASE_LIGHT_PIN 4 // MUST BE HARDWARE PWM - see if IO Header is available +#endif + // // LCD / Controller // @@ -181,14 +215,62 @@ #else #define BTN_ENC 30 #endif - #elif ENABLED(OLED_PANEL_TINYBOY2) - #define BTN_ENC 28 - #define LCD_SDSS -1 - #else // !Panelolu2, !TinyBoy2 + #else // !Panelolu2 #define BTN_ENC 16 #define LCD_SDSS 28 // Smart Controller SD card reader rather than the Melzi - #endif // !Panelolu2, !TinyBoy2 + #endif // !Panelolu2 #define SD_DETECT_PIN -1 #endif // ULTRA_LCD && NEWPANEL + +// +// M3/M4/M5 - Spindle/Laser Control +// +#if ENABLED(SPINDLE_LASER_ENABLE) + #if !MB(AZTEEG_X1) && ENABLED(SANGUINOLOLU_V_1_2) && !(ENABLED(ULTRA_LCD) && ENABLED(NEWPANEL)) // try to use IO Header + + #define SPINDLE_LASER_ENABLE_PIN 10 // Pin should have a pullup/pulldown! + #define SPINDLE_LASER_PWM_PIN 4 // MUST BE HARDWARE PWM + #define SPINDLE_DIR_PIN 11 + + #elif !MB(MELZI) // use X stepper motor socket + + /** + * To control the spindle speed and have an LCD you must sacrifice + * the Extruder and pull some signals off the X stepper driver socket. + * + * The following assumes: + * - The X stepper driver socket is empty + * - The extruder driver socket has a driver board plugged into it + * - The X stepper wires are attached the the extruder connector + */ + + /** + * Where to get the spindle signals + * + * spindle signal socket name socket name + * ------- + * /ENABLE O| |O VMOT + * MS1 O| |O GND + * MS2 O| |O 2B + * MS3 O| |O 2A + * /RESET O| |O 1A + * /SLEEP O| |O 1B + * SPINDLE_LASER_PWM_PIN STEP O| |O VDD + * SPINDLE_LASER_ENABLE_PIN DIR O| |O GND + * ------- + * + * Note: Socket names vary from vendor to vendor. + */ + #undef X_DIR_PIN + #undef X_ENABLE_PIN + #undef X_STEP_PIN + #define X_DIR_PIN 0 + #define X_ENABLE_PIN 14 + #define X_STEP_PIN 1 + #define SPINDLE_LASER_PWM_PIN 15 // MUST BE HARDWARE PWM + #define SPINDLE_LASER_ENABLE_PIN 21 // Pin should have a pullup! + #define SPINDLE_DIR_PIN -1 // No pin available on the socket for the direction pin + #endif +#endif // SPINDLE_LASER_ENABLE diff --git a/Marlin/pins_SAV_MKI.h b/Marlin/pins_SAV_MKI.h index 019139d1e..2048af925 100644 --- a/Marlin/pins_SAV_MKI.h +++ b/Marlin/pins_SAV_MKI.h @@ -115,7 +115,6 @@ #define EXT_AUX_A4 4 // Analog #define EXT_AUX_A4_IO 44 // Digital IO, 42 (teensy), 44 (marlin) - // // LCD / Controller // @@ -134,10 +133,23 @@ #endif // SAV_3DLCD #if ENABLED(SAV_3DLCD) || ENABLED(SAV_3DGLCD) + #define BTN_EN1 EXT_AUX_A1_IO #define BTN_EN2 EXT_AUX_A0_IO #define BTN_ENC EXT_AUX_PWM_D24 #define KILL_PIN EXT_AUX_A2_IO #define HOME_PIN EXT_AUX_A4_IO -#endif // SAV_3DLCD || SAV_3DGLCD + +#else // Try to use the expansion header for spindle control + + // + // M3/M4/M5 - Spindle/Laser Control + // + #define SPINDLE_LASER_PWM_PIN 24 // 12 AT90USB… pin # + #define SPINDLE_LASER_ENABLE_PIN 39 // Pin should have a pullup! 41 AT90USB… pin # + #define SPINDLE_DIR_PIN 40 // 42 AT90USB… pin # + + #define CASE_LIGHT_PIN 0 // 24 AT90USB… pin # + +#endif diff --git a/Marlin/pins_SETHI.h b/Marlin/pins_SETHI.h index 12521f40a..a05bb9eb2 100644 --- a/Marlin/pins_SETHI.h +++ b/Marlin/pins_SETHI.h @@ -24,6 +24,31 @@ * Sethi 3D_1 pin assignments - www.sethi3d.com.br */ +/** + * Rev B 26 DEC 2016 + * + * added pointer to a current Arduino IDE extension + * this assumes that this board uses the Sanguino pin map + */ + +/** + * A useable Arduino IDE extension (board manager) can be found at + * https://github.com/Lauszus/Sanguino + * + * This extension has been tested on Arduino 1.6.12 & 1.8.0 + * + * Here's the JSON path: + * https://raw.githubusercontent.com/Lauszus/Sanguino/master/package_lauszus_sanguino_index.json + * + * When installing select 1.0.2 + * + * Installation instructions can be found at https://learn.sparkfun.com/pages/CustomBoardsArduino + * Just use the above JSON URL instead of Sparkfun's JSON. + * + * Once installed select the Sanguino board and then select the CPU. + * + */ + #if !defined(__AVR_ATmega644P__) && !defined(__AVR_ATmega644__) && !defined(__AVR_ATmega1284P__) #error "Oops! Make sure you have 'Sethi 3D' selected from the 'Tools -> Boards' menu." #endif diff --git a/Marlin/pins_TEENSY2.h b/Marlin/pins_TEENSY2.h index b7cf484be..971de27e8 100644 --- a/Marlin/pins_TEENSY2.h +++ b/Marlin/pins_TEENSY2.h @@ -124,6 +124,7 @@ #define SDSS 20 // 8 #define LED_PIN 6 #define PS_ON_PIN 27 +#define CASE_LIGHT_PIN 1 // MUST BE HARDWARE PWM // // LCD / Controller @@ -139,3 +140,10 @@ #define BTN_EN2 39 #define BTN_ENC 40 #endif + +// +// M3/M4/M5 - Spindle/Laser Control +// +#define SPINDLE_LASER_ENABLE_PIN 5 // Pin should have a pullup! +#define SPINDLE_LASER_PWM_PIN 0 // MUST BE HARDWARE PWM +#define SPINDLE_DIR_PIN 7 diff --git a/Marlin/pins_TEENSYLU.h b/Marlin/pins_TEENSYLU.h index b0fc8aec5..d845e312e 100644 --- a/Marlin/pins_TEENSYLU.h +++ b/Marlin/pins_TEENSYLU.h @@ -12,27 +12,82 @@ * * 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 + * 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 . + * along with this program. If not, see . * */ /** - * Teensylu 0.7 pin assignments (AT90USB1286) - * Requires the Teensyduino software with Teensy++ 2.0 selected in Arduino IDE! - * http://www.pjrc.com/teensy/teensyduino.html - * See http://reprap.org/wiki/Printrboard for more info + * rev B 30 DEC 2016 + * + * The original version of this file did NOT result in a useful program because: + * 1. The pin numbers assumed that the "#define AT90USBxx_TEENSYPP_ASSIGNMENTS" line + * in FASTIO.h was commented out. There wasn't an Arduino IDE 1.6.x extension/package + * that supported this pin map so the latest Marlin wouldn't compile. + * 2. The silkscreen for the four end stops don't agree with the schematic. Activating + * the X endstop would tell the software that the Y endstop just went active. + * 3. The thermistor inputs also had heater names assigned to them. The result was + * thermistor inputs that were set to digital outputs. + * + * Rev B corrects the above problems by: + * 1. The "Marlin_AT90USB" extension/package was developed. This extension enables the + * latest Marlin software to compile using Arduino IDE 1.6.x and 1.80. + * 2. The endstop pin numbers in this file were changed to match the silkscreen. This + * makes it a little confusing when trying to correlate the schematic with the pin + * numbers used in this file. + * 3. The offending heater names were deleted. + * + * To create a useable image for Teensylu do the following: + * a) Install the Marlin_AT90USB extension with either of the following methods: + * Automatic - paste this URL into preferences and then use Boards manager + * https://rawgit.com/Bob-the-Kuhn/Marlin_AT90USB/master/package_MARLIN_AT90USB_index.json + * Manual: + * 1. Copy the following URL into Go to "https://github.com/Bob-the-Kuhn/Marlin_AT90USB", + * click on the "Clone or Download" button and then click on "Download ZIP" button. + * 2. Unzip the file, find the "Marlin_AT90USB" directory and then copy it to the + * hardware directory in Arduino. The Arduino hardware directory will probably be + * located in a path similar to this: C:\Program Files (x86)\Arduino\hardware + * b) Connect the USBtinyISP to the board. + * c) In the Arduino IDE select the "AT90USB1286_STANDARD" board in the of the "Marlin_AT90USB" + * section and select the "USBtinyISP" programmer. + * d) In the Arduino IDE click on "burn bootloader". Don't worry about the "verify + * failed at 1F000" error message. + * e) The USBtinyISP programmer is no longer needed. Remove it. + * f) In FASTIO.h comment out the "#define AT90USBxx_TEENSYPP_ASSIGNMENTS" line. + * g) To upload a sketch do the following: + * 1. remove the jumper + * 2. press reset + * 3. click on the "upload" button in the Arduino IDE + * 4. wait until the upload finishes (less than a minute) + * 5. put the jumper back on + * 6. press the reset button + * + * + * NOTE - the "Marlin_AT90USB" pin maps make PWM0A available rather than the usual PWM1C. + * These PWMs share the same physical pin. Marlin uses TIMER1 to generate + * interrupts and sets it up such that PWM1A, PWM1B & PWM1C can not be used. */ -#ifndef __AVR_AT90USB1286__ - #error "Oops! Make sure you have 'Teensy++ 2.0' selected from the 'Tools -> Boards' menu." + /** + * SILKSCREEN ERROR + * + * The silkscreen for the endstops do NOT match the schematic. The silkscreen SHOULD + * read (from left to right) X-STOP, Y-STOP, Z-STOP & E-STOP. The silkscreen actually + * reads E-STOP, X-STOP, Y-STOP & Z-STOP. + * + * The pin assignments in this file match the silkscreen. + */ + + +#if !defined(__AVR_AT90USB1286__) && !defined(__AVR_AT90USB1286P__) + #error "Oops! Make sure you have 'AT90USB1286_STANDARD' selected from the 'Tools -> Boards' menu." #endif -#if ENABLED(AT90USBxx_TEENSYPP_ASSIGNMENTS) // use Teensyduino Teensy++2.0 pin assignments instead of Marlin traditional. - #error "These Teensylu assignments depend on traditional Marlin assignments, not AT90USBxx_TEENSYPP_ASSIGNMENTS in fastio.h" +#if ENABLED(AT90USBxx_TEENSYPP_ASSIGNMENTS) + #error "please disable (comment out) the AT90USBxx_TEENSYPP_ASSIGNMENTS flag in FASTIO.h " #endif #define BOARD_NAME "Teensylu" @@ -40,74 +95,84 @@ #define USBCON 1286 // Disable MarlinSerial etc. #define LARGE_FLASH true + +// +// Limit Switche definitions that match the SCHEMATIC +// +//#define X_STOP_PIN 13 +//#define Y_STOP_PIN 14 +//#define Z_STOP_PIN 15 +//#define E_STOP_PIN 36 + + // -// Limit Switches +// Limit Switch definitions that match the SILKSCREEN // -#define X_STOP_PIN 13 -#define Y_STOP_PIN 14 -#define Z_STOP_PIN 15 +#define X_STOP_PIN 14 +#define Y_STOP_PIN 15 +#define Z_STOP_PIN 36 +//#define E_STOP_PIN 13 // // Steppers // -#define X_STEP_PIN 0 -#define X_DIR_PIN 1 -#define X_ENABLE_PIN 39 +#define X_STEP_PIN 0 +#define X_DIR_PIN 1 +#define X_ENABLE_PIN 39 -#define Y_STEP_PIN 2 -#define Y_DIR_PIN 3 -#define Y_ENABLE_PIN 38 +#define Y_STEP_PIN 2 +#define Y_DIR_PIN 3 +#define Y_ENABLE_PIN 38 -#define Z_STEP_PIN 4 -#define Z_DIR_PIN 5 -#define Z_ENABLE_PIN 23 +#define Z_STEP_PIN 4 +#define Z_DIR_PIN 5 +#define Z_ENABLE_PIN 23 + +#define E0_STEP_PIN 6 +#define E0_DIR_PIN 7 +#define E0_ENABLE_PIN 19 -#define E0_STEP_PIN 6 -#define E0_DIR_PIN 7 -#define E0_ENABLE_PIN 19 -// // Temperature Sensors -// -#define TEMP_0_PIN 7 // Analog Input (Extruder) -#define TEMP_BED_PIN 6 // Analog Input (Bed) + +#define TEMP_0_PIN 7 // Analog Input (Extruder) +#define TEMP_BED_PIN 6 // Analog Input (Bed) // // Heaters / Fans // -#define HEATER_0_PIN 21 // Extruder -#define HEATER_1_PIN 46 -#define HEATER_2_PIN 47 -#define HEATER_BED_PIN 20 - -// If soft or fast PWM is off then use Teensyduino pin numbering, Marlin -// fastio pin numbering otherwise -#if ENABLED(FAN_SOFT_PWM) || ENABLED(FAST_PWM_FAN) - #define FAN_PIN 22 -#else - #define FAN_PIN 16 -#endif +#define HEATER_0_PIN 21 // Extruder +#define HEATER_BED_PIN 20 + +#define FAN_PIN 22 // // Misc. Functions // -#define SDSS 8 +#define SDSS 8 +#define CASE_LIGHT_PIN 24 // // LCD / Controller // #if ENABLED(ULTRA_LCD) && ENABLED(NEWPANEL) - #define BEEPER_PIN -1 + #define BEEPER_PIN -1 #if ENABLED(LCD_I2C_PANELOLU2) - #define BTN_EN1 27 // RX1 - fastio.h pin mapping 27 - #define BTN_EN2 26 // TX1 - fastio.h pin mapping 26 - #define BTN_ENC 43 // A3 - fastio.h pin mapping 43 - #define SDSS 40 // use SD card on Panelolu2 (Teensyduino pin mapping) + #define BTN_EN1 27 + #define BTN_EN2 26 + #define BTN_ENC 43 + #define SDSS 40 // use SD card on Panelolu2 #endif // LCD_I2C_PANELOLU2 - #define SD_DETECT_PIN -1 + #define SD_DETECT_PIN -1 #endif // ULTRA_LCD && NEWPANEL +// +// M3/M4/M5 - Spindle/Laser Control +// +#define SPINDLE_LASER_PWM_PIN 12 // MUST BE HARDWARE PWM +#define SPINDLE_LASER_ENABLE_PIN 41 // Pin should have a pullup! +#define SPINDLE_DIR_PIN 42 diff --git a/Marlin/pins_ULTIMAIN_2.h b/Marlin/pins_ULTIMAIN_2.h index 731f6f88f..d4b99fafc 100644 --- a/Marlin/pins_ULTIMAIN_2.h +++ b/Marlin/pins_ULTIMAIN_2.h @@ -24,6 +24,14 @@ * Ultiboard v2.0 pin assignments */ +/** + * Rev B 2 JAN 2017 + * + * Added pin definitions for: + * M3, M4 & M5 spindle control commands + * case light + */ + #ifndef __AVR_ATmega2560__ #error "Oops! Make sure you have 'Arduino Mega 2560' selected from the 'Tools -> Boards' menu." #endif @@ -110,3 +118,16 @@ #define BTN_EN1 40 #define BTN_EN2 41 #define BTN_ENC 19 + +// +// M3/M4/M5 - Spindle/Laser Control +// +#if ENABLED(SPINDLE_LASER_ENABLE) // use the LED_PIN for spindle speed control or case light + #undef LED_PIN + #define SPINDLE_DIR_PIN 16 + #define SPINDLE_LASER_ENABLE_PIN 17 // Pin should have a pullup! + #define SPINDLE_LASER_PWM_PIN 8 // MUST BE HARDWARE PWM +#else + #undef LED_PIN + #define CASE_LIGHT_PIN 8 +#endif diff --git a/Marlin/pins_ULTIMAKER.h b/Marlin/pins_ULTIMAKER.h index 4b4b31ad8..cb1176807 100644 --- a/Marlin/pins_ULTIMAKER.h +++ b/Marlin/pins_ULTIMAKER.h @@ -24,6 +24,14 @@ * Ultimaker pin assignments */ +/** + * Rev B 2 JAN 2017 + * + * Added pin definitions for: + * M3, M4 & M5 spindle control commands + * case light + */ + #if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__) #error "Oops! Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu." #endif @@ -102,6 +110,7 @@ #define LED_PIN 13 #define PS_ON_PIN 12 #define SUICIDE_PIN 54 // PIN that has to be turned on right after start, to keep power flowing. +#define CASE_LIGHT_PIN 8 // // LCD / Controller @@ -146,3 +155,10 @@ #endif // !NEWPANEL #endif // ULTRA_LCD + +// +// M3/M4/M5 - Spindle/Laser Control +// +#define SPINDLE_LASER_PWM_PIN 9 // MUST BE HARDWARE PWM +#define SPINDLE_LASER_ENABLE_PIN 10 // Pin should have a pullup! +#define SPINDLE_DIR_PIN 11 // use the EXP3 PWM header diff --git a/Marlin/pins_ULTIMAKER_OLD.h b/Marlin/pins_ULTIMAKER_OLD.h index b42ba6958..5dafda2d3 100644 --- a/Marlin/pins_ULTIMAKER_OLD.h +++ b/Marlin/pins_ULTIMAKER_OLD.h @@ -24,6 +24,42 @@ * Ultimaker pin assignments (Old electronics) */ + /** + * Rev B 3 JAN 2017 + * + * Details on pin definitions for M3, M4 & M5 spindle control commands and for + * the CASE_LIGHT_PIN are at the end of this file. + * + * This started out as an attempt to add pin definitions for M3, M4 & M5 spindle + * control commands but quickly turned into a head scratcher as the sources for + * the revisions provided inconsistent information. + * + * As best I can determine: + * 1.5.3 boards should use the pins_ULTIMAKER.h file which means the BOARD_NAME + * define in this file should say 1.5.3 rather than 1.5.4 + * This file is meant for 1.1 - 1.3 boards. + * The endstops for the 1.0 boards use different definitions than on the 1.1 - 1.3 + * boards. + * + * I've added sections that have the 1.0 and 1.5.3 + endstop definitions so you can + * easily switch if needed. I've also copied over the 1.5.3 + LCD definitions. + * + * To be 100% sure of the board you have: + * 1. In Configuration_adv.h enable "PINS_DEBUGGING" + * 2. Compile & uploade + * 3. Enter the command "M43 W1 I1". This command will report that pin nmumber and + * name of any pin that changes state. + * 4. Using a 1k (approximately) resistor pull the endstops and some of the LCD pins + * to ground and see what is reported. + * 5. If the reported pin doesn't match the file then try a different board revision + * and repeat steps 2 - 5 + */ + +#define board_rev_1_1_TO_1_3 +//#define board_rev_1_0 +//#define board_rev_1_5 + + #if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__) #error "Oops! Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu." #endif @@ -37,18 +73,38 @@ // // Limit Switches // -#define X_MIN_PIN 15 -#define X_MAX_PIN 14 -#define Y_MIN_PIN 17 -#define Y_MAX_PIN 16 -#define Z_MIN_PIN 19 -#define Z_MAX_PIN 18 +#if ENABLED(board_rev_1_1_TO_1_3) + #define X_MIN_PIN 15 // SW1 + #define X_MAX_PIN 14 // SW2 + #define Y_MIN_PIN 17 // SW3 + #define Y_MAX_PIN 16 // SW4 + #define Z_MIN_PIN 19 // SW5 + #define Z_MAX_PIN 18 // SW6 +#endif + +#if ENABLED(board_rev_1_0) + #define X_MIN_PIN 13 // SW1 + #define X_MAX_PIN 12 // SW2 + #define Y_MIN_PIN 11 // SW3 + #define Y_MAX_PIN 10 // SW4 + #define Z_MIN_PIN 9 // SW5 + #define Z_MAX_PIN 8 // SW6 +#endif + +#if ENABLED(board_rev_1_5) + #define X_MIN_PIN 22 + #define X_MAX_PIN 24 + #define Y_MIN_PIN 26 + #define Y_MAX_PIN 28 + #define Z_MIN_PIN 30 + #define Z_MAX_PIN 32 +#endif // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 18 + #define Z_MIN_PROBE_PIN Z_MAX_PIN #endif // @@ -70,9 +126,9 @@ #define E0_DIR_PIN 45 #define E0_ENABLE_PIN 41 -#define E1_STEP_PIN -1 -#define E1_DIR_PIN -1 -#define E1_ENABLE_PIN -1 +#define E1_STEP_PIN -1 // 49 +#define E1_DIR_PIN -1 // 47 +#define E1_ENABLE_PIN -1 // 48 // // Temperature Sensors @@ -84,14 +140,144 @@ // Heaters / Fans // #define HEATER_0_PIN 2 -#define HEATER_1_PIN 1 +//#define HEATER_1_PIN 3 // used for case light Rev A said "1" +#define HEATER_BED_PIN 4 // // LCD / Controller // -#define LCD_PINS_RS 24 -#define LCD_PINS_ENABLE 22 -#define LCD_PINS_D4 36 -#define LCD_PINS_D5 34 -#define LCD_PINS_D6 32 -#define LCD_PINS_D7 30 +#if ENABLED(board_rev_1_0) || ENABLED(board_rev_1_1_TO_1_3) + #define LCD_PINS_RS 24 + #define LCD_PINS_ENABLE 22 + #define LCD_PINS_D4 36 + #define LCD_PINS_D5 34 + #define LCD_PINS_D6 32 + #define LCD_PINS_D7 30 +#elif ENABLED(board_rev_1_5) && ENABLED(ULTRA_LCD) + + #define BEEPER_PIN 18 + + #if ENABLED(NEWPANEL) + + #define LCD_PINS_RS 20 + #define LCD_PINS_ENABLE 17 + #define LCD_PINS_D4 16 + #define LCD_PINS_D5 21 + #define LCD_PINS_D6 5 + #define LCD_PINS_D7 6 + + // buttons are directly attached + #define BTN_EN1 40 + #define BTN_EN2 42 + #define BTN_ENC 19 + + #define SD_DETECT_PIN 38 + + #else // !NEWPANEL - Old style panel with shift register + + // buttons are attached to a shift register + #define SHIFT_CLK 38 + #define SHIFT_LD 42 + #define SHIFT_OUT 40 + #define SHIFT_EN 17 + + #define LCD_PINS_RS 16 + #define LCD_PINS_ENABLE 5 + #define LCD_PINS_D4 6 + #define LCD_PINS_D5 21 + #define LCD_PINS_D6 20 + #define LCD_PINS_D7 19 + + #define SD_DETECT_PIN -1 + + #endif // !NEWPANEL + +#endif // ULTRA_LCD + +// +// case light - see spindle section for more info on available hardware PWMs +// +#if !PIN_EXISTS(CASE_LIGHT) && ENABLED(board_rev_1_5) + #define CASE_LIGHT_PIN 7 // use PWM - MUST BE HARDWARE PWM +#endif + +// +// M3/M4/M5 - Spindle/Laser Control +// +#if ENABLED(SPINDLE_LASER_ENABLE) + + #if ENABLED(board_rev_1_0) // use the last three SW positions + + #undef Z_MIN_PROBE_PIN + #undef X_MIN_PIN // SW1 + #undef X_MAX_PIN // SW2 + #undef Y_MIN_PIN // SW3 + #undef Y_MAX_PIN // SW4 + #undef Z_MIN_PIN // SW5 + #undef Z_MAX_PIN // SW6 + + #define X_STOP_PIN 13 // SW1 (didn't change) - also has a useable hardware PWM + #define Y_STOP_PIN 12 // SW2 + #define Z_STOP_PIN 11 // SW3 + + #define SPINDLE_DIR_PIN 10 // SW4 + #define SPINDLE_LASER_PWM_PIN 9 // SW5 MUST BE HARDWARE PWM + #define SPINDLE_LASER_ENABLE_PIN 8 // SW6 Pin should have a pullup! + + #elif ENABLED(board_rev_1_5) // use the same pins - but now they are on a different connector + + #define SPINDLE_DIR_PIN 10 // EXP3-6 (silkscreen says 10) + #define SPINDLE_LASER_PWM_PIN 9 // EXP3-7 (silkscreen says 9) MUST BE HARDWARE PWM + #define SPINDLE_LASER_ENABLE_PIN 8 // EXP3-8 (silkscreen says 8) Pin should have a pullup! + + #elif ENABLED(board_rev_1_1_TO_1_3) + + /** + * Only four hardware PWMs physically connected to anything on these boards: + * + * HEATER_0_PIN 2 silkscreen varies - usually "PWM 1" or "HEATER1" + * HEATER_1_PIN 3 silkscreen varies - usually "PWM 2" or "HEATER2" + * HEATER_BED_PIN 4 silkscreen varies - usually "PWM 3" or "HEATED BED" + * E0_DIR_PIN 45 + * + * If one of the heaters is used then special precautions will usually be needed. + * They have an LED and resistor pullup to +24V which could damage 3.3V-5V ICs. + */ + #if EXTRUDERS == 1 // Move E0 stepper module to the spare and get signals from E0 + #undef E0_STEP_PIN + #undef E0_DIR_PIN + #undef E0_ENABLE_PIN + #define E0_STEP_PIN 49 + #define E0_DIR_PIN 47 + #define E0_ENABLE_PIN 48 + #define SPINDLE_DIR_PIN 43 + #define SPINDLE_LASER_PWM_PIN 45 // MUST BE HARDWARE PWM + #define SPINDLE_LASER_ENABLE_PIN 41 // Pin should have a pullup! + #elif TEMP_SENSOR_BED == 0 // Can't use E0 so see if HEATER_BED_PIN is available + #undef HEATER_BED_PIN + #define SPINDLE_DIR_PIN 38 // Probably pin 4 on 10 pin connector closest to the E0 socket + #define SPINDLE_LASER_PWM_PIN 4 // MUST BE HARDWARE PWM - Special precautions usually needed. + #define SPINDLE_LASER_ENABLE_PIN 40 // Pin should have a pullup! (Probably pin 6 on the 10-pin + // connector closest to the E0 socket) + #endif + #endif +#endif + +/** + * Where to get the spindle signals on the E0 socket + * + * spindle signal socket name socket name + * ------- + * SPINDLE_LASER_ENABLE_PIN /ENABLE *| |O VMOT + * MS1 O| |O GND + * MS2 O| |O 2B + * MS3 O| |O 2A + * /RESET O| |O 1A + * /SLEEP O| |O 1B + * SPINDLE_DIR_PIN STEP O| |O VDD + * SPINDLE_LASER_PWM_PIN DIR O| |O GND + * ------- + * * - pin closest to MS1, MS2 & MS3 jumpers on the board + * + * Note: Socket names vary from vendor to vendor. + */ From 55a87da036c48559fabd20246d9b810a3c93b0fe Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 7 Apr 2017 13:52:45 -0500 Subject: [PATCH 100/189] SPINDLE/LASER implementation --- Marlin/Marlin_main.cpp | 141 +++++++++++++++++++++++++++++++++++++++++ 1 file changed, 141 insertions(+) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index e6ce386ef..cb7ec8696 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -73,6 +73,9 @@ * * M0 - Unconditional stop - Wait for user to press a button on the LCD (Only if ULTRA_LCD is enabled) * M1 - Same as M0 + * M3 - Turn laser/spindle on, set spindle/laser speed/power, set rotation to clockwise + * M4 - Turn laser/spindle on, set spindle/laser speed/power, set rotation to counter-clockwise + * M5 - Turn laser/spindle off * M17 - Enable/Power all stepper motors * M18 - Disable all stepper motors; same as M84 * M20 - List SD card. (Requires SDSUPPORT) @@ -5611,6 +5614,121 @@ inline void gcode_G92() { #endif // HAS_RESUME_CONTINUE +#if ENABLED(SPINDLE_LASER_ENABLE) + /** + * M3: Spindle Clockwise + * M4: Spindle Counter-clockwise + * + * S0 turns off spindle. + * + * If no speed PWM output is defined then M3/M4 just turns it on. + * + * At least 12.8KHz (50Hz * 256) is needed for spindle PWM. + * Hardware PWM is required. ISRs are too slow. + * + * NOTE: WGM for timers 3, 4, and 5 must be either Mode 1 or Mode 5. + * No other settings give a PWM signal that goes from 0 to 5 volts. + * + * The system automatically sets WGM to Mode 1, so no special + * initialization is needed. + * + * WGM bits for timer 2 are automatically set by the system to + * Mode 1. This produces an acceptable 0 to 5 volt signal. + * No special initialization is needed. + * + * NOTE: A minimum PWM frequency of 50 Hz is needed. All prescaler + * factors for timers 2, 3, 4, and 5 are acceptable. + * + * SPINDLE_LASER_ENABLE_PIN needs an external pullup or it may power on + * the spindle/laser during power-up or when connecting to the host + * (usually goes through a reset which sets all I/O pins to tri-state) + * + * PWM duty cycle goes from 0 (off) to 255 (always on). + */ + + // Wait for spindle to come up to speed + inline void delay_for_power_up() { + refresh_cmd_timeout(); + while (PENDING(millis(), SPINDLE_LASER_POWERUP_DELAY + previous_cmd_ms)) idle(); + } + + // Wait for spindle to stop turning + inline void delay_for_power_down() { + refresh_cmd_timeout(); + while (PENDING(millis(), SPINDLE_LASER_POWERDOWN_DELAY + previous_cmd_ms + 1)) idle(); + } + + /** + * ocr_val_mode() is used for debugging and to get the points needed to compute the RPM vs ocr_val line + * + * it accepts inputs of 0-255 + */ + + inline void ocr_val_mode() { + uint8_t spindle_laser_power = code_value_byte(); + WRITE(SPINDLE_LASER_ENABLE_PIN, SPINDLE_LASER_ENABLE_INVERT); // turn spindle on (active low) + if (SPINDLE_LASER_PWM_INVERT) spindle_laser_power = 255 - spindle_laser_power; + analogWrite(SPINDLE_LASER_PWM_PIN, spindle_laser_power); + } + + inline void gcode_M3_M4(bool is_M3) { + + stepper.synchronize(); // wait until previous movement commands (G0/G0/G2/G3) have completed before playing with the spindle + #if SPINDLE_DIR_CHANGE + const bool rotation_dir = (is_M3 && !SPINDLE_INVERT_DIR || !is_M3 && SPINDLE_INVERT_DIR) ? HIGH : LOW; + if (SPINDLE_STOP_ON_DIR_CHANGE \ + && READ(SPINDLE_LASER_ENABLE_PIN) == SPINDLE_LASER_ENABLE_INVERT \ + && READ(SPINDLE_DIR_PIN) != rotation_dir + ) { + WRITE(SPINDLE_LASER_ENABLE_PIN, !SPINDLE_LASER_ENABLE_INVERT); // turn spindle off + delay_for_power_down(); + } + digitalWrite(SPINDLE_DIR_PIN, rotation_dir); + #endif + + /** + * Our final value for ocr_val is an unsigned 8 bit value between 0 and 255 which usually means uint8_t. + * Went to uint16_t because some of the uint8_t calculations would sometimes give 1000 0000 rather than 1111 1111. + * Then needed to AND the uint16_t result with 0x00FF to make sure we only wrote the byte of interest. + */ + #if ENABLED(SPINDLE_LASER_PWM) + if (code_seen('O')) ocr_val_mode(); + else { + const float spindle_laser_power = code_seen('S') ? code_value_float() : 0; + if (spindle_laser_power == 0) { + WRITE(SPINDLE_LASER_ENABLE_PIN, !SPINDLE_LASER_ENABLE_INVERT); // turn spindle off (active low) + delay_for_power_down(); + } + else { + int16_t ocr_val = (spindle_laser_power - (SPEED_POWER_INTERCEPT)) * (1.0 / (SPEED_POWER_SLOPE)); // convert RPM to PWM duty cycle + NOMORE(ocr_val, 255); // limit to max the Atmel PWM will support + if (spindle_laser_power <= SPEED_POWER_MIN) + ocr_val = (SPEED_POWER_MIN - (SPEED_POWER_INTERCEPT)) * (1.0 / (SPEED_POWER_SLOPE)); // minimum setting + if (spindle_laser_power >= SPEED_POWER_MAX) + ocr_val = (SPEED_POWER_MAX - (SPEED_POWER_INTERCEPT)) * (1.0 / (SPEED_POWER_SLOPE)); // limit to max RPM + if (SPINDLE_LASER_PWM_INVERT) ocr_val = 255 - ocr_val; + WRITE(SPINDLE_LASER_ENABLE_PIN, SPINDLE_LASER_ENABLE_INVERT); // turn spindle on (active low) + analogWrite(SPINDLE_LASER_PWM_PIN, ocr_val & 0xFF); // only write low byte + delay_for_power_up(); + } + } + #else + WRITE(SPINDLE_LASER_ENABLE_PIN, SPINDLE_LASER_ENABLE_INVERT); // turn spindle on (active low) if spindle speed option not enabled + delay_for_power_up(); + #endif + } + + /** + * M5 turn off spindle + */ + inline void gcode_M5() { + stepper.synchronize(); + WRITE(SPINDLE_LASER_ENABLE_PIN, !SPINDLE_LASER_ENABLE_INVERT); + delay_for_power_down(); + } + +#endif // SPINDLE_LASER_ENABLE + /** * M17: Enable power on all stepper motors */ @@ -5626,6 +5744,7 @@ inline void gcode_M17() { #endif #if ENABLED(PARK_HEAD_ON_PAUSE) + float resume_position[XYZE]; bool move_away_flag = false; @@ -9946,6 +10065,17 @@ void process_next_command() { break; #endif // ULTIPANEL + #if ENABLED(SPINDLE_LASER_ENABLE) + case 3: + gcode_M3_M4(true); // M3: turn spindle/laser on, set laser/spindle power/speed, set rotation direction CW + break; // synchronizes with movement commands + case 4: + gcode_M3_M4(false); // M4: turn spindle/laser on, set laser/spindle power/speed, set rotation direction CCW + break; // synchronizes with movement commands + case 5: + gcode_M5(); // M5 - turn spindle/laser off + break; // synchronizes with movement commands + #endif case 17: // M17: Enable all stepper motors gcode_M17(); break; @@ -12262,6 +12392,17 @@ void setup() { update_case_light(); #endif + #if ENABLED(SPINDLE_LASER_ENABLE) + OUT_WRITE(SPINDLE_LASER_ENABLE_PIN, !SPINDLE_LASER_ENABLE_INVERT); // init spindle to off + #if SPINDLE_DIR_CHANGE + OUT_WRITE(SPINDLE_DIR_PIN, SPINDLE_INVERT_DIR ? 255 : 0); // init rotation to clockwise (M3) + #endif + #if ENABLED(SPINDLE_LASER_PWM) + SET_OUTPUT(SPINDLE_LASER_PWM_PIN); + analogWrite(SPINDLE_LASER_PWM_PIN, SPINDLE_LASER_PWM_INVERT ? 255 : 0); // set to lowest speed + #endif + #endif + #if HAS_BED_PROBE endstops.enable_z_probe(false); #endif From f0fe26c411de5bd49572a013cccacb51a1f3710e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 17 May 2017 05:07:35 -0500 Subject: [PATCH 101/189] Ensure Arduino.h and configs are included for serial.cpp --- Marlin/serial.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Marlin/serial.h b/Marlin/serial.h index 62e06c989..b57e7b1b6 100644 --- a/Marlin/serial.h +++ b/Marlin/serial.h @@ -23,6 +23,8 @@ #ifndef __SERIAL_H__ #define __SERIAL_H__ +#include "MarlinConfig.h" + #ifdef USBCON #include "HardwareSerial.h" #if ENABLED(BLUETOOTH) From 3370329751a21130c97f2b0c621ad8a75dd449b7 Mon Sep 17 00:00:00 2001 From: Brian Date: Thu, 11 May 2017 10:48:16 -0400 Subject: [PATCH 102/189] Fix broken EEPROM save/load --- Marlin/configuration_store.cpp | 14 ++++++++------ Marlin/configuration_store.h | 4 ++-- Marlin/utility.cpp | 4 ++-- 3 files changed, 12 insertions(+), 10 deletions(-) diff --git a/Marlin/configuration_store.cpp b/Marlin/configuration_store.cpp index 4ea56ff6f..a6a330616 100644 --- a/Marlin/configuration_store.cpp +++ b/Marlin/configuration_store.cpp @@ -625,15 +625,18 @@ void MarlinSettings::postprocess() { if (!eeprom_error) { const int eeprom_size = eeprom_index; + const uint16_t tcrc = working_crc; + // Write the EEPROM header eeprom_index = EEPROM_OFFSET; + EEPROM_WRITE(version); - EEPROM_WRITE(working_crc); + EEPROM_WRITE(tcrc); // Report storage size SERIAL_ECHO_START; SERIAL_ECHOPAIR("Settings Stored (", eeprom_size - (EEPROM_OFFSET)); - SERIAL_ECHOPAIR(" bytes; crc ", working_crc); + SERIAL_ECHOPAIR(" bytes; crc ", tcrc); SERIAL_ECHOLNPGM(")"); } @@ -982,11 +985,11 @@ void MarlinSettings::postprocess() { } else { SERIAL_ERROR_START; - SERIAL_ERRORPGM("EEPROM checksum mismatch - (stored CRC)"); + SERIAL_ERRORPGM("EEPROM CRC mismatch - (stored) "); SERIAL_ERROR(stored_crc); SERIAL_ERRORPGM(" != "); SERIAL_ERROR(working_crc); - SERIAL_ERRORLNPGM(" (calculated CRC)!"); + SERIAL_ERRORLNPGM(" (calculated)!"); reset(); } @@ -1027,7 +1030,6 @@ void MarlinSettings::postprocess() { return !eeprom_error; } - #if ENABLED(AUTO_BED_LEVELING_UBL) void ubl_invalid_slot(const int s) { @@ -1051,7 +1053,7 @@ void MarlinSettings::postprocess() { if (!WITHIN(slot, 0, a - 1)) { ubl_invalid_slot(a); SERIAL_PROTOCOLPAIR("E2END=", E2END); - SERIAL_PROTOCOLPAIR(" meshes_end=", (int)meshes_end); + SERIAL_PROTOCOLPAIR(" meshes_end=", meshes_end); SERIAL_PROTOCOLLNPAIR(" slot=", slot); SERIAL_EOL; return; diff --git a/Marlin/configuration_store.h b/Marlin/configuration_store.h index 1166ed29e..23a716a94 100644 --- a/Marlin/configuration_store.h +++ b/Marlin/configuration_store.h @@ -67,8 +67,8 @@ class MarlinSettings { #if ENABLED(AUTO_BED_LEVELING_UBL) // Eventually make these available if any leveling system // That can store is enabled static int meshes_begin; - const static int mat_end = E2END; // Mesh allocation table; this may not end up being necessary - const static int meshes_end = mat_end - 128; // 128 is a placeholder for the size of the MAT + const static int meshes_end = E2END - 128; // 128 is a placeholder for the size of the MAT; the MAT will always + // live at the very end of the eeprom #endif diff --git a/Marlin/utility.cpp b/Marlin/utility.cpp index 43544106e..15378fb62 100644 --- a/Marlin/utility.cpp +++ b/Marlin/utility.cpp @@ -37,8 +37,8 @@ void safe_delay(millis_t ms) { #if ENABLED(EEPROM_SETTINGS) void crc16(uint16_t *crc, const void * const data, uint16_t cnt) { - uint8_t *ptr = (uint8_t*)data; - while (cnt-- > 0) { + uint8_t *ptr = (uint8_t *)data; + while (cnt--) { *crc = (uint16_t)(*crc ^ (uint16_t)(((uint16_t)*ptr++) << 8)); for (uint8_t x = 0; x < 8; x++) *crc = (uint16_t)((*crc & 0x8000) ? ((uint16_t)(*crc << 1) ^ 0x1021) : (*crc << 1)); From 6c064bb7d6ef12475a5ff247aa714aca847949d3 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 15 May 2017 18:32:26 -0500 Subject: [PATCH 103/189] Some probe_pt error-handling --- Marlin/Marlin_main.cpp | 29 ++++++++++++++++------------- Marlin/ubl_G29.cpp | 28 +++++++++++++++++----------- 2 files changed, 33 insertions(+), 24 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index f68ec7b09..d1225fbe8 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -4743,12 +4743,12 @@ void home_all_axes() { gcode_G28(true); } // Retain the last probe position xProbe = LOGICAL_X_POSITION(points[i].x); yProbe = LOGICAL_Y_POSITION(points[i].y); - measured_z = points[i].z = faux ? 0.001 * random(-100, 101) : probe_pt(xProbe, yProbe, stow_probe_after_each, verbose_level); - } - - if (isnan(measured_z)) { - planner.abl_enabled = abl_should_enable; - return; + measured_z = faux ? 0.001 * random(-100, 101) : probe_pt(xProbe, yProbe, stow_probe_after_each, verbose_level); + if (isnan(measured_z)) { + planner.abl_enabled = abl_should_enable; + return; + } + points[i].z = measured_z; } if (!dryrun) { @@ -5021,9 +5021,11 @@ void home_all_axes() { gcode_G28(true); } const float measured_z = probe_pt(xpos, ypos, !code_seen('S') || code_value_bool(), 1); - SERIAL_PROTOCOLPAIR("Bed X: ", FIXFLOAT(xpos)); - SERIAL_PROTOCOLPAIR(" Y: ", FIXFLOAT(ypos)); - SERIAL_PROTOCOLLNPAIR(" Z: ", FIXFLOAT(measured_z)); + if (!isnan(measured_z)) { + SERIAL_PROTOCOLPAIR("Bed X: ", FIXFLOAT(xpos)); + SERIAL_PROTOCOLPAIR(" Y: ", FIXFLOAT(ypos)); + SERIAL_PROTOCOLLNPAIR(" Z: ", FIXFLOAT(measured_z)); + } clean_up_after_endstop_or_probe_move(); @@ -5170,13 +5172,13 @@ void home_all_axes() { gcode_G28(true); } if (!do_all_positions && !do_circle_x3) { // probe the center setup_for_endstop_or_probe_move(); - z_at_pt[0] += probe_pt(0.0, 0.0 , true, 1); + z_at_pt[0] += probe_pt(0.0, 0.0 , true, 1); // TODO: Needs error handling clean_up_after_endstop_or_probe_move(); } if (probe_center_plus_3) { // probe extra center points for (int8_t axis = probe_center_plus_6 ? 11 : 9; axis > 0; axis -= probe_center_plus_6 ? 2 : 4) { setup_for_endstop_or_probe_move(); - z_at_pt[0] += probe_pt( + z_at_pt[0] += probe_pt( // TODO: Needs error handling cos(RADIANS(180 + 30 * axis)) * (0.1 * delta_calibration_radius), sin(RADIANS(180 + 30 * axis)) * (0.1 * delta_calibration_radius), true, 1); clean_up_after_endstop_or_probe_move(); @@ -5192,7 +5194,7 @@ void home_all_axes() { gcode_G28(true); } do_circle_x2 ? (zig_zag ? 0.5 : 0.0) : 0); for (float circles = -offset_circles ; circles <= offset_circles; circles++) { setup_for_endstop_or_probe_move(); - z_at_pt[axis] += probe_pt( + z_at_pt[axis] += probe_pt( // TODO: Needs error handling cos(RADIANS(180 + 30 * axis)) * delta_calibration_radius * (1 + circles * 0.1 * (zig_zag ? 1 : -1)), sin(RADIANS(180 + 30 * axis)) * delta_calibration_radius * @@ -6372,7 +6374,8 @@ inline void gcode_M42() { setup_for_endstop_or_probe_move(); // Move to the first point, deploy, and probe - probe_pt(X_probe_location, Y_probe_location, stow_probe_after_each, verbose_level); + const float t = probe_pt(X_probe_location, Y_probe_location, stow_probe_after_each, verbose_level); + if (isnan(t)) return; randomSeed(millis()); diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 6e97d702f..68a261952 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -393,19 +393,24 @@ ubl.save_ubl_active_state_and_disable(); ubl.tilt_mesh_based_on_probed_grid(code_seen('T')); ubl.restore_ubl_active_state_and_leave(); - } else { // grid_size==0 which means a 3-Point leveling has been requested - float z1 = probe_pt(LOGICAL_X_POSITION(UBL_PROBE_PT_1_X), LOGICAL_Y_POSITION(UBL_PROBE_PT_1_Y), false, g29_verbose_level), - z2 = probe_pt(LOGICAL_X_POSITION(UBL_PROBE_PT_2_X), LOGICAL_Y_POSITION(UBL_PROBE_PT_2_Y), false, g29_verbose_level), - z3 = probe_pt(LOGICAL_X_POSITION(UBL_PROBE_PT_3_X), LOGICAL_Y_POSITION(UBL_PROBE_PT_3_Y), true, g29_verbose_level); + } + else { // grid_size == 0 : A 3-Point leveling has been requested + float z3, z2, z1 = probe_pt(LOGICAL_X_POSITION(UBL_PROBE_PT_1_X), LOGICAL_Y_POSITION(UBL_PROBE_PT_1_Y), false, g29_verbose_level); + if (!isnan(z1)) { + z2 = probe_pt(LOGICAL_X_POSITION(UBL_PROBE_PT_2_X), LOGICAL_Y_POSITION(UBL_PROBE_PT_2_Y), false, g29_verbose_level); + if (!isnan(z2)) + z3 = probe_pt(LOGICAL_X_POSITION(UBL_PROBE_PT_3_X), LOGICAL_Y_POSITION(UBL_PROBE_PT_3_Y), true, g29_verbose_level); + } - if ( isnan(z1) || isnan(z2) || isnan(z3)) { // probe_pt will return NAN if unreachable + if (isnan(z1) || isnan(z2) || isnan(z3)) { // probe_pt will return NAN if unreachable SERIAL_ERROR_START; SERIAL_ERRORLNPGM("Attempt to probe off the bed."); goto LEAVE; } - // We need to adjust z1, z2, z3 by the Mesh Height at these points. Just because they are non-zero doesn't mean - // the Mesh is tilted! (We need to compensate each probe point by what the Mesh says that location's height is) + // Adjust z1, z2, z3 by the Mesh Height at these points. Just because they're non-zero + // doesn't mean the Mesh is tilted! (Compensate each probe point by what the Mesh says + // its height is.) ubl.save_ubl_active_state_and_disable(); z1 -= ubl.get_z_correction(LOGICAL_X_POSITION(UBL_PROBE_PT_1_X), LOGICAL_Y_POSITION(UBL_PROBE_PT_1_Y)) /* + zprobe_zoffset */ ; @@ -706,7 +711,7 @@ const float mean = sum / n; // - // Now do the sumation of the squares of difference from mean + // Sum the squares of difference from mean // float sum_of_diff_squared = 0.0; for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) @@ -769,12 +774,13 @@ const float rawx = pgm_read_float(&ubl.mesh_index_to_xpos[location.x_index]), rawy = pgm_read_float(&ubl.mesh_index_to_ypos[location.y_index]); - const float measured_z = probe_pt(LOGICAL_X_POSITION(rawx), LOGICAL_Y_POSITION(rawy), stow_probe, g29_verbose_level); + const float measured_z = probe_pt(LOGICAL_X_POSITION(rawx), LOGICAL_Y_POSITION(rawy), stow_probe, g29_verbose_level); // TODO: Needs error handling ubl.z_values[location.x_index][location.y_index] = measured_z; } if (do_ubl_mesh_map) ubl.display_map(map_type); - } while ((location.x_index >= 0) && (--max_iterations)); + + } while (location.x_index >= 0 && --max_iterations); STOW_PROBE(); ubl.restore_ubl_active_state_and_leave(); @@ -1548,7 +1554,7 @@ const float x = float(x_min) + ix * dx; for (int8_t iy = 0; iy < grid_size; iy++) { const float y = float(y_min) + dy * (zig_zag ? grid_size - 1 - iy : iy); - float measured_z = probe_pt(LOGICAL_X_POSITION(x), LOGICAL_Y_POSITION(y), code_seen('E'), g29_verbose_level); + float measured_z = probe_pt(LOGICAL_X_POSITION(x), LOGICAL_Y_POSITION(y), code_seen('E'), g29_verbose_level); // TODO: Needs error handling #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) { SERIAL_CHAR('('); From 3843a5151ac5934690d7c937f194227e6e4ec0e7 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 17 May 2017 09:44:34 -0500 Subject: [PATCH 104/189] Patch LCD code for 5th extruder, EEPROM reset --- Marlin/language_en.h | 6 +++--- Marlin/ultralcd.cpp | 33 +++++++++++++++++++-------------- 2 files changed, 22 insertions(+), 17 deletions(-) diff --git a/Marlin/language_en.h b/Marlin/language_en.h index 7dd2edf0a..fefc41082 100644 --- a/Marlin/language_en.h +++ b/Marlin/language_en.h @@ -455,16 +455,16 @@ #define MSG_CONTRAST _UxGT("LCD contrast") #endif #ifndef MSG_STORE_EEPROM - #define MSG_STORE_EEPROM _UxGT("Store memory") + #define MSG_STORE_EEPROM _UxGT("Store settings") #endif #ifndef MSG_LOAD_EEPROM - #define MSG_LOAD_EEPROM _UxGT("Load memory") + #define MSG_LOAD_EEPROM _UxGT("Load settings") #endif #ifndef MSG_RESTORE_FAILSAFE #define MSG_RESTORE_FAILSAFE _UxGT("Restore failsafe") #endif #ifndef MSG_INIT_EEPROM - #define MSG_INIT_EEPROM _UxGT("Initalize Memory") + #define MSG_INIT_EEPROM _UxGT("Initialize EEPROM") #endif #ifndef MSG_REFRESH #define MSG_REFRESH _UxGT("Refresh") diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 6b3784bac..5d9ee2982 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -1289,7 +1289,7 @@ void kill_screen(const char* lcd_msg) { void lcd_preheat_m2_bedonly() { _lcd_preheat(0, 0, lcd_preheat_bed_temp[1], lcd_preheat_fan_speed[1]); } #endif - #if TEMP_SENSOR_0 != 0 && (TEMP_SENSOR_1 != 0 || TEMP_SENSOR_2 != 0 || TEMP_SENSOR_3 != 0 || TEMP_SENSOR_BED != 0) + #if TEMP_SENSOR_0 != 0 && (TEMP_SENSOR_1 != 0 || TEMP_SENSOR_2 != 0 || TEMP_SENSOR_3 != 0 || TEMP_SENSOR_4 != 0 || TEMP_SENSOR_BED != 0) void lcd_preheat_m1_menu() { START_MENU(); @@ -1395,7 +1395,7 @@ void kill_screen(const char* lcd_msg) { END_MENU(); } - #endif // TEMP_SENSOR_0 && (TEMP_SENSOR_1 || TEMP_SENSOR_2 || TEMP_SENSOR_3 || TEMP_SENSOR_BED) + #endif // TEMP_SENSOR_0 && (TEMP_SENSOR_1 || TEMP_SENSOR_2 || TEMP_SENSOR_3 || TEMP_SENSOR_4 || TEMP_SENSOR_BED) void lcd_cooldown() { #if FAN_COUNT > 0 @@ -2076,18 +2076,14 @@ void kill_screen(const char* lcd_msg) { MENU_ITEM(gcode, MSG_DISABLE_STEPPERS, PSTR("M84")); // - // Preheat PLA - // Preheat ABS + // Change filament // - #if TEMP_SENSOR_0 != 0 + #if ENABLED(FILAMENT_CHANGE_FEATURE) + if (!thermalManager.tooColdToExtrude(active_extruder)) + MENU_ITEM(function, MSG_FILAMENTCHANGE, lcd_enqueue_filament_change); + #endif - // - // Change filament - // - #if ENABLED(FILAMENT_CHANGE_FEATURE) - if (!thermalManager.tooColdToExtrude(active_extruder)) - MENU_ITEM(function, MSG_FILAMENTCHANGE, lcd_enqueue_filament_change); - #endif + #if TEMP_SENSOR_0 != 0 // // Cooldown @@ -2102,7 +2098,7 @@ void kill_screen(const char* lcd_msg) { // // Preheat for Material 1 and 2 // - #if TEMP_SENSOR_1 != 0 || TEMP_SENSOR_2 != 0 || TEMP_SENSOR_3 != 0 || TEMP_SENSOR_BED != 0 + #if TEMP_SENSOR_1 != 0 || TEMP_SENSOR_2 != 0 || TEMP_SENSOR_3 != 0 || TEMP_SENSOR_4 != 0 || TEMP_SENSOR_BED != 0 MENU_ITEM(submenu, MSG_PREHEAT_1, lcd_preheat_m1_menu); MENU_ITEM(submenu, MSG_PREHEAT_2, lcd_preheat_m2_menu); #else @@ -2498,7 +2494,7 @@ void kill_screen(const char* lcd_msg) { MENU_ITEM(function, MSG_STORE_EEPROM, lcd_store_settings); MENU_ITEM(function, MSG_LOAD_EEPROM, lcd_load_settings); MENU_ITEM(function, MSG_RESTORE_FAILSAFE, lcd_factory_settings); - MENU_ITEM(gcode, MSG_INIT_EEPROM, PSTR("M502\nM500\nM501")); + MENU_ITEM(gcode, MSG_INIT_EEPROM, PSTR("M502\nM500")); // TODO: Add "Are You Sure?" step #endif END_MENU(); } @@ -3146,6 +3142,15 @@ void kill_screen(const char* lcd_msg) { STATIC_ITEM(MSG_INFO_MAX_TEMP ": " STRINGIFY(HEATER_3_MAXTEMP), false); #endif + #if TEMP_SENSOR_4 != 0 + #undef THERMISTOR_ID + #define THERMISTOR_ID TEMP_SENSOR_4 + #include "thermistornames.h" + STATIC_ITEM("T4: " THERMISTOR_NAME, false, true); + STATIC_ITEM(MSG_INFO_MIN_TEMP ": " STRINGIFY(HEATER_4_MINTEMP), false); + STATIC_ITEM(MSG_INFO_MAX_TEMP ": " STRINGIFY(HEATER_4_MAXTEMP), false); + #endif + #if TEMP_SENSOR_BED != 0 #undef THERMISTOR_ID #define THERMISTOR_ID TEMP_SENSOR_BED From 43c24f0027554fdb9fb8b9742b43421e40f6b523 Mon Sep 17 00:00:00 2001 From: Brian Date: Wed, 17 May 2017 17:16:38 -0400 Subject: [PATCH 105/189] Fix recent regressions, &c. - fix broken `M421` due to less-than-careful optimization - add HOME_AFTER_DEACTIVATE define to advanced config so not everyone has to rehome after steppers are deactivated - misc. cleanups (remove unused label, unused variables) --- Marlin/Configuration_adv.h | 2 + Marlin/Marlin_main.cpp | 40 ++++++++++++------- Marlin/configuration_store.cpp | 10 ++--- .../Cartesio/Configuration_adv.h | 2 + .../Felix/Configuration_adv.h | 2 + .../FolgerTech-i3-2020/Configuration_adv.h | 2 + .../Hephestos/Configuration_adv.h | 2 + .../Hephestos_2/Configuration_adv.h | 2 + .../K8200/Configuration_adv.h | 2 + .../K8400/Configuration_adv.h | 2 + .../RigidBot/Configuration_adv.h | 2 + .../SCARA/Configuration_adv.h | 2 + .../TAZ4/Configuration_adv.h | 2 + .../TinyBoy2/Configuration_adv.h | 2 + .../WITBOX/Configuration_adv.h | 2 + .../FLSUN/auto_calibrate/Configuration_adv.h | 2 + .../FLSUN/kossel_mini/Configuration_adv.h | 2 + .../delta/generic/Configuration_adv.h | 2 + .../delta/kossel_mini/Configuration_adv.h | 2 + .../delta/kossel_pro/Configuration_adv.h | 2 + .../delta/kossel_xl/Configuration_adv.h | 2 + .../gCreate_gMax1.5+/Configuration_adv.h | 2 + .../makibox/Configuration_adv.h | 2 + .../tvrrug/Round2/Configuration_adv.h | 2 + .../wt150/Configuration_adv.h | 2 + Marlin/ubl_G29.cpp | 3 +- Marlin/ultralcd.cpp | 1 - 27 files changed, 78 insertions(+), 22 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 131af4706..173113830 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -365,6 +365,8 @@ #define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate #define DEFAULT_MINTRAVELFEEDRATE 0.0 +//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated + // @section lcd #if ENABLED(ULTIPANEL) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index f68ec7b09..352c01eb6 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -1856,9 +1856,15 @@ static void clean_up_after_endstop_or_probe_move() { #if HAS_PROBING_PROCEDURE || HOTENDS > 1 || ENABLED(Z_PROBE_ALLEN_KEY) || ENABLED(Z_PROBE_SLED) || ENABLED(NOZZLE_CLEAN_FEATURE) || ENABLED(NOZZLE_PARK_FEATURE) || ENABLED(DELTA_AUTO_CALIBRATION) bool axis_unhomed_error(const bool x/*=true*/, const bool y/*=true*/, const bool z/*=true*/) { +#if ENABLED(HOME_AFTER_DEACTIVATE) const bool xx = x && !axis_known_position[X_AXIS], yy = y && !axis_known_position[Y_AXIS], zz = z && !axis_known_position[Z_AXIS]; +#else + const bool xx = x && !axis_homed[X_AXIS], + yy = y && !axis_homed[Y_AXIS], + zz = z && !axis_homed[Z_AXIS]; +#endif if (xx || yy || zz) { SERIAL_ECHO_START; SERIAL_ECHOPGM(MSG_HOME " "); @@ -8550,12 +8556,12 @@ void quickstop_stepper() { */ inline void gcode_M421() { const bool hasX = code_seen('X'), hasI = code_seen('I'); - const int8_t ix = hasI ? code_value_byte() : hasX ? mbl.probe_index_x(RAW_X_POSITION(code_value_linear_units())) : -1; + const int8_t ix = hasI ? code_value_int() : hasX ? mbl.probe_index_x(RAW_X_POSITION(code_value_linear_units())) : -1; const bool hasY = code_seen('Y'), hasJ = code_seen('J'); - const int8_t iy = hasJ ? code_value_byte() : hasY ? mbl.probe_index_y(RAW_Y_POSITION(code_value_linear_units())) : -1; - const bool hasZ = code_seen('Z'), hasQ = code_seen('Q'); + const int8_t iy = hasJ ? code_value_int() : hasY ? mbl.probe_index_y(RAW_Y_POSITION(code_value_linear_units())) : -1; + const bool hasZ = code_seen('Z'), hasQ = !hasZ && code_seen('Q'); - if (int(hasI && hasJ) + int(hasX && hasY) != 1 || hasZ == hasQ) { + if (int(hasI && hasJ) + int(hasX && hasY) != 1 || !(hasZ || hasQ)) { SERIAL_ERROR_START; SERIAL_ERRORLNPGM(MSG_ERR_M421_PARAMETERS); } @@ -8578,12 +8584,12 @@ void quickstop_stepper() { */ inline void gcode_M421() { const bool hasI = code_seen('I'); - const int8_t ix = hasI ? code_value_byte() : -1; + const int8_t ix = hasI ? code_value_int() : -1; const bool hasJ = code_seen('J'); - const int8_t iy = hasJ ? code_value_byte() : -1; - const bool hasZ = code_seen('Z'), hasQ = code_seen('Q'); + const int8_t iy = hasJ ? code_value_int() : -1; + const bool hasZ = code_seen('Z'), hasQ = !hasZ && code_seen('Q'); - if (!hasI || !hasJ || hasZ == hasQ) { + if (!hasI || !hasJ || !(hasZ || hasQ)) { SERIAL_ERROR_START; SERIAL_ERRORLNPGM(MSG_ERR_M421_PARAMETERS); } @@ -8611,14 +8617,20 @@ void quickstop_stepper() { * M421 C Q */ inline void gcode_M421() { - const mesh_index_pair location = find_closest_mesh_point_of_type(REAL, current_position[X_AXIS], current_position[Y_AXIS], USE_NOZZLE_AS_REFERENCE, NULL, false); - const bool hasC = code_seen('C'), hasI = code_seen('I'); - const int8_t ix = hasI ? code_value_byte() : hasC ? location.x_index : -1; + const bool hasC = code_seen('C'); + const bool hasI = code_seen('I'); + int8_t ix = hasI ? code_value_int() : -1; const bool hasJ = code_seen('J'); - const int8_t iy = hasJ ? code_value_byte() : hasC ? location.y_index : -1; - const bool hasZ = code_seen('Z'), hasQ = code_seen('Q'); + int8_t iy = hasJ ? code_value_int() : -1; + const bool hasZ = code_seen('Z'), hasQ = !hasZ && code_seen('Q'); + + if (hasC) { + const mesh_index_pair location = find_closest_mesh_point_of_type(REAL, current_position[X_AXIS], current_position[Y_AXIS], USE_NOZZLE_AS_REFERENCE, NULL, false); + ix = location.x_index; + iy = location.y_index; + } - if (int(hasC) + int(hasI && hasJ) != 1 || hasZ == hasQ) { + if (int(hasC) + int(hasI && hasJ) != 1 || !(hasZ || hasQ)) { SERIAL_ERROR_START; SERIAL_ERRORLNPGM(MSG_ERR_M421_PARAMETERS); } diff --git a/Marlin/configuration_store.cpp b/Marlin/configuration_store.cpp index a6a330616..a6cb8889d 100644 --- a/Marlin/configuration_store.cpp +++ b/Marlin/configuration_store.cpp @@ -625,18 +625,18 @@ void MarlinSettings::postprocess() { if (!eeprom_error) { const int eeprom_size = eeprom_index; - const uint16_t tcrc = working_crc; + const uint16_t final_crc = working_crc; // Write the EEPROM header eeprom_index = EEPROM_OFFSET; EEPROM_WRITE(version); - EEPROM_WRITE(tcrc); + EEPROM_WRITE(final_crc); // Report storage size SERIAL_ECHO_START; SERIAL_ECHOPAIR("Settings Stored (", eeprom_size - (EEPROM_OFFSET)); - SERIAL_ECHOPAIR(" bytes; crc ", tcrc); + SERIAL_ECHOPAIR(" bytes; crc ", final_crc); SERIAL_ECHOLNPGM(")"); } @@ -1066,7 +1066,7 @@ void MarlinSettings::postprocess() { // Write crc to MAT along with other data, or just tack on to the beginning or end - SERIAL_PROTOCOLPAIR("Mesh saved in slot ", slot); + SERIAL_PROTOCOLLNPAIR("Mesh saved in slot ", slot); #else @@ -1093,7 +1093,7 @@ void MarlinSettings::postprocess() { // Compare crc with crc from MAT, or read from end - SERIAL_PROTOCOLPAIR("Mesh loaded from slot ", slot); + SERIAL_PROTOCOLLNPAIR("Mesh loaded from slot ", slot); #else diff --git a/Marlin/example_configurations/Cartesio/Configuration_adv.h b/Marlin/example_configurations/Cartesio/Configuration_adv.h index 372d3fff5..29f57a9d1 100644 --- a/Marlin/example_configurations/Cartesio/Configuration_adv.h +++ b/Marlin/example_configurations/Cartesio/Configuration_adv.h @@ -365,6 +365,8 @@ #define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate #define DEFAULT_MINTRAVELFEEDRATE 0.0 +//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated + // @section lcd #if ENABLED(ULTIPANEL) diff --git a/Marlin/example_configurations/Felix/Configuration_adv.h b/Marlin/example_configurations/Felix/Configuration_adv.h index 3dabf65d4..10bf0a853 100644 --- a/Marlin/example_configurations/Felix/Configuration_adv.h +++ b/Marlin/example_configurations/Felix/Configuration_adv.h @@ -365,6 +365,8 @@ #define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate #define DEFAULT_MINTRAVELFEEDRATE 0.0 +//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated + // @section lcd #if ENABLED(ULTIPANEL) diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h index c003216e0..dcbb34130 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h @@ -365,6 +365,8 @@ #define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate #define DEFAULT_MINTRAVELFEEDRATE 0.0 +//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated + // @section lcd #if ENABLED(ULTIPANEL) diff --git a/Marlin/example_configurations/Hephestos/Configuration_adv.h b/Marlin/example_configurations/Hephestos/Configuration_adv.h index 903b1ab79..dc3cce298 100644 --- a/Marlin/example_configurations/Hephestos/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos/Configuration_adv.h @@ -365,6 +365,8 @@ #define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate #define DEFAULT_MINTRAVELFEEDRATE 0.0 +//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated + // @section lcd #if ENABLED(ULTIPANEL) diff --git a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h index fd07d62e8..86cddce71 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h @@ -365,6 +365,8 @@ #define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate #define DEFAULT_MINTRAVELFEEDRATE 0.0 +//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated + // @section lcd #if ENABLED(ULTIPANEL) diff --git a/Marlin/example_configurations/K8200/Configuration_adv.h b/Marlin/example_configurations/K8200/Configuration_adv.h index 7ae8a9394..c591d39a2 100644 --- a/Marlin/example_configurations/K8200/Configuration_adv.h +++ b/Marlin/example_configurations/K8200/Configuration_adv.h @@ -378,6 +378,8 @@ #define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate #define DEFAULT_MINTRAVELFEEDRATE 0.0 +//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated + // @section lcd #if ENABLED(ULTIPANEL) diff --git a/Marlin/example_configurations/K8400/Configuration_adv.h b/Marlin/example_configurations/K8400/Configuration_adv.h index 03e130a40..a9115994c 100644 --- a/Marlin/example_configurations/K8400/Configuration_adv.h +++ b/Marlin/example_configurations/K8400/Configuration_adv.h @@ -365,6 +365,8 @@ #define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate #define DEFAULT_MINTRAVELFEEDRATE 0.0 +//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated + // @section lcd #if ENABLED(ULTIPANEL) diff --git a/Marlin/example_configurations/RigidBot/Configuration_adv.h b/Marlin/example_configurations/RigidBot/Configuration_adv.h index 4b82cbe35..188522253 100644 --- a/Marlin/example_configurations/RigidBot/Configuration_adv.h +++ b/Marlin/example_configurations/RigidBot/Configuration_adv.h @@ -365,6 +365,8 @@ #define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate #define DEFAULT_MINTRAVELFEEDRATE 0.0 +//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated + // @section lcd #if ENABLED(ULTIPANEL) diff --git a/Marlin/example_configurations/SCARA/Configuration_adv.h b/Marlin/example_configurations/SCARA/Configuration_adv.h index 2ace54433..8ace9a94c 100644 --- a/Marlin/example_configurations/SCARA/Configuration_adv.h +++ b/Marlin/example_configurations/SCARA/Configuration_adv.h @@ -365,6 +365,8 @@ #define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate #define DEFAULT_MINTRAVELFEEDRATE 0.0 +//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated + // @section lcd #if ENABLED(ULTIPANEL) diff --git a/Marlin/example_configurations/TAZ4/Configuration_adv.h b/Marlin/example_configurations/TAZ4/Configuration_adv.h index ab8ddc908..f9ed3dc76 100644 --- a/Marlin/example_configurations/TAZ4/Configuration_adv.h +++ b/Marlin/example_configurations/TAZ4/Configuration_adv.h @@ -365,6 +365,8 @@ #define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate #define DEFAULT_MINTRAVELFEEDRATE 0.0 +//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated + // @section lcd #if ENABLED(ULTIPANEL) diff --git a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h index 7e714b359..d0aa44293 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h @@ -365,6 +365,8 @@ #define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate #define DEFAULT_MINTRAVELFEEDRATE 0.0 +//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated + // @section lcd #if ENABLED(ULTIPANEL) diff --git a/Marlin/example_configurations/WITBOX/Configuration_adv.h b/Marlin/example_configurations/WITBOX/Configuration_adv.h index 903b1ab79..dc3cce298 100644 --- a/Marlin/example_configurations/WITBOX/Configuration_adv.h +++ b/Marlin/example_configurations/WITBOX/Configuration_adv.h @@ -365,6 +365,8 @@ #define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate #define DEFAULT_MINTRAVELFEEDRATE 0.0 +//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated + // @section lcd #if ENABLED(ULTIPANEL) diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h index 3f1f4db53..8ac6fde4b 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h @@ -365,6 +365,8 @@ #define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate #define DEFAULT_MINTRAVELFEEDRATE 0.0 +//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated + // @section lcd #if ENABLED(ULTIPANEL) diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h index 4234c831a..9fa70a736 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h @@ -365,6 +365,8 @@ #define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate #define DEFAULT_MINTRAVELFEEDRATE 0.0 +//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated + // @section lcd #if ENABLED(ULTIPANEL) diff --git a/Marlin/example_configurations/delta/generic/Configuration_adv.h b/Marlin/example_configurations/delta/generic/Configuration_adv.h index 295b82b0d..d7fe9281c 100644 --- a/Marlin/example_configurations/delta/generic/Configuration_adv.h +++ b/Marlin/example_configurations/delta/generic/Configuration_adv.h @@ -365,6 +365,8 @@ #define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate #define DEFAULT_MINTRAVELFEEDRATE 0.0 +//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated + // @section lcd #if ENABLED(ULTIPANEL) diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h index 295b82b0d..d7fe9281c 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h @@ -365,6 +365,8 @@ #define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate #define DEFAULT_MINTRAVELFEEDRATE 0.0 +//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated + // @section lcd #if ENABLED(ULTIPANEL) diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h index dc0a77bdb..b2431d7e0 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h @@ -370,6 +370,8 @@ #define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate #define DEFAULT_MINTRAVELFEEDRATE 0.0 +//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated + // @section lcd #if ENABLED(ULTIPANEL) diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h index 5f73c52f2..c4341165f 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h @@ -365,6 +365,8 @@ #define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate #define DEFAULT_MINTRAVELFEEDRATE 0.0 +//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated + // @section lcd #if ENABLED(ULTIPANEL) diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h index 1bf2b69c5..2a7371020 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h @@ -365,6 +365,8 @@ #define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate #define DEFAULT_MINTRAVELFEEDRATE 0.0 +//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated + // @section lcd #if ENABLED(ULTIPANEL) diff --git a/Marlin/example_configurations/makibox/Configuration_adv.h b/Marlin/example_configurations/makibox/Configuration_adv.h index 9050fc676..50843a39a 100644 --- a/Marlin/example_configurations/makibox/Configuration_adv.h +++ b/Marlin/example_configurations/makibox/Configuration_adv.h @@ -365,6 +365,8 @@ #define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate #define DEFAULT_MINTRAVELFEEDRATE 0.0 +//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated + // @section lcd #if ENABLED(ULTIPANEL) diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h index f3022c7b2..19c17e29f 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h @@ -365,6 +365,8 @@ #define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate #define DEFAULT_MINTRAVELFEEDRATE 0.0 +//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated + // @section lcd #if ENABLED(ULTIPANEL) diff --git a/Marlin/example_configurations/wt150/Configuration_adv.h b/Marlin/example_configurations/wt150/Configuration_adv.h index d5d595201..9baf16688 100644 --- a/Marlin/example_configurations/wt150/Configuration_adv.h +++ b/Marlin/example_configurations/wt150/Configuration_adv.h @@ -365,6 +365,8 @@ #define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate #define DEFAULT_MINTRAVELFEEDRATE 0.0 +//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated + // @section lcd #if ENABLED(ULTIPANEL) diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 6e97d702f..09a86c3a3 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -307,7 +307,7 @@ static int g29_verbose_level, phase_value, repetition_cnt, storage_slot = 0, map_type, grid_size; static bool repeat_flag, c_flag, x_flag, y_flag; - static float x_pos, y_pos, measured_z, card_thickness = 0.0, ubl_constant = 0.0; + static float x_pos, y_pos, card_thickness = 0.0, ubl_constant = 0.0; extern void lcd_setstatus(const char* message, const bool persist); extern void lcd_setstatuspgm(const char* message, const uint8_t level); @@ -1026,7 +1026,6 @@ if (do_ubl_mesh_map) ubl.display_map(map_type); - LEAVE: ubl.restore_ubl_active_state_and_leave(); KEEPALIVE_STATE(IN_HANDLER); do_blocking_move_to_z(Z_CLEARANCE_DEPLOY_PROBE); diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 6b3784bac..cfeb0b72b 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -1858,7 +1858,6 @@ void kill_screen(const char* lcd_msg) { * UBL Build Mesh submenu */ void _lcd_ubl_build_mesh() { - int GRID_NUM_POINTS = GRID_MAX_POINTS; START_MENU(); MENU_BACK(MSG_UBL_TOOLS); #if (WATCH_THE_BED) From 13599a73c7d2c356b20695e2e1556952b2f5d3cf Mon Sep 17 00:00:00 2001 From: Brian Date: Wed, 17 May 2017 19:03:00 -0400 Subject: [PATCH 106/189] Add `G7` gcode command to move between UBL mesh points - can be augmented in the future to enable for other leveling systems Quite simple, but did not want to modify `G1` as the additional checking would slow it down. Tested & working. --- Marlin/Marlin_main.cpp | 38 ++++++++++++++++++++++++++++++++++++++ 1 file changed, 38 insertions(+) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 352c01eb6..1d2985366 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -3395,6 +3395,34 @@ inline void gcode_G4() { #endif // BEZIER_CURVE_SUPPORT +#if ENABLED(AUTO_BED_LEVELING_UBL) //todo: enable for other leveling systems? +/** + * G7: Move X & Y axes to mesh coordinates + */ +inline void gcode_G7( + #if IS_SCARA + bool fast_move=false + #endif +) { + if (IsRunning()) { + destination[X_AXIS] = code_seen('I') ? pgm_read_float(&ubl.mesh_index_to_xpos[code_has_value() ? code_value_int() : 0]) : current_position[X_AXIS]; + destination[Y_AXIS] = code_seen('J') ? pgm_read_float(&ubl.mesh_index_to_ypos[code_has_value() ? code_value_int() : 0]) : current_position[Y_AXIS]; + destination[Z_AXIS] = current_position[Z_AXIS]; //todo: perhaps add Z-move support? + destination[E_AXIS] = current_position[E_AXIS]; + + if (code_seen('F') && code_value_linear_units() > 0.0) + feedrate_mm_s = MMM_TO_MMS(code_value_linear_units()); + + #if IS_SCARA + fast_move ? prepare_uninterpolated_move_to_destination() : prepare_move_to_destination(); + #else + prepare_move_to_destination(); + #endif + } +} +#endif + + #if ENABLED(FWRETRACT) /** @@ -9982,6 +10010,16 @@ void process_next_command() { break; #endif // BEZIER_CURVE_SUPPORT + #if ENABLED(AUTO_BED_LEVELING_UBL) + case 7: + #if IS_SCARA + gcode_G7(codenum == 0); + #else + gcode_G7(); + #endif + break; + #endif + #if ENABLED(FWRETRACT) case 10: // G10: retract case 11: // G11: retract_recover From e09b4ce4a5a552eb93c509ff38d3e6d475296b34 Mon Sep 17 00:00:00 2001 From: Brian Date: Wed, 17 May 2017 19:46:16 -0400 Subject: [PATCH 107/189] Add checking --- Marlin/Marlin_main.cpp | 15 +++++++++++++-- 1 file changed, 13 insertions(+), 2 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 1d2985366..34b156616 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -51,6 +51,7 @@ * G3 - CCW ARC * G4 - Dwell S or P * G5 - Cubic B-spline with XYZE destination and IJPQ offsets + * G7 - Coordinated move between UBL mesh points (I & J) * G10 - Retract filament according to settings of M207 * G11 - Retract recover filament according to settings of M208 * G12 - Clean tool @@ -3405,8 +3406,18 @@ inline void gcode_G7( #endif ) { if (IsRunning()) { - destination[X_AXIS] = code_seen('I') ? pgm_read_float(&ubl.mesh_index_to_xpos[code_has_value() ? code_value_int() : 0]) : current_position[X_AXIS]; - destination[Y_AXIS] = code_seen('J') ? pgm_read_float(&ubl.mesh_index_to_ypos[code_has_value() ? code_value_int() : 0]) : current_position[Y_AXIS]; + const bool hasI = code_seen('I'); + const int8_t ix = code_has_value() ? code_value_int() : 0; + const bool hasJ = code_seen('J'); + const int8_t iy = code_has_value() ? code_value_int() : 0; + + if ((hasI && !WITHIN(ix, 0, GRID_MAX_POINTS_X - 1)) || (hasJ && !WITHIN(iy, 0, GRID_MAX_POINTS_Y - 1))) { + SERIAL_ECHOLNPGM(MSG_ERR_MESH_XY); + return; + } + + destination[X_AXIS] = hasI ? pgm_read_float(&ubl.mesh_index_to_xpos[ix]) : current_position[X_AXIS]; + destination[Y_AXIS] = hasJ ? pgm_read_float(&ubl.mesh_index_to_ypos[iy]) : current_position[Y_AXIS]; destination[Z_AXIS] = current_position[Z_AXIS]; //todo: perhaps add Z-move support? destination[E_AXIS] = current_position[E_AXIS]; From 01f452c37c84d952f0d0ddbf0441a8666389e1ef Mon Sep 17 00:00:00 2001 From: Brian Date: Thu, 18 May 2017 13:00:13 -0400 Subject: [PATCH 108/189] Tweak Azteeg X3 PRO _pins.h so Viki2 will work for those without a case light. - add comment explaining that the Panucatt Viki2 wiring diagram uses pin 44 --- Marlin/pins_AZTEEG_X3_PRO.h | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/Marlin/pins_AZTEEG_X3_PRO.h b/Marlin/pins_AZTEEG_X3_PRO.h index 7701f8b68..65a060b34 100644 --- a/Marlin/pins_AZTEEG_X3_PRO.h +++ b/Marlin/pins_AZTEEG_X3_PRO.h @@ -144,9 +144,11 @@ // // Misc. Functions // -#undef DOGLCD_A0 // steal pin 44 for the case light -#define DOGLCD_A0 57 #if ENABLED(OK_TO_CHANGE_CASE_LIGHT) + #undef DOGLCD_A0 // steal pin 44 for the case light; if you have a Viki2 and have connected it + #define DOGLCD_A0 57 // following the Panucatt wiring diagram, you may need to tweak these pin assignments + // as the wiring diagram uses pin 44 for DOGLCD_A0 + #undef CASE_LIGHT_PIN #define CASE_LIGHT_PIN 44 // must have a hardware PWM #endif From 75badae2f8501098cec1167d3e454e3523c271c3 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 19 May 2017 06:50:01 -0500 Subject: [PATCH 109/189] Disable PROBE_MANUALLY for UBL Plus some other UBL tweaks. --- Marlin/Conditionals_LCD.h | 7 +++++++ Marlin/Marlin.h | 3 +++ Marlin/SanityCheck.h | 16 ++++++++++------ Marlin/ubl_G29.cpp | 13 ++++++++----- 4 files changed, 28 insertions(+), 11 deletions(-) diff --git a/Marlin/Conditionals_LCD.h b/Marlin/Conditionals_LCD.h index 3c775a115..5ea664bb8 100644 --- a/Marlin/Conditionals_LCD.h +++ b/Marlin/Conditionals_LCD.h @@ -373,6 +373,13 @@ */ #define HAS_Z_SERVO_ENDSTOP (defined(Z_ENDSTOP_SERVO_NR) && Z_ENDSTOP_SERVO_NR >= 0) + /** + * UBL has its own manual probing, so this just causes trouble. + */ + #if ENABLED(AUTO_BED_LEVELING_UBL) + #undef PROBE_MANUALLY + #endif + /** * Set a flag for any enabled probe */ diff --git a/Marlin/Marlin.h b/Marlin/Marlin.h index 9d505d87f..d09616937 100644 --- a/Marlin/Marlin.h +++ b/Marlin/Marlin.h @@ -351,6 +351,9 @@ int16_t code_value_temp_diff(); void refresh_zprobe_zoffset(const bool no_babystep=false); #define DEPLOY_PROBE() set_probe_deployed(true) #define STOW_PROBE() set_probe_deployed(false) +#else + #define DEPLOY_PROBE() + #define STOW_PROBE() #endif #if ENABLED(HOST_KEEPALIVE_FEATURE) diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index 9ddda7cbc..a63bbfdad 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -463,16 +463,16 @@ static_assert(1 >= 0 #if ENABLED(BLTOUCH) + 1 #endif - #if ENABLED(Z_PROBE_ALLEN_KEY) + #if ENABLED(SOLENOID_PROBE) + 1 #endif - #if ENABLED(Z_PROBE_SLED) + #if ENABLED(Z_PROBE_ALLEN_KEY) + 1 #endif - #if ENABLED(SOLENOID_PROBE) + #if ENABLED(Z_PROBE_SLED) + 1 #endif - , "Please enable only one probe: PROBE_MANUALLY, FIX_MOUNTED_PROBE, Z Servo, BLTOUCH, Z_PROBE_ALLEN_KEY, or Z_PROBE_SLED." + , "Please enable only one probe option: PROBE_MANUALLY, FIX_MOUNTED_PROBE, BLTOUCH, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, or Z Servo." ); @@ -547,9 +547,13 @@ static_assert(1 >= 0 * Require some kind of probe for bed leveling and probe testing */ #if HAS_ABL - #error "Auto Bed Leveling requires a probe! Define a Z Servo, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, or FIX_MOUNTED_PROBE." + #if ENABLED(AUTO_BED_LEVELING_UBL) + #error "Unified Bed Leveling requires a probe: FIX_MOUNTED_PROBE, BLTOUCH, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, or Z Servo." + #else + #error "Auto Bed Leveling requires one of these: PROBE_MANUALLY, FIX_MOUNTED_PROBE, BLTOUCH, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, or a Z Servo." + #endif #elif ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST) - #error "Z_MIN_PROBE_REPEATABILITY_TEST requires a probe! Define a Z Servo, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, or FIX_MOUNTED_PROBE." + #error "Z_MIN_PROBE_REPEATABILITY_TEST requires a probe: FIX_MOUNTED_PROBE, BLTOUCH, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, or Z Servo." #endif #endif diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 5f20c59b2..42a95ef56 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -640,10 +640,10 @@ ubl.state.z_offset = code_value_float(); // do the simple case. Just lock in the specified value else { ubl.save_ubl_active_state_and_disable(); - //measured_z = probe_pt(x_pos + X_PROBE_OFFSET_FROM_EXTRUDER, y_pos + Y_PROBE_OFFSET_FROM_EXTRUDER, ProbeDeployAndStow, g29_verbose_level); + //float measured_z = probe_pt(x_pos + X_PROBE_OFFSET_FROM_EXTRUDER, y_pos + Y_PROBE_OFFSET_FROM_EXTRUDER, ProbeDeployAndStow, g29_verbose_level); ubl.has_control_of_lcd_panel = true; // Grab the LCD Hardware - measured_z = 1.5; + float measured_z = 1.5; do_blocking_move_to_z(measured_z); // Get close to the bed, but leave some space so we don't damage anything // The user is not going to be locking in a new Z-Offset very often so // it won't be that painful to spin the Encoder Wheel for 1.5mm @@ -1185,9 +1185,12 @@ SERIAL_PROTOCOL_F(planner.z_fade_height, 4); SERIAL_EOL; #endif - SERIAL_PROTOCOLPGM("zprobe_zoffset: "); - SERIAL_PROTOCOL_F(zprobe_zoffset, 7); - SERIAL_EOL; + + #if HAS_BED_PROBE + SERIAL_PROTOCOLPGM("zprobe_zoffset: "); + SERIAL_PROTOCOL_F(zprobe_zoffset, 7); + SERIAL_EOL; + #endif SERIAL_ECHOLNPAIR("UBL_MESH_MIN_X " STRINGIFY(UBL_MESH_MIN_X) "=", UBL_MESH_MIN_X); SERIAL_ECHOLNPAIR("UBL_MESH_MIN_Y " STRINGIFY(UBL_MESH_MIN_Y) "=", UBL_MESH_MIN_Y); From 3c061a9f9a1d13a90281cd6d506c35a9936e0ee5 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 15 May 2017 18:46:07 -0500 Subject: [PATCH 110/189] UBL tabs, whitespace, spelling, etc. --- Marlin/ubl_G29.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 42a95ef56..b906a4760 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -538,7 +538,9 @@ // // Fine Tune (i.e., Edit) the Mesh // + fine_tune_mesh(x_pos, y_pos, code_seen('T')); + break; case 5: ubl.find_mean_mesh_height(); break; From b3a38fd300f51e52bf602f7331bfe4f3eb796538 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 20 May 2017 19:13:04 -0500 Subject: [PATCH 111/189] Clean up bugfix readme --- README.md | 95 +++++++------------------------------------------------ 1 file changed, 11 insertions(+), 84 deletions(-) diff --git a/README.md b/README.md index c253011d4..dbbcf9721 100644 --- a/README.md +++ b/README.md @@ -6,7 +6,7 @@ Additional documentation can be found at the [Marlin Home Page](http://marlinfw.org/). -Please test this firmware and inform us if it misbehaves in any way, volunteers are standing by! +Please test this firmware and let us know if it misbehaves in any way. Volunteers are standing by! ## Bugfix Branch @@ -14,91 +14,18 @@ __Not for production use. Use with caution!__ This branch is used to accumulate patches to the latest 1.1.x release version. Periodically this branch will form the basis for the next minor 1.1.x release. -Download earlier versions of Marlin on the [Releases page](https://github.com/MarlinFirmware/Marlin/releases). (The latest tagged release of Marlin is version 1.1.0.) +Download earlier versions of Marlin on the [Releases page](https://github.com/MarlinFirmware/Marlin/releases). (The latest tagged release of Marlin is version 1.1.1.) ## Recent Changes -- 1.1.0 - 4 May 2017 - - See the [1.1.0 Release Notes](https://github.com/MarlinFirmware/Marlin/releases/tag/1.1.0) for a full list of changes. - -- RC8 - 6 Dec 2016 - - Major performance improvement for Graphical LCDs - - Simplified probe configuration - - Enable Auto Bed Leveling by type - - Reduce serial communication errors - - Make Bilinear (Mesh) Grid Leveling available for non-delta - - Support for Trinamic TMC2130 SilentStepStick SPI-based drivers - - Add `M211` to Enable/Disable Software Endstops - - Add `M355` to turn the case light on/off and set brightness - - Improved I2C class with full master/slave support - - Add `G38.2` `G38.3` command option for CNC style probing - - Add `MINIMUM_STEPPER_PULSE` option to adjust step pulse duration - - Add `R` parameter support for `G2`/`G3` - - Add `M43` optional command (`PINS_DEBUGGING`) - - Remove SCARA axis scaling - - Improved sanity checking of configuration - - Improved support for PlatformIO and command-line build - - Usable `DELTA_CALIBRATION_MENU` - - Support for Printrbot Rev.F - - New and updated languages - -- RC7 - 26 Jul 2016 - - Add Print Job Timer and Print Counter (`PRINTCOUNTER`) - - New `M600` Filament Change (`FILAMENT_CHANGE_FEATURE`) - - New `G12` Nozzle Clean (`NOZZLE_CLEAN_FEATURE`) - - New `G27` Nozzle Park (`NOZZLE_PARK_FEATURE`) - - Add support for `COREYZ` - - Add a new Advance Extrusion algorithm (`LIN_ADVANCE`) - - Add support for inches, Fahrenheit, Kelvin units (`INCH_MODE_SUPPORT`, `TEMPERATURE_UNITS_SUPPORT`) - - Better handling of `G92` shifting of the coordinate space - - Add Greek and Croatian languages - - Improve the Manual (Mesh) Bed Leveling user interface - - Add support for more boards, controllers, and probes: - - Vellemann K8400 (`BOARD_K8400`) - - RigidBot V2 (`BOARD_RIGIDBOARD_V2`) - - Cartesio UI (`BOARD_CNCONTROLS_12`) - - BLTouch probe sensor (`BLTOUCH`) - - Viki 2 with RAMPS and MKS boards - - Improve support for `DELTA` and other kinematics - - Improve thermal management, add `WATCH_BED_TEMP_PERIOD` - - Better handling of toolchange, multiple tools - - Add support for two X steppers `X_DUAL_STEPPER_DRIVERS` - - Add support for `SINGLENOZZLE`, `MIXING_EXTRUDER`, `SWITCHING_NOZZLE`, and `SWITCHING_EXTRUDER` - - Simplified probe configuration, allow usage without bed leveling - - And much more… See the [1.1.0-RC7 Change Log](https://github.com/MarlinFirmware/Marlin/releases/tag/1.1.0-RC7) for the complete list of changes. - -- RC6 - 24 Apr 2016 - - Marlin now requires Arduino version 1.6.0 or later - - Completed support for CoreXY / CoreXZ - - See the [1.1.0-RC6 Change Log](https://github.com/MarlinFirmware/Marlin/releases/tag/1.1.0-RC6) for all the changes. - -- RC5 - 01 Apr 2016 - - Warn if compiling with older versions (<1.50) of Arduino - - Fix various LCD menu issues - - Add formal support for MKSv1.3 and Sainsmart (RAMPS variants) - - Fix bugs in M104, M109, and M190 - - Fix broken M404 command - - Fix issues with M23 and "Start SD Print" - - More output for M111 - - Rename FILAMENT_SENSOR to FILAMENT_WIDTH_SENSOR - - Fix SD card bugs - - and a lot more - - See the [1.1.0-RC5 Change Log](https://github.com/MarlinFirmware/Marlin/releases/tag/1.1.0-RC5) for more! - -- RC4 - 24 Mar 2016 - - Many lingering bugs and nagging issues addressed - - Improvements to LCD menus, CoreXY/CoreXZ, Delta, Bed Leveling, and more… - -- RC3 - 01 Dec 2015 - - A number of language sensitive strings have been revised - - Formatting of the LCD display has been improved to handle negative coordinates better - - Various compiler-related issues have been corrected - -- RC2 - 29 Sep 2015 - - File styling reverted - - LCD update frequency reduced - -- RC1 - 19 Sep 2015 - - Published for testing +- Further integration of Unified Bed Leveling +- Initial UBL LCD Menu +- New optimized G-code parser singleton +- Initial M3/M4/M5 Spindle and Laser support +- Added M421 Q to offset a mesh point +- Refinements to G26 and G33 +- Added M80 S to query the power state +- "Cancel Print" now shuts off heaters +- Added `EXTRAPOLATE_BEYOND_GRID` option for mesh-based leveling ## Submitting Patches From 6ce2b1ff4aac03ecc577ff05107c14c4fa002e6a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 20 May 2017 19:23:39 -0500 Subject: [PATCH 112/189] G33 evolutionary changes --- Marlin/Marlin_main.cpp | 224 ++++++++++-------- .../FLSUN/auto_calibrate/Configuration.h | 8 +- .../delta/FLSUN/kossel_mini/Configuration.h | 8 +- .../delta/generic/Configuration.h | 8 +- .../delta/kossel_mini/Configuration.h | 8 +- .../delta/kossel_pro/Configuration.h | 8 +- .../delta/kossel_xl/Configuration.h | 8 +- Marlin/planner.h | 6 +- Marlin/ultralcd.cpp | 8 + README.md | 2 +- 10 files changed, 168 insertions(+), 120 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 90a7b6aa2..30ffb1162 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -3019,12 +3019,12 @@ static void homeaxis(const AxisEnum axis) { // so here it re-homes each tower in turn. // Delta homing treats the axes as normal linear axes. - // retrace by the amount specified in endstop_adj - if (endstop_adj[axis] * Z_HOME_DIR < 0) { + // retrace by the amount specified in endstop_adj + additional 0.1mm in order to have minimum steps + if (endstop_adj[axis] * Z_HOME_DIR <= 0) { #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("endstop_adj:"); #endif - do_homing_move(axis, endstop_adj[axis]); + do_homing_move(axis, endstop_adj[axis] - 0.1); } #else @@ -5098,20 +5098,18 @@ void home_all_axes() { gcode_G28(true); } * * Parameters: * - * P Number of probe points: + * Pn Number of probe points: * * P1 Probe center and set height only. * P2 Probe center and towers. Set height, endstops, and delta radius. * P3 Probe all positions: center, towers and opposite towers. Set all. * P4-P7 Probe all positions at different locations and average them. * - * A Abort delta height calibration after 1 probe (only P1) - * - * O Use opposite tower points instead of tower points (only P2) - * - * T Don't calibrate tower angle corrections (P3-P7) - * - * V Verbose level: + * T Don't calibrate tower angle corrections + * + * Cn.nn Calibration precision; when omitted calibrates to maximum precision + * + * Vn Verbose level: * * V0 Dry-run mode. Report settings and probe results. No calibration. * V1 Report settings @@ -5131,30 +5129,61 @@ void home_all_axes() { gcode_G28(true); } return; } - const bool do_height_only = probe_points == 1, - do_center_and_towers = probe_points == 2, - do_all_positions = probe_points == 3, - do_circle_x2 = probe_points == 5, - do_circle_x3 = probe_points == 6, - do_circle_x4 = probe_points == 7, - probe_center_plus_3 = probe_points >= 3, - point_averaging = probe_points >= 4, - probe_center_plus_6 = probe_points >= 5; + const float calibration_precision = code_seen('C') ? code_value_float() : 0.0; + if (calibration_precision < 0) { + SERIAL_PROTOCOLLNPGM("?(C)alibration precision is implausible (>0)."); + return; + } - const char negating_parameter = do_height_only ? 'A' : do_center_and_towers ? 'O' : 'T'; - int8_t probe_mode = code_seen(negating_parameter) && code_value_bool() ? -probe_points : probe_points; + const bool towers_set = !code_seen('T'), + + _1p_calibration = probe_points == 1, + _4p_calibration = probe_points == 2, + _4p_towers_points = _4p_calibration && towers_set, + _4p_opposite_points = _4p_calibration && !towers_set, + _7p_calibration = probe_points >= 3, + _7p_half_circle = probe_points == 3, + _7p_double_circle = probe_points == 5, + _7p_triple_circle = probe_points == 6, + _7p_quadruple_circle = probe_points == 7, + _7p_multi_circle = _7p_double_circle || _7p_triple_circle || _7p_quadruple_circle, + _7p_intermed_points = _7p_calibration && !_7p_half_circle; + + if (!_1p_calibration) { // test if the outer radius is reachable + for (uint8_t axis = 1; axis < 13; ++axis) { + float circles = (_7p_quadruple_circle ? 1.5 : + _7p_triple_circle ? 1.0 : + _7p_double_circle ? 0.5 : 0); + if (!position_is_reachable_by_probe_xy(cos(RADIANS(180 + 30 * axis)) * + delta_calibration_radius * (1 + circles * 0.1), + sin(RADIANS(180 + 30 * axis)) * + delta_calibration_radius * (1 + circles * 0.1))) { + SERIAL_PROTOCOLLNPGM("?(M665 B)ed radius is implausible."); + return; + } + } + } SERIAL_PROTOCOLLNPGM("G33 Auto Calibrate"); + stepper.synchronize(); #if HAS_LEVELING - set_bed_leveling_enabled(false); + reset_bed_level(); // After calibration bed-level data is no longer valid #endif + #if HOTENDS > 1 + const uint8_t old_tool_index = active_extruder; + tool_change(0, 0, true); + #endif + setup_for_endstop_or_probe_move(); - home_all_axes(); + endstops.enable(true); + home_delta(); + endstops.not_homing(); const static char save_message[] PROGMEM = "Save with M500 and/or copy to Configuration.h"; float test_precision, zero_std_dev = (verbose_level ? 999.0 : 0.0), // 0.0 in dry-run mode : forced end + zero_std_dev_old = zero_std_dev, e_old[XYZ] = { endstop_adj[A_AXIS], endstop_adj[B_AXIS], @@ -5173,7 +5202,7 @@ void home_all_axes() { gcode_G28(true); } LCD_MESSAGEPGM("Checking... AC"); // TODO: Make translatable string SERIAL_PROTOCOLPAIR(".Height:", DELTA_HEIGHT + home_offset[Z_AXIS]); - if (!do_height_only) { + if (!_1p_calibration) { SERIAL_PROTOCOLPGM(" Ex:"); if (endstop_adj[A_AXIS] >= 0) SERIAL_CHAR('+'); SERIAL_PROTOCOL_F(endstop_adj[A_AXIS], 2); @@ -5186,7 +5215,7 @@ void home_all_axes() { gcode_G28(true); } SERIAL_PROTOCOLPAIR(" Radius:", delta_radius); } SERIAL_EOL; - if (probe_mode > 2) { // negative disables tower angles + if (_7p_calibration && towers_set) { SERIAL_PROTOCOLPGM(".Tower angle : Tx:"); if (delta_tower_angle_trim[A_AXIS] >= 0) SERIAL_CHAR('+'); SERIAL_PROTOCOL_F(delta_tower_angle_trim[A_AXIS], 2); @@ -5202,80 +5231,76 @@ void home_all_axes() { gcode_G28(true); } #endif int8_t iterations = 0; + + home_offset[Z_AXIS] -= probe_pt(0.0, 0.0 , true, 1); // 1st probe to set height + do_probe_raise(Z_CLEARANCE_BETWEEN_PROBES); do { - float z_at_pt[13] = { 0 }, - S1 = 0.0, - S2 = 0.0; + float z_at_pt[13] = { 0.0 }, S1 = 0.0, S2 = 0.0; int16_t N = 0; - test_precision = zero_std_dev; + test_precision = zero_std_dev_old != 999.0 ? (zero_std_dev + zero_std_dev_old) / 2 : zero_std_dev; + iterations++; // Probe the points - if (!do_all_positions && !do_circle_x3) { // probe the center - setup_for_endstop_or_probe_move(); - z_at_pt[0] += probe_pt(0.0, 0.0 , true, 1); // TODO: Needs error handling - clean_up_after_endstop_or_probe_move(); + if (!_7p_half_circle && !_7p_triple_circle) { // probe the center + z_at_pt[0] += probe_pt(0.0, 0.0 , true, 1); } - if (probe_center_plus_3) { // probe extra center points - for (int8_t axis = probe_center_plus_6 ? 11 : 9; axis > 0; axis -= probe_center_plus_6 ? 2 : 4) { - setup_for_endstop_or_probe_move(); - z_at_pt[0] += probe_pt( // TODO: Needs error handling - cos(RADIANS(180 + 30 * axis)) * (0.1 * delta_calibration_radius), - sin(RADIANS(180 + 30 * axis)) * (0.1 * delta_calibration_radius), true, 1); - clean_up_after_endstop_or_probe_move(); + if (_7p_calibration) { // probe extra center points + for (int8_t axis = _7p_multi_circle ? 11 : 9; axis > 0; axis -= _7p_multi_circle ? 2 : 4) { + const float a = RADIANS(180 + 30 * axis), r = delta_calibration_radius * 0.1; + z_at_pt[0] += probe_pt(cos(a) * r, sin(a) * r, true, 1); // TODO: Needs error handling } - z_at_pt[0] /= float(do_circle_x2 ? 7 : probe_points); + z_at_pt[0] /= float(_7p_double_circle ? 7 : probe_points); } - if (!do_height_only) { // probe the radius + if (!_1p_calibration) { // probe the radius bool zig_zag = true; - for (uint8_t axis = (probe_mode == -2 ? 3 : 1); axis < 13; - axis += (do_center_and_towers ? 4 : do_all_positions ? 2 : 1)) { - float offset_circles = (do_circle_x4 ? (zig_zag ? 1.5 : 1.0) : - do_circle_x3 ? (zig_zag ? 1.0 : 0.5) : - do_circle_x2 ? (zig_zag ? 0.5 : 0.0) : 0); + const uint8_t start = _4p_opposite_points ? 3 : 1, + step = _4p_calibration ? 4 : _7p_half_circle ? 2 : 1; + for (uint8_t axis = start; axis < 13; axis += step) { + const float offset_circles = _7p_quadruple_circle ? (zig_zag ? 1.5 : 1.0) : + _7p_triple_circle ? (zig_zag ? 1.0 : 0.5) : + _7p_double_circle ? (zig_zag ? 0.5 : 0.0) : 0; for (float circles = -offset_circles ; circles <= offset_circles; circles++) { - setup_for_endstop_or_probe_move(); - z_at_pt[axis] += probe_pt( // TODO: Needs error handling - cos(RADIANS(180 + 30 * axis)) * delta_calibration_radius * - (1 + circles * 0.1 * (zig_zag ? 1 : -1)), - sin(RADIANS(180 + 30 * axis)) * delta_calibration_radius * - (1 + circles * 0.1 * (zig_zag ? 1 : -1)), true, 1); - clean_up_after_endstop_or_probe_move(); + const float a = RADIANS(180 + 30 * axis), + r = delta_calibration_radius * (1 + circles * (zig_zag ? 0.1 : -0.1)); + z_at_pt[axis] += probe_pt(cos(a) * r, sin(a) * r, true, 1); // TODO: Needs error handling } zig_zag = !zig_zag; z_at_pt[axis] /= (2 * offset_circles + 1); } } - if (point_averaging) // average intermediates to tower and opposites + if (_7p_intermed_points) // average intermediates to tower and opposites for (uint8_t axis = 1; axis <= 11; axis += 2) z_at_pt[axis] = (z_at_pt[axis] + (z_at_pt[axis + 1] + z_at_pt[(axis + 10) % 12 + 1]) / 2.0) / 2.0; S1 += z_at_pt[0]; S2 += sq(z_at_pt[0]); N++; - if (!do_height_only) // std dev from zero plane - for (uint8_t axis = (probe_mode == -2 ? 3 : 1); axis < 13; axis += (do_center_and_towers ? 4 : 2)) { + if (!_1p_calibration) // std dev from zero plane + for (uint8_t axis = (_4p_opposite_points ? 3 : 1); axis < 13; axis += (_4p_calibration ? 4 : 2)) { S1 += z_at_pt[axis]; S2 += sq(z_at_pt[axis]); N++; } + zero_std_dev_old = zero_std_dev; zero_std_dev = round(sqrt(S2 / N) * 1000.0) / 1000.0 + 0.00001; + + if (iterations == 1) home_offset[Z_AXIS] = zh_old; // reset height after 1st probe change // Solve matrices - if (zero_std_dev < test_precision) { + if (zero_std_dev < test_precision && zero_std_dev > calibration_precision) { COPY(e_old, endstop_adj); dr_old = delta_radius; zh_old = home_offset[Z_AXIS]; alpha_old = delta_tower_angle_trim[A_AXIS]; beta_old = delta_tower_angle_trim[B_AXIS]; - float e_delta[XYZ] = { 0.0 }, r_delta = 0.0, - t_alpha = 0.0, t_beta = 0.0; + float e_delta[XYZ] = { 0.0 }, r_delta = 0.0, t_alpha = 0.0, t_beta = 0.0; const float r_diff = delta_radius - delta_calibration_radius, h_factor = 1.00 + r_diff * 0.001, //1.02 for r_diff = 20mm r_factor = -(1.75 + 0.005 * r_diff + 0.001 * sq(r_diff)), //2.25 for r_diff = 20mm @@ -5293,25 +5318,25 @@ void home_all_axes() { gcode_G28(true); } #define Z0444(I) ZP(a_factor * 4.0 / 9.0, I) #define Z0888(I) ZP(a_factor * 8.0 / 9.0, I) - switch (probe_mode) { - case -1: - test_precision = 0.00; + switch (probe_points) { case 1: + test_precision = 0.00; LOOP_XYZ(i) e_delta[i] = Z1000(0); break; case 2: - e_delta[X_AXIS] = Z1050(0) + Z0700(1) - Z0350(5) - Z0350(9); - e_delta[Y_AXIS] = Z1050(0) - Z0350(1) + Z0700(5) - Z0350(9); - e_delta[Z_AXIS] = Z1050(0) - Z0350(1) - Z0350(5) + Z0700(9); - r_delta = Z2250(0) - Z0750(1) - Z0750(5) - Z0750(9); - break; - - case -2: - e_delta[X_AXIS] = Z1050(0) - Z0700(7) + Z0350(11) + Z0350(3); - e_delta[Y_AXIS] = Z1050(0) + Z0350(7) - Z0700(11) + Z0350(3); - e_delta[Z_AXIS] = Z1050(0) + Z0350(7) + Z0350(11) - Z0700(3); - r_delta = Z2250(0) - Z0750(7) - Z0750(11) - Z0750(3); + if (towers_set) { + e_delta[X_AXIS] = Z1050(0) + Z0700(1) - Z0350(5) - Z0350(9); + e_delta[Y_AXIS] = Z1050(0) - Z0350(1) + Z0700(5) - Z0350(9); + e_delta[Z_AXIS] = Z1050(0) - Z0350(1) - Z0350(5) + Z0700(9); + r_delta = Z2250(0) - Z0750(1) - Z0750(5) - Z0750(9); + } + else { + e_delta[X_AXIS] = Z1050(0) - Z0700(7) + Z0350(11) + Z0350(3); + e_delta[Y_AXIS] = Z1050(0) + Z0350(7) - Z0700(11) + Z0350(3); + e_delta[Z_AXIS] = Z1050(0) + Z0350(7) + Z0350(11) - Z0700(3); + r_delta = Z2250(0) - Z0750(7) - Z0750(11) - Z0750(3); + } break; default: @@ -5320,9 +5345,9 @@ void home_all_axes() { gcode_G28(true); } e_delta[Z_AXIS] = Z1050(0) - Z0175(1) - Z0175(5) + Z0350(9) + Z0175(7) + Z0175(11) - Z0350(3); r_delta = Z2250(0) - Z0375(1) - Z0375(5) - Z0375(9) - Z0375(7) - Z0375(11) - Z0375(3); - if (probe_mode > 0) { // negative disables tower angles - t_alpha = + Z0444(1) - Z0888(5) + Z0444(9) + Z0444(7) - Z0888(11) + Z0444(3); - t_beta = - Z0888(1) + Z0444(5) + Z0444(9) - Z0888(7) + Z0444(11) + Z0444(3); + if (towers_set) { + t_alpha = Z0444(1) - Z0888(5) + Z0444(9) + Z0444(7) - Z0888(11) + Z0444(3); + t_beta = Z0888(1) - Z0444(5) - Z0444(9) + Z0888(7) - Z0444(11) - Z0444(3); } break; } @@ -5330,7 +5355,7 @@ void home_all_axes() { gcode_G28(true); } LOOP_XYZ(axis) endstop_adj[axis] += e_delta[axis]; delta_radius += r_delta; delta_tower_angle_trim[A_AXIS] += t_alpha; - delta_tower_angle_trim[B_AXIS] -= t_beta; + delta_tower_angle_trim[B_AXIS] += t_beta; // adjust delta_height and endstops by the max amount const float z_temp = MAX3(endstop_adj[A_AXIS], endstop_adj[B_AXIS], endstop_adj[C_AXIS]); @@ -5339,7 +5364,7 @@ void home_all_axes() { gcode_G28(true); } recalc_delta_settings(delta_radius, delta_diagonal_rod); } - else { // step one back + else if(zero_std_dev >= test_precision) { // step one back COPY(endstop_adj, e_old); delta_radius = dr_old; home_offset[Z_AXIS] = zh_old; @@ -5355,7 +5380,7 @@ void home_all_axes() { gcode_G28(true); } SERIAL_PROTOCOLPGM(". c:"); if (z_at_pt[0] > 0) SERIAL_CHAR('+'); SERIAL_PROTOCOL_F(z_at_pt[0], 2); - if (probe_mode == 2 || probe_center_plus_3) { + if (_4p_towers_points || _7p_calibration) { SERIAL_PROTOCOLPGM(" x:"); if (z_at_pt[1] >= 0) SERIAL_CHAR('+'); SERIAL_PROTOCOL_F(z_at_pt[1], 2); @@ -5366,9 +5391,9 @@ void home_all_axes() { gcode_G28(true); } if (z_at_pt[9] >= 0) SERIAL_CHAR('+'); SERIAL_PROTOCOL_F(z_at_pt[9], 2); } - if (probe_mode != -2) SERIAL_EOL; - if (probe_mode == -2 || probe_center_plus_3) { - if (probe_center_plus_3) { + if (!_4p_opposite_points) SERIAL_EOL; + if ((_4p_opposite_points) || _7p_calibration) { + if (_7p_calibration) { SERIAL_CHAR('.'); SERIAL_PROTOCOL_SP(13); } @@ -5385,10 +5410,15 @@ void home_all_axes() { gcode_G28(true); } } } if (test_precision != 0.0) { // !forced end - if (zero_std_dev >= test_precision) { // end iterations + if (zero_std_dev >= test_precision || zero_std_dev <= calibration_precision) { // end iterations SERIAL_PROTOCOLPGM("Calibration OK"); SERIAL_PROTOCOL_SP(36); - SERIAL_PROTOCOLPGM("rolling back."); + if (zero_std_dev >= test_precision) + SERIAL_PROTOCOLPGM("rolling back."); + else { + SERIAL_PROTOCOLPGM("std dev:"); + SERIAL_PROTOCOL_F(zero_std_dev, 3); + } SERIAL_EOL; LCD_MESSAGEPGM("Calibration OK"); // TODO: Make translatable string } @@ -5404,7 +5434,7 @@ void home_all_axes() { gcode_G28(true); } lcd_setstatus(mess); } SERIAL_PROTOCOLPAIR(".Height:", DELTA_HEIGHT + home_offset[Z_AXIS]); - if (!do_height_only) { + if (!_1p_calibration) { SERIAL_PROTOCOLPGM(" Ex:"); if (endstop_adj[A_AXIS] >= 0) SERIAL_CHAR('+'); SERIAL_PROTOCOL_F(endstop_adj[A_AXIS], 2); @@ -5417,7 +5447,7 @@ void home_all_axes() { gcode_G28(true); } SERIAL_PROTOCOLPAIR(" Radius:", delta_radius); } SERIAL_EOL; - if (probe_mode > 2) { // negative disables tower angles + if (_7p_calibration && towers_set) { SERIAL_PROTOCOLPGM(".Tower angle : Tx:"); if (delta_tower_angle_trim[A_AXIS] >= 0) SERIAL_CHAR('+'); SERIAL_PROTOCOL_F(delta_tower_angle_trim[A_AXIS], 2); @@ -5427,7 +5457,7 @@ void home_all_axes() { gcode_G28(true); } SERIAL_PROTOCOLPGM(" Tz:+0.00"); SERIAL_EOL; } - if (zero_std_dev >= test_precision) + if (zero_std_dev >= test_precision || zero_std_dev <= calibration_precision) serialprintPGM(save_message); SERIAL_EOL; } @@ -5449,12 +5479,20 @@ void home_all_axes() { gcode_G28(true); } } } - stepper.synchronize(); - - home_all_axes(); + endstops.enable(true); + home_delta(); + endstops.not_homing(); - } while (zero_std_dev < test_precision && iterations < 31); + } + while (zero_std_dev < test_precision && zero_std_dev > calibration_precision && iterations < 31); + #if ENABLED(DELTA_HOME_TO_SAFE_ZONE) + do_blocking_move_to_z(delta_clip_start_height); + #endif + clean_up_after_endstop_or_probe_move(); + #if HOTENDS > 1 + tool_change(old_tool_index, 0, true); + #endif #if ENABLED(Z_PROBE_SLED) RETRACT_PROBE(); #endif diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h index 2c31e0226..b23bb75f6 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h @@ -447,10 +447,10 @@ #define DELTA_DIAGONAL_ROD 218.0 // mm // Horizontal distance bridged by diagonal push rods when effector is centered. - #define DELTA_RADIUS 100.00 //mm // get this value from auto calibrate + #define DELTA_RADIUS 100.00 //mm Get this value from auto calibrate // height from z=0 to home position - #define DELTA_HEIGHT 295.00 // get this value from auto calibrate - use G33 P1 A at 1st time calibration + #define DELTA_HEIGHT 295.00 // get this value from auto calibrate - use G33 P1 at 1st time calibration // Print surface diameter/2 minus unreachable space (avoid collisions with vertical towers). #define DELTA_PRINTABLE_RADIUS 85.0 @@ -460,8 +460,8 @@ // See http://minow.blogspot.com/index.html#4918805519571907051 #define DELTA_CALIBRATION_MENU - // set the radius for the calibration probe points - max 0.8 * DELTA_PRINTABLE_RADIUS if DELTA_AUTO_CALIBRATION enabled - #define DELTA_CALIBRATION_RADIUS (DELTA_PRINTABLE_RADIUS - 17) // mm + // set the radius for the calibration probe points - max DELTA_PRINTABLE_RADIUS*0.869 if DELTA_AUTO_CALIBRATION enabled + #define DELTA_CALIBRATION_RADIUS ((DELTA_PRINTABLE_RADIUS) * 0.869) // mm // G33 Delta Auto-Calibration (Enable EEPROM_SETTINGS to store results) #define DELTA_AUTO_CALIBRATION diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h index ce585c1af..9838387b4 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h @@ -454,10 +454,10 @@ #define DELTA_CARRIAGE_OFFSET 22.0 // mm // Horizontal distance bridged by diagonal push rods when effector is centered. - #define DELTA_RADIUS (DELTA_SMOOTH_ROD_OFFSET - DELTA_EFFECTOR_OFFSET - DELTA_CARRIAGE_OFFSET) //mm // get this value from auto calibrate + #define DELTA_RADIUS (DELTA_SMOOTH_ROD_OFFSET - DELTA_EFFECTOR_OFFSET - DELTA_CARRIAGE_OFFSET) //mm Get this value from auto calibrate // height from z=0.00 to home position - #define DELTA_HEIGHT 280 // get this value from auto calibrate - use G33 C-1 at 1st time calibration + #define DELTA_HEIGHT 280 // get this value from auto calibrate - use G33 P1 at 1st time calibration // Print surface diameter/2 minus unreachable space (avoid collisions with vertical towers). #define DELTA_PRINTABLE_RADIUS 85.0 @@ -467,8 +467,8 @@ // See http://minow.blogspot.com/index.html#4918805519571907051 //#define DELTA_CALIBRATION_MENU - // set the radius for the calibration probe points - max 0.8 * DELTA_PRINTABLE_RADIUS if DELTA_AUTO_CALIBRATION enabled - #define DELTA_CALIBRATION_RADIUS (DELTA_PRINTABLE_RADIUS - 17) // mm + // set the radius for the calibration probe points - max DELTA_PRINTABLE_RADIUS*0.869 if DELTA_AUTO_CALIBRATION enabled + #define DELTA_CALIBRATION_RADIUS ((DELTA_PRINTABLE_RADIUS) * 0.869) // mm // G33 Delta Auto-Calibration (Enable EEPROM_SETTINGS to store results) //#define DELTA_AUTO_CALIBRATION diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index 0b942adba..dee93545c 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -444,10 +444,10 @@ #define DELTA_CARRIAGE_OFFSET 18.0 // mm // Horizontal distance bridged by diagonal push rods when effector is centered. - #define DELTA_RADIUS (DELTA_SMOOTH_ROD_OFFSET - DELTA_EFFECTOR_OFFSET - DELTA_CARRIAGE_OFFSET) //mm // get this value from auto calibrate // height from z=0.00 to home position + #define DELTA_RADIUS (DELTA_SMOOTH_ROD_OFFSET - DELTA_EFFECTOR_OFFSET - DELTA_CARRIAGE_OFFSET) //mm Get this value from auto calibrate // height from z=0.00 to home position - #define DELTA_HEIGHT 250 // get this value from auto calibrate - use G33 C-1 at 1st time calibration + #define DELTA_HEIGHT 250 // get this value from auto calibrate - use G33 P1 at 1st time calibration // Print surface diameter/2 minus unreachable space (avoid collisions with vertical towers). #define DELTA_PRINTABLE_RADIUS 140.0 @@ -456,8 +456,8 @@ // See http://minow.blogspot.com/index.html#4918805519571907051 //#define DELTA_CALIBRATION_MENU - // set the radius for the calibration probe points - max 0.8 * DELTA_PRINTABLE_RADIUS if DELTA_AUTO_CALIBRATION enabled - #define DELTA_CALIBRATION_RADIUS (DELTA_PRINTABLE_RADIUS - 28) // mm + // set the radius for the calibration probe points - max DELTA_PRINTABLE_RADIUS*0.869 if DELTA_AUTO_CALIBRATION enabled + #define DELTA_CALIBRATION_RADIUS ((DELTA_PRINTABLE_RADIUS) * 0.869) // mm // G33 Delta Auto-Calibration (Enable EEPROM_SETTINGS to store results) //#define DELTA_AUTO_CALIBRATION diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index 3c9fff7d6..5af56f449 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -444,10 +444,10 @@ #define DELTA_CARRIAGE_OFFSET 19.5 // mm // Horizontal distance bridged by diagonal push rods when effector is centered. - #define DELTA_RADIUS (DELTA_SMOOTH_ROD_OFFSET - DELTA_EFFECTOR_OFFSET - DELTA_CARRIAGE_OFFSET) //mm // get this value from auto calibrate + #define DELTA_RADIUS (DELTA_SMOOTH_ROD_OFFSET - DELTA_EFFECTOR_OFFSET - DELTA_CARRIAGE_OFFSET) //mm Get this value from auto calibrate // height from z=0.00 to home position - #define DELTA_HEIGHT 250 // get this value from auto calibrate - use G33 C-1 at 1st time calibration + #define DELTA_HEIGHT 250 // get this value from auto calibrate - use G33 P1 at 1st time calibration // Print surface diameter/2 minus unreachable space (avoid collisions with vertical towers). #define DELTA_PRINTABLE_RADIUS 90.0 @@ -456,8 +456,8 @@ // See http://minow.blogspot.com/index.html#4918805519571907051 //#define DELTA_CALIBRATION_MENU - // set the radius for the calibration probe points - max 0.8 * DELTA_PRINTABLE_RADIUS if DELTA_AUTO_CALIBRATION enabled - #define DELTA_CALIBRATION_RADIUS (DELTA_PRINTABLE_RADIUS - 18) // mm + // set the radius for the calibration probe points - max DELTA_PRINTABLE_RADIUS*0.869 if DELTA_AUTO_CALIBRATION enabled + #define DELTA_CALIBRATION_RADIUS ((DELTA_PRINTABLE_RADIUS) * 0.869) // mm // G33 Delta Auto-Calibration (Enable EEPROM_SETTINGS to store results) //#define DELTA_AUTO_CALIBRATION diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration.h b/Marlin/example_configurations/delta/kossel_pro/Configuration.h index 6e672402a..1a623d6b0 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration.h @@ -431,10 +431,10 @@ #define DELTA_CARRIAGE_OFFSET 30.0 // mm // Horizontal distance bridged by diagonal push rods when effector is centered. - #define DELTA_RADIUS (DELTA_SMOOTH_ROD_OFFSET - DELTA_EFFECTOR_OFFSET - DELTA_CARRIAGE_OFFSET) //mm // get this value from auto calibrate + #define DELTA_RADIUS (DELTA_SMOOTH_ROD_OFFSET - DELTA_EFFECTOR_OFFSET - DELTA_CARRIAGE_OFFSET) //mm Get this value from auto calibrate // height from z=0.00 to home position - #define DELTA_HEIGHT 277 // get this value from auto calibrate - use G33 C-1 at 1st time calibration + #define DELTA_HEIGHT 277 // get this value from auto calibrate - use G33 P1 at 1st time calibration // Print surface diameter/2 minus unreachable space (avoid collisions with vertical towers). #define DELTA_PRINTABLE_RADIUS 127.0 @@ -443,8 +443,8 @@ // See http://minow.blogspot.com/index.html#4918805519571907051 //#define DELTA_CALIBRATION_MENU - // set the radius for the calibration probe points - max 0.8 * DELTA_PRINTABLE_RADIUS if DELTA_AUTO_CALIBRATION enabled - #define DELTA_CALIBRATION_RADIUS (DELTA_PRINTABLE_RADIUS - 25.4) // mm + // set the radius for the calibration probe points - max DELTA_PRINTABLE_RADIUS*0.869 if DELTA_AUTO_CALIBRATION enabled + #define DELTA_CALIBRATION_RADIUS ((DELTA_PRINTABLE_RADIUS) * 0.869) // mm // G33 Delta Auto-Calibration (Enable EEPROM_SETTINGS to store results) //#define DELTA_AUTO_CALIBRATION diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration.h b/Marlin/example_configurations/delta/kossel_xl/Configuration.h index 62f9bafb5..fa9c00692 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration.h @@ -449,10 +449,10 @@ #define DELTA_CARRIAGE_OFFSET 22.0 // mm // Horizontal distance bridged by diagonal push rods when effector is centered. - #define DELTA_RADIUS (DELTA_SMOOTH_ROD_OFFSET - DELTA_EFFECTOR_OFFSET - DELTA_CARRIAGE_OFFSET) //mm // get this value from auto calibrate + #define DELTA_RADIUS (DELTA_SMOOTH_ROD_OFFSET - DELTA_EFFECTOR_OFFSET - DELTA_CARRIAGE_OFFSET) //mm Get this value from auto calibrate // height from z=0.00 to home position - #define DELTA_HEIGHT 380 // get this value from auto calibrate - use G33 C-1 at 1st time calibration + #define DELTA_HEIGHT 380 // get this value from auto calibrate - use G33 P1 at 1st time calibration // Print surface diameter/2 minus unreachable space (avoid collisions with vertical towers). #define DELTA_PRINTABLE_RADIUS 140.0 @@ -461,8 +461,8 @@ // See http://minow.blogspot.com/index.html#4918805519571907051 //#define DELTA_CALIBRATION_MENU - // set the radius for the calibration probe points - max 0.8 * DELTA_PRINTABLE_RADIUS if DELTA_AUTO_CALIBRATION enabled - #define DELTA_CALIBRATION_RADIUS (DELTA_PRINTABLE_RADIUS - 28) // mm + // set the radius for the calibration probe points - max DELTA_PRINTABLE_RADIUS*0.869 if DELTA_AUTO_CALIBRATION enabled + #define DELTA_CALIBRATION_RADIUS ((DELTA_PRINTABLE_RADIUS) * 0.869) // mm // G33 Delta Auto-Calibration (Enable EEPROM_SETTINGS to store results) //#define DELTA_AUTO_CALIBRATION diff --git a/Marlin/planner.h b/Marlin/planner.h index ca23979fa..d389adc46 100644 --- a/Marlin/planner.h +++ b/Marlin/planner.h @@ -160,8 +160,10 @@ class Planner { min_travel_feedrate_mm_s; #if HAS_ABL - static bool abl_enabled; // Flag that bed leveling is enabled - static matrix_3x3 bed_level_matrix; // Transform to compensate for bed level + static bool abl_enabled; // Flag that bed leveling is enabled + #if ABL_PLANAR + static matrix_3x3 bed_level_matrix; // Transform to compensate for bed level + #endif #endif #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index ac702737b..e66f55a53 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -2151,6 +2151,10 @@ void kill_screen(const char* lcd_msg) { } void _lcd_delta_calibrate_home() { + #if HAS_LEVELING + reset_bed_level(); // After calibration bed-level data is no longer valid + #endif + enqueue_and_echo_commands_P(PSTR("G28")); lcd_goto_screen(_lcd_calibrate_homing); } @@ -2158,6 +2162,10 @@ void kill_screen(const char* lcd_msg) { // Move directly to the tower position with uninterpolated moves // If we used interpolated moves it would cause this to become re-entrant void _goto_tower_pos(const float &a) { + #if HAS_LEVELING + reset_bed_level(); // After calibration bed-level data is no longer valid + #endif + current_position[Z_AXIS] = max(Z_HOMING_HEIGHT, Z_CLEARANCE_BETWEEN_PROBES) + (DELTA_PRINTABLE_RADIUS) / 5; line_to_current(Z_AXIS); diff --git a/README.md b/README.md index dbbcf9721..2b296dc26 100644 --- a/README.md +++ b/README.md @@ -69,7 +69,7 @@ More features have been added by: - [[@Tannoo](https://github.com/Tannoo)] - [[@teemuatlut](https://github.com/teemuatlut)] - [[@bgort](https://github.com/bgort)] - - [[@LVD-AC](https://github.com/LVD-AC)] + - Luc Van Daele[[@LVD-AC](https://github.com/LVD-AC)] - Dutch, French, English - [[@paulusjacobus](https://github.com/paulusjacobus)] - ...and many others From ebcd1aaf88429850787c0ed38458998ee69d2585 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 21 May 2017 04:46:31 -0500 Subject: [PATCH 113/189] Access hotend/bed temperatures as float --- Marlin/temperature.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/temperature.h b/Marlin/temperature.h index e8632311d..c9dce1e6b 100644 --- a/Marlin/temperature.h +++ b/Marlin/temperature.h @@ -327,13 +327,13 @@ class Temperature { //inline so that there is no performance decrease. //deg=degreeCelsius - static int16_t degHotend(uint8_t e) { + static float degHotend(uint8_t e) { #if HOTENDS == 1 UNUSED(e); #endif return current_temperature[HOTEND_INDEX]; } - static int16_t degBed() { return current_temperature_bed; } + static float degBed() { return current_temperature_bed; } #if ENABLED(SHOW_TEMP_ADC_VALUES) static int16_t rawHotendTemp(uint8_t e) { From b29dbbd5e43fa95e7089d41c1bf1f9092ff533c8 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 21 May 2017 04:48:53 -0500 Subject: [PATCH 114/189] Use uint16_t for temps --- Marlin/temperature.cpp | 8 ++++---- Marlin/temperature.h | 8 ++++---- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/Marlin/temperature.cpp b/Marlin/temperature.cpp index 94c1e4a58..bc503b6bd 100644 --- a/Marlin/temperature.cpp +++ b/Marlin/temperature.cpp @@ -103,24 +103,24 @@ int16_t Temperature::current_temperature_raw[HOTENDS] = { 0 }, #endif #if WATCH_HOTENDS - int Temperature::watch_target_temp[HOTENDS] = { 0 }; + uint16_t Temperature::watch_target_temp[HOTENDS] = { 0 }; millis_t Temperature::watch_heater_next_ms[HOTENDS] = { 0 }; #endif #if WATCH_THE_BED - int Temperature::watch_target_bed_temp = 0; + uint16_t Temperature::watch_target_bed_temp = 0; millis_t Temperature::watch_bed_next_ms = 0; #endif #if ENABLED(PREVENT_COLD_EXTRUSION) bool Temperature::allow_cold_extrude = false; - float Temperature::extrude_min_temp = EXTRUDE_MINTEMP; + uint16_t Temperature::extrude_min_temp = EXTRUDE_MINTEMP; #endif // private: #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - int Temperature::redundant_temperature_raw = 0; + uint16_t Temperature::redundant_temperature_raw = 0; float Temperature::redundant_temperature = 0.0; #endif diff --git a/Marlin/temperature.h b/Marlin/temperature.h index c9dce1e6b..a3c4372df 100644 --- a/Marlin/temperature.h +++ b/Marlin/temperature.h @@ -158,18 +158,18 @@ class Temperature { #endif #if WATCH_HOTENDS - static int watch_target_temp[HOTENDS]; + static uint16_t watch_target_temp[HOTENDS]; static millis_t watch_heater_next_ms[HOTENDS]; #endif #if WATCH_THE_BED - static int watch_target_bed_temp; + static uint16_t watch_target_bed_temp; static millis_t watch_bed_next_ms; #endif #if ENABLED(PREVENT_COLD_EXTRUSION) static bool allow_cold_extrude; - static float extrude_min_temp; + static uint16_t extrude_min_temp; static bool tooColdToExtrude(uint8_t e) { #if HOTENDS == 1 UNUSED(e); @@ -183,7 +183,7 @@ class Temperature { private: #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - static int redundant_temperature_raw; + static uint16_t redundant_temperature_raw; static float redundant_temperature; #endif From 8a0a5cfcccbfe16f9019230f9750516ec41aad35 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 21 May 2017 04:49:25 -0500 Subject: [PATCH 115/189] Temp-related cosmetic changes --- Marlin/Marlin_main.cpp | 8 +++--- Marlin/temperature.cpp | 55 +++++++++++++----------------------------- 2 files changed, 21 insertions(+), 42 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 30ffb1162..3caccf8d9 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -6684,7 +6684,8 @@ inline void gcode_M104() { } #endif - if (code_value_temp_abs() > thermalManager.degHotend(target_extruder)) lcd_status_printf_P(0, PSTR("E%i %s"), target_extruder + 1, MSG_HEATING); + if (code_value_temp_abs() > thermalManager.degHotend(target_extruder)) + lcd_status_printf_P(0, PSTR("E%i %s"), target_extruder + 1, MSG_HEATING); } #if ENABLED(AUTOTEMP) @@ -8290,7 +8291,7 @@ inline void gcode_M226() { // Report current state SERIAL_ECHO_START; SERIAL_ECHOPAIR("Cold extrudes are ", (thermalManager.allow_cold_extrude ? "en" : "dis")); - SERIAL_ECHOPAIR("abled (min temp ", int(thermalManager.extrude_min_temp + 0.5)); + SERIAL_ECHOPAIR("abled (min temp ", thermalManager.extrude_min_temp); SERIAL_ECHOLNPGM("C)"); } } @@ -11909,9 +11910,8 @@ void prepare_move_to_destination() { #if HAS_TEMP_BED max_temp = MAX3(max_temp, thermalManager.degTargetBed(), thermalManager.degBed()); #endif - HOTEND_LOOP() { + HOTEND_LOOP() max_temp = MAX3(max_temp, thermalManager.degHotend(e), thermalManager.degTargetHotend(e)); - } bool new_led = (max_temp > 55.0) ? true : (max_temp < 54.0) ? false : red_led; if (new_led != red_led) { red_led = new_led; diff --git a/Marlin/temperature.cpp b/Marlin/temperature.cpp index bc503b6bd..d7d681430 100644 --- a/Marlin/temperature.cpp +++ b/Marlin/temperature.cpp @@ -695,66 +695,47 @@ void Temperature::manage_heater() { updateTemperaturesFromRawValues(); // also resets the watchdog #if ENABLED(HEATER_0_USES_MAX6675) - if (current_temperature[0] > min(HEATER_0_MAXTEMP, MAX6675_TMAX - 1)) max_temp_error(0); - if (current_temperature[0] < max(HEATER_0_MINTEMP, MAX6675_TMIN + 0.01)) min_temp_error(0); + if (current_temperature[0] > min(HEATER_0_MAXTEMP, MAX6675_TMAX - 1.0)) max_temp_error(0); + if (current_temperature[0] < max(HEATER_0_MINTEMP, MAX6675_TMIN + .01)) min_temp_error(0); #endif #if WATCH_HOTENDS || WATCH_THE_BED || DISABLED(PIDTEMPBED) || HAS_AUTO_FAN millis_t ms = millis(); #endif - // Loop through all hotends HOTEND_LOOP() { #if ENABLED(THERMAL_PROTECTION_HOTENDS) + // Check for thermal runaway thermal_runaway_protection(&thermal_runaway_state_machine[e], &thermal_runaway_timer[e], current_temperature[e], target_temperature[e], e, THERMAL_PROTECTION_PERIOD, THERMAL_PROTECTION_HYSTERESIS); #endif - float pid_output = get_pid_output(e); + soft_pwm_amount[e] = (current_temperature[e] > minttemp[e] || is_preheating(e)) && current_temperature[e] < maxttemp[e] ? (int)get_pid_output(e) >> 1 : 0; - // Check if temperature is within the correct range - soft_pwm_amount[e] = (current_temperature[e] > minttemp[e] || is_preheating(e)) && current_temperature[e] < maxttemp[e] ? (int)pid_output >> 1 : 0; - - // Check if the temperature is failing to increase #if WATCH_HOTENDS - - // Is it time to check this extruder's heater? - if (watch_heater_next_ms[e] && ELAPSED(ms, watch_heater_next_ms[e])) { - // Has it failed to increase enough? - if (degHotend(e) < watch_target_temp[e]) { - // Stop! + // Make sure temperature is increasing + if (watch_heater_next_ms[e] && ELAPSED(ms, watch_heater_next_ms[e])) { // Time to check this extruder? + if (degHotend(e) < watch_target_temp[e]) // Failed to increase enough? _temp_error(e, PSTR(MSG_T_HEATING_FAILED), PSTR(MSG_HEATING_FAILED_LCD)); - } - else { - // Start again if the target is still far off + else // Start again if the target is still far off start_watching_heater(e); - } } + #endif - #endif // THERMAL_PROTECTION_HOTENDS - - // Check if the temperature is failing to increase #if WATCH_THE_BED - - // Is it time to check the bed? - if (watch_bed_next_ms && ELAPSED(ms, watch_bed_next_ms)) { - // Has it failed to increase enough? - if (degBed() < watch_target_bed_temp) { - // Stop! + // Make sure temperature is increasing + if (watch_bed_next_ms && ELAPSED(ms, watch_bed_next_ms)) { // Time to check the bed? + if (degBed() < watch_target_bed_temp) // Failed to increase enough? _temp_error(-1, PSTR(MSG_T_HEATING_FAILED), PSTR(MSG_HEATING_FAILED_LCD)); - } - else { - // Start again if the target is still far off + else // Start again if the target is still far off start_watching_bed(); - } } - - #endif // THERMAL_PROTECTION_HOTENDS + #endif #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - if (fabs(current_temperature[0] - redundant_temperature) > MAX_REDUNDANT_TEMP_SENSOR_DIFF) { + // Make sure measured temperatures are close together + if (fabs(current_temperature[0] - redundant_temperature) > MAX_REDUNDANT_TEMP_SENSOR_DIFF) _temp_error(0, PSTR(MSG_REDUNDANCY), PSTR(MSG_ERR_REDUNDANT_TEMP)); - } #endif } // HOTEND_LOOP @@ -792,9 +773,7 @@ void Temperature::manage_heater() { #endif #if ENABLED(PIDTEMPBED) - float pid_output = get_pid_output_bed(); - - soft_pwm_amount_bed = WITHIN(current_temperature_bed, BED_MINTEMP, BED_MAXTEMP) ? (int)pid_output >> 1 : 0; + soft_pwm_amount_bed = WITHIN(current_temperature_bed, BED_MINTEMP, BED_MAXTEMP) ? (int)get_pid_output_bed() >> 1 : 0; #elif ENABLED(BED_LIMIT_SWITCHING) // Check if temperature is within the correct band From 11fc9564c9700a884ff8c7feb2465a5e0207d947 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 20 May 2017 19:54:23 -0500 Subject: [PATCH 116/189] Add live editing option to LCD menu --- Marlin/configuration_store.cpp | 6 +-- Marlin/ultralcd.cpp | 80 +++++++++++++--------------------- Marlin/ultralcd.h | 4 +- Marlin/ultralcd_impl_DOGM.h | 2 +- 4 files changed, 37 insertions(+), 55 deletions(-) diff --git a/Marlin/configuration_store.cpp b/Marlin/configuration_store.cpp index a6cb8889d..85780fbc3 100644 --- a/Marlin/configuration_store.cpp +++ b/Marlin/configuration_store.cpp @@ -123,7 +123,7 @@ * 490 M304 PID thermalManager.bedKp, .bedKi, .bedKd (float x3) * * DOGLCD: 2 bytes - * 502 M250 C lcd_contrast (int) + * 502 M250 C lcd_contrast (uint16_t) * * FWRETRACT: 29 bytes * 504 M209 S autoretract_enabled (bool) @@ -502,7 +502,7 @@ void MarlinSettings::postprocess() { #endif #if !HAS_LCD_CONTRAST - const int lcd_contrast = 32; + const uint16_t lcd_contrast = 32; #endif EEPROM_WRITE(lcd_contrast); @@ -883,7 +883,7 @@ void MarlinSettings::postprocess() { #endif #if !HAS_LCD_CONTRAST - int lcd_contrast; + uint16_t lcd_contrast; #endif EEPROM_READ(lcd_contrast); diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index e66f55a53..868846952 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -148,10 +148,6 @@ uint16_t max_display_update_time = 0; void lcd_dac_write_eeprom(); #endif - #if HAS_LCD_CONTRAST - void lcd_set_contrast(); - #endif - #if ENABLED(FWRETRACT) void lcd_control_retract_menu(); #endif @@ -181,7 +177,7 @@ uint16_t max_display_update_time = 0; void menu_edit_callback_ ## _name(); \ void _menu_action_setting_edit_ ## _name(const char * const pstr, _type* const ptr, const _type minValue, const _type maxValue); \ void menu_action_setting_edit_ ## _name(const char * const pstr, _type * const ptr, const _type minValue, const _type maxValue); \ - void menu_action_setting_edit_callback_ ## _name(const char * const pstr, _type * const ptr, const _type minValue, const _type maxValue, const screenFunc_t callback); \ + void menu_action_setting_edit_callback_ ## _name(const char * const pstr, _type * const ptr, const _type minValue, const _type maxValue, const screenFunc_t callback, const bool live=false); \ typedef void _name##_void DECLARE_MENU_EDIT_TYPE(int, int3); @@ -419,6 +415,7 @@ uint16_t max_display_update_time = 0; void *editValue; int32_t minEditValue, maxEditValue; screenFunc_t callbackFunc; + bool liveEdit; // Manual Moves const float manual_feedrate_mm_m[] = MANUAL_FEEDRATE; @@ -590,7 +587,7 @@ void lcd_status_screen() { } #if ENABLED(ULTIPANEL_FEEDMULTIPLY) - int new_frm = feedrate_percentage + (int32_t)encoderPosition; + const int new_frm = feedrate_percentage + (int32_t)encoderPosition; // Dead zone at 100% feedrate if ((feedrate_percentage < 100 && new_frm > 100) || (feedrate_percentage > 100 && new_frm < 100)) { feedrate_percentage = 100; @@ -2465,6 +2462,17 @@ void kill_screen(const char* lcd_msg) { * */ + /** + * + * Callback for LCD contrast + * + */ + #if HAS_LCD_CONTRAST + + void lcd_callback_set_contrast() { set_lcd_contrast(lcd_contrast); } + + #endif // HAS_LCD_CONTRAST + #if ENABLED(EEPROM_SETTINGS) static void lcd_store_settings() { lcd_completion_feedback(settings.save()); } static void lcd_load_settings() { lcd_completion_feedback(settings.load()); } @@ -2483,8 +2491,7 @@ void kill_screen(const char* lcd_msg) { MENU_ITEM(submenu, MSG_FILAMENT, lcd_control_filament_menu); #if HAS_LCD_CONTRAST - //MENU_ITEM_EDIT(int3, MSG_CONTRAST, &lcd_contrast, 0, 63); - MENU_ITEM(submenu, MSG_CONTRAST, lcd_set_contrast); + MENU_ITEM_EDIT_CALLBACK(int3, MSG_CONTRAST, &lcd_contrast, LCD_CONTRAST_MIN, LCD_CONTRAST_MAX, lcd_callback_set_contrast, true); #endif #if ENABLED(FWRETRACT) MENU_ITEM(submenu, MSG_RETRACT, lcd_control_retract_menu); @@ -2953,32 +2960,6 @@ void kill_screen(const char* lcd_msg) { END_MENU(); } - /** - * - * "Control" > "Contrast" submenu - * - */ - #if HAS_LCD_CONTRAST - void lcd_set_contrast() { - if (lcd_clicked) { return lcd_goto_previous_menu(); } - ENCODER_DIRECTION_NORMAL(); - if (encoderPosition) { - set_lcd_contrast(lcd_contrast + encoderPosition); - encoderPosition = 0; - lcdDrawUpdate = LCDVIEW_REDRAW_NOW; - } - if (lcdDrawUpdate) { - lcd_implementation_drawedit(PSTR(MSG_CONTRAST), - #if LCD_CONTRAST_MAX >= 100 - itostr3(lcd_contrast) - #else - itostr2(lcd_contrast) - #endif - ); - } - } - #endif // HAS_LCD_CONTRAST - /** * * "Control" > "Retract" submenu @@ -3492,7 +3473,7 @@ void kill_screen(const char* lcd_msg) { * void menu_edit_callback_int3(); // edit int (interactively) with callback on completion * void _menu_action_setting_edit_int3(const char * const pstr, int * const ptr, const int minValue, const int maxValue); * void menu_action_setting_edit_int3(const char * const pstr, int * const ptr, const int minValue, const int maxValue); - * void menu_action_setting_edit_callback_int3(const char * const pstr, int * const ptr, const int minValue, const int maxValue, const screenFunc_t callback); // edit int with callback + * void menu_action_setting_edit_callback_int3(const char * const pstr, int * const ptr, const int minValue, const int maxValue, const screenFunc_t callback, const bool live); // edit int with callback * * You can then use one of the menu macros to present the edit interface: * MENU_ITEM_EDIT(int3, MSG_SPEED, &feedrate_percentage, 10, 999) @@ -3500,29 +3481,27 @@ void kill_screen(const char* lcd_msg) { * This expands into a more primitive menu item: * MENU_ITEM(setting_edit_int3, MSG_SPEED, PSTR(MSG_SPEED), &feedrate_percentage, 10, 999) * - * - * Also: MENU_MULTIPLIER_ITEM_EDIT, MENU_ITEM_EDIT_CALLBACK, and MENU_MULTIPLIER_ITEM_EDIT_CALLBACK - * + * ...which calls: * menu_action_setting_edit_int3(PSTR(MSG_SPEED), &feedrate_percentage, 10, 999) */ #define DEFINE_MENU_EDIT_TYPE(_type, _name, _strFunc, _scale) \ - bool _menu_edit_ ## _name () { \ + bool _menu_edit_ ## _name() { \ ENCODER_DIRECTION_NORMAL(); \ if ((int32_t)encoderPosition < 0) encoderPosition = 0; \ if ((int32_t)encoderPosition > maxEditValue) encoderPosition = maxEditValue; \ if (lcdDrawUpdate) \ lcd_implementation_drawedit(editLabel, _strFunc(((_type)((int32_t)encoderPosition + minEditValue)) * (1.0 / _scale))); \ - if (lcd_clicked) { \ + if (lcd_clicked || (liveEdit && lcdDrawUpdate)) { \ _type value = ((_type)((int32_t)encoderPosition + minEditValue)) * (1.0 / _scale); \ - if (editValue != NULL) \ - *((_type*)editValue) = value; \ - lcd_goto_previous_menu(); \ + if (editValue != NULL) *((_type*)editValue) = value; \ + if (liveEdit) (*callbackFunc)(); \ + if (lcd_clicked) lcd_goto_previous_menu(); \ } \ return lcd_clicked; \ } \ - void menu_edit_ ## _name () { _menu_edit_ ## _name(); } \ - void menu_edit_callback_ ## _name () { if (_menu_edit_ ## _name ()) (*callbackFunc)(); } \ - void _menu_action_setting_edit_ ## _name (const char * const pstr, _type* const ptr, const _type minValue, const _type maxValue) { \ + void menu_edit_ ## _name() { _menu_edit_ ## _name(); } \ + void menu_edit_callback_ ## _name() { if (_menu_edit_ ## _name()) (*callbackFunc)(); } \ + void _menu_action_setting_edit_ ## _name(const char * const pstr, _type* const ptr, const _type minValue, const _type maxValue) { \ lcd_save_previous_screen(); \ \ lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; \ @@ -3533,14 +3512,15 @@ void kill_screen(const char* lcd_msg) { maxEditValue = maxValue * _scale - minEditValue; \ encoderPosition = (*ptr) * _scale - minEditValue; \ } \ - void menu_action_setting_edit_ ## _name (const char * const pstr, _type * const ptr, const _type minValue, const _type maxValue) { \ + void menu_action_setting_edit_ ## _name(const char * const pstr, _type * const ptr, const _type minValue, const _type maxValue) { \ _menu_action_setting_edit_ ## _name(pstr, ptr, minValue, maxValue); \ currentScreen = menu_edit_ ## _name; \ } \ - void menu_action_setting_edit_callback_ ## _name (const char * const pstr, _type * const ptr, const _type minValue, const _type maxValue, const screenFunc_t callback) { \ + void menu_action_setting_edit_callback_ ## _name(const char * const pstr, _type * const ptr, const _type minValue, const _type maxValue, const screenFunc_t callback, const bool live) { \ _menu_action_setting_edit_ ## _name(pstr, ptr, minValue, maxValue); \ currentScreen = menu_edit_callback_ ## _name; \ callbackFunc = callback; \ + liveEdit = live; \ } \ typedef void _name @@ -3641,7 +3621,7 @@ void kill_screen(const char* lcd_msg) { #endif // SDSUPPORT - void menu_action_setting_edit_bool(const char* pstr, bool* ptr) {UNUSED(pstr); *ptr ^= true; lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; } + void menu_action_setting_edit_bool(const char* pstr, bool* ptr) { UNUSED(pstr); *ptr ^= true; lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; } void menu_action_setting_edit_callback_bool(const char* pstr, bool* ptr, screenFunc_t callback) { menu_action_setting_edit_bool(pstr, ptr); (*callback)(); @@ -4071,10 +4051,12 @@ void lcd_setalertstatuspgm(const char * const message) { void lcd_reset_alert_level() { lcd_status_message_level = 0; } #if HAS_LCD_CONTRAST + void set_lcd_contrast(const int value) { lcd_contrast = constrain(value, LCD_CONTRAST_MIN, LCD_CONTRAST_MAX); u8g.setContrast(lcd_contrast); } + #endif #if ENABLED(ULTIPANEL) diff --git a/Marlin/ultralcd.h b/Marlin/ultralcd.h index fbc5e1c4a..1bce5a096 100644 --- a/Marlin/ultralcd.h +++ b/Marlin/ultralcd.h @@ -55,8 +55,8 @@ #endif #if ENABLED(DOGLCD) - extern int lcd_contrast; - void set_lcd_contrast(int value); + extern uint16_t lcd_contrast; + void set_lcd_contrast(uint16_t value); #elif ENABLED(SHOW_BOOTSCREEN) void bootscreen(); #endif diff --git a/Marlin/ultralcd_impl_DOGM.h b/Marlin/ultralcd_impl_DOGM.h index 9c36573c5..8664c64b8 100644 --- a/Marlin/ultralcd_impl_DOGM.h +++ b/Marlin/ultralcd_impl_DOGM.h @@ -195,7 +195,7 @@ #include "utf_mapper.h" -int lcd_contrast; +uint16_t lcd_contrast; static char currentfont = 0; // The current graphical page being rendered From 52e20aeab3119751d33e34759aaa3316be255ea4 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 20 May 2017 19:30:36 -0500 Subject: [PATCH 117/189] Pins-related cleanup, formatting --- Marlin/pinsDebug.h | 2 +- Marlin/pins_BRAINWAVE.h | 2 +- Marlin/pins_BRAINWAVE_PRO.h | 2 +- Marlin/pins_RUMBA.h | 4 ++-- Marlin/pins_TEENSYLU.h | 2 +- .../pin_interrupt_test/pin_interrupt_test.ino | 22 +++++++++---------- 6 files changed, 17 insertions(+), 17 deletions(-) diff --git a/Marlin/pinsDebug.h b/Marlin/pinsDebug.h index a14f2b519..18062b79e 100644 --- a/Marlin/pinsDebug.h +++ b/Marlin/pinsDebug.h @@ -357,7 +357,7 @@ static void pwm_details(uint8_t pin) { // on pins that have two PWMs, print info on second PWM #if AVR_ATmega2560_FAMILY || AVR_AT90USB1286_FAMILY // looking for port B7 - PWMs 0A and 1C - if ( ('B' == digitalPinToPort(pin) + 64) && (0x80 == digitalPinToBitMask(pin))) { + if (digitalPinToPort(pin) == 2 && digitalPinToBitMask(pin) == 0x80) { #ifndef TEENSYDUINO_IDE SERIAL_PROTOCOLPGM("\n ."); SERIAL_PROTOCOL_SP(18); diff --git a/Marlin/pins_BRAINWAVE.h b/Marlin/pins_BRAINWAVE.h index 0d17cac10..83e7a35a9 100644 --- a/Marlin/pins_BRAINWAVE.h +++ b/Marlin/pins_BRAINWAVE.h @@ -41,7 +41,7 @@ * * "Marlin_AT90USB" makes PWM0A available rather than the usual PWM1C. These PWMs share * the same physical pin. Marlin uses TIMER1 to generate interrupts and sets it up such - * that PWM1A, PWM1B & PWM1C can not be used. + * that PWM1A, PWM1B & PWM1C can't be used. * * Installation: * diff --git a/Marlin/pins_BRAINWAVE_PRO.h b/Marlin/pins_BRAINWAVE_PRO.h index 1884d3cb1..02835ca27 100644 --- a/Marlin/pins_BRAINWAVE_PRO.h +++ b/Marlin/pins_BRAINWAVE_PRO.h @@ -63,7 +63,7 @@ * * "Marlin_AT90USB" makes PWM0A available rather than the usual PWM1C. These PWMs share * the same physical pin. Marlin uses TIMER1 to generate interrupts and sets it up such - * that PWM1A, PWM1B & PWM1C can not be used. + * that PWM1A, PWM1B & PWM1C can't be used. * * Installation: * diff --git a/Marlin/pins_RUMBA.h b/Marlin/pins_RUMBA.h index 23a9c3ad1..5f567783a 100644 --- a/Marlin/pins_RUMBA.h +++ b/Marlin/pins_RUMBA.h @@ -100,7 +100,7 @@ #endif #if TEMP_SENSOR_2 == -1 - #define TEMP_2_PIN 7 // Analog Input (connector *K3* on RUMBA thermocouple ADD ON is used <-- this can not be used when TEMP_SENSOR_BED is defined as thermocouple) + #define TEMP_2_PIN 7 // Analog Input (connector *K3* on RUMBA thermocouple ADD ON is used <-- this can't be used when TEMP_SENSOR_BED is defined as thermocouple) #else #define TEMP_2_PIN 13 // Analog Input (default connector for thermistor *T2* on rumba board is used) #endif @@ -109,7 +109,7 @@ //#define TEMP_X_PIN 12 // Analog Input (default connector for thermistor *T3* on rumba board is used) #if TEMP_SENSOR_BED == -1 - #define TEMP_BED_PIN 7 // Analog Input (connector *K3* on RUMBA thermocouple ADD ON is used <-- this can not be used when TEMP_SENSOR_2 is defined as thermocouple) + #define TEMP_BED_PIN 7 // Analog Input (connector *K3* on RUMBA thermocouple ADD ON is used <-- this can't be used when TEMP_SENSOR_2 is defined as thermocouple) #else #define TEMP_BED_PIN 11 // Analog Input (default connector for thermistor *THB* on rumba board is used) #endif diff --git a/Marlin/pins_TEENSYLU.h b/Marlin/pins_TEENSYLU.h index d845e312e..5f12e710c 100644 --- a/Marlin/pins_TEENSYLU.h +++ b/Marlin/pins_TEENSYLU.h @@ -68,7 +68,7 @@ * * NOTE - the "Marlin_AT90USB" pin maps make PWM0A available rather than the usual PWM1C. * These PWMs share the same physical pin. Marlin uses TIMER1 to generate - * interrupts and sets it up such that PWM1A, PWM1B & PWM1C can not be used. + * interrupts and sets it up such that PWM1A, PWM1B & PWM1C can't be used. */ /** diff --git a/buildroot/share/pin_interrupt_test/pin_interrupt_test.ino b/buildroot/share/pin_interrupt_test/pin_interrupt_test.ino index 8650a3d13..9702d9d91 100644 --- a/buildroot/share/pin_interrupt_test/pin_interrupt_test.ino +++ b/buildroot/share/pin_interrupt_test/pin_interrupt_test.ino @@ -1,26 +1,26 @@ -// Search pins uasable for endstop-interupts -// Compile with the same settings you'd use with Marlin. +// Search pins usable for endstop-interrupts +// Compile with the same build settings you'd use for Marlin. #if defined(ARDUINO_AVR_MEGA2560) || defined(ARDUINO_AVR_MEGA) #undef digitalPinToPCICR - #define digitalPinToPCICR(p) ( (((p) >= 10) && ((p) <= 15)) || \ - (((p) >= 50) && ((p) <= 53)) || \ - (((p) >= 62) && ((p) <= 69)) ? (&PCICR) : ((uint8_t *)0) ) + #define digitalPinToPCICR(p) ( ((p) >= 10 && (p) <= 15) || \ + ((p) >= 50 && (p) <= 53) || \ + ((p) >= 62 && (p) <= 69) ? &PCICR : (uint8_t *)0) #endif void setup() { Serial.begin(9600); Serial.println("PINs causing interrups are:"); - for(int i=2; i Date: Sun, 21 May 2017 05:28:38 -0500 Subject: [PATCH 118/189] UBL-related cleanup, spacing, standards Reference: #6804 --- Marlin/Marlin.h | 51 ++++++++++++++++------------------- Marlin/Marlin_main.cpp | 17 ++++++------ Marlin/ubl_G29.cpp | 60 ++++++++++++++++++++---------------------- 3 files changed, 60 insertions(+), 68 deletions(-) diff --git a/Marlin/Marlin.h b/Marlin/Marlin.h index d09616937..37f539320 100644 --- a/Marlin/Marlin.h +++ b/Marlin/Marlin.h @@ -438,63 +438,56 @@ void do_blocking_move_to_xy(const float &x, const float &y, const float &fr_mm_s #if IS_KINEMATIC // (DELTA or SCARA) - #if ENABLED(DELTA) - #define DELTA_PRINTABLE_RADIUS_SQUARED ((float)DELTA_PRINTABLE_RADIUS * (float)DELTA_PRINTABLE_RADIUS ) - #endif - #if IS_SCARA extern const float L1, L2; #endif - inline bool position_is_reachable_raw_xy( float raw_x, float raw_y ) { + inline bool position_is_reachable_raw_xy(const float &rx, const float &ry) { #if ENABLED(DELTA) - return ( HYPOT2( raw_x, raw_y ) <= DELTA_PRINTABLE_RADIUS_SQUARED ); + return HYPOT2(rx, ry) <= sq(DELTA_PRINTABLE_RADIUS); #elif IS_SCARA #if MIDDLE_DEAD_ZONE_R > 0 - const float R2 = HYPOT2(raw_x - SCARA_OFFSET_X, raw_y - SCARA_OFFSET_Y); + const float R2 = HYPOT2(rx - SCARA_OFFSET_X, ry - SCARA_OFFSET_Y); return R2 >= sq(float(MIDDLE_DEAD_ZONE_R)) && R2 <= sq(L1 + L2); #else - return HYPOT2(raw_x - SCARA_OFFSET_X, raw_y - SCARA_OFFSET_Y) <= sq(L1 + L2); + return HYPOT2(rx - SCARA_OFFSET_X, ry - SCARA_OFFSET_Y) <= sq(L1 + L2); #endif #else // CARTESIAN - #error + // To be migrated from MakerArm branch in future #endif } - inline bool position_is_reachable_by_probe_raw_xy( float raw_x, float raw_y ) { + inline bool position_is_reachable_by_probe_raw_xy(const float &rx, const float &ry) { - // both the nozzle and the probe must be able to reach the point + // Both the nozzle and the probe must be able to reach the point. + // This won't work on SCARA since the probe offset rotates with the arm. - return ( position_is_reachable_raw_xy( raw_x, raw_y ) && - position_is_reachable_raw_xy( - raw_x - X_PROBE_OFFSET_FROM_EXTRUDER, - raw_y - Y_PROBE_OFFSET_FROM_EXTRUDER )); + return position_is_reachable_raw_xy(rx, ry) + && position_is_reachable_raw_xy(rx - X_PROBE_OFFSET_FROM_EXTRUDER, ry - Y_PROBE_OFFSET_FROM_EXTRUDER); } #else // CARTESIAN - inline bool position_is_reachable_raw_xy( float raw_x, float raw_y ) { - // note to reviewer: this +/-0.0001 logic is copied from original postion_is_reachable - return WITHIN(raw_x, X_MIN_POS - 0.0001, X_MAX_POS + 0.0001) - && WITHIN(raw_y, Y_MIN_POS - 0.0001, Y_MAX_POS + 0.0001); + inline bool position_is_reachable_raw_xy(const float &rx, const float &ry) { + // Add 0.001 margin to deal with float imprecision + return WITHIN(rx, X_MIN_POS - 0.001, X_MAX_POS + 0.001) + && WITHIN(ry, Y_MIN_POS - 0.001, Y_MAX_POS + 0.001); } - inline bool position_is_reachable_by_probe_raw_xy( float raw_x, float raw_y ) { - // note to reviewer: this logic is copied from UBL_G29.cpp and does not contain the +/-0.0001 above - return WITHIN(raw_x, MIN_PROBE_X, MAX_PROBE_X) - && WITHIN(raw_y, MIN_PROBE_Y, MAX_PROBE_Y); + inline bool position_is_reachable_by_probe_raw_xy(const float &rx, const float &ry) { + // Add 0.001 margin to deal with float imprecision + return WITHIN(rx, MIN_PROBE_X - 0.001, MAX_PROBE_X + 0.001) + && WITHIN(ry, MIN_PROBE_Y - 0.001, MAX_PROBE_Y + 0.001); } #endif // CARTESIAN -inline bool position_is_reachable_by_probe_xy( float target_x, float target_y ) { - return position_is_reachable_by_probe_raw_xy( - RAW_X_POSITION( target_x ), - RAW_Y_POSITION( target_y )); +FORCE_INLINE bool position_is_reachable_by_probe_xy(const float &lx, const float &ly) { + return position_is_reachable_by_probe_raw_xy(RAW_X_POSITION(lx), RAW_Y_POSITION(ly)); } -inline bool position_is_reachable_xy( float target_x, float target_y ) { - return position_is_reachable_raw_xy( RAW_X_POSITION( target_x ), RAW_Y_POSITION( target_y )); +FORCE_INLINE bool position_is_reachable_xy(const float &lx, const float &ly) { + return position_is_reachable_raw_xy(RAW_X_POSITION(lx), RAW_Y_POSITION(ly)); } #endif //MARLIN_H diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 3caccf8d9..7e408edbe 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -1684,7 +1684,7 @@ void do_blocking_move_to(const float &x, const float &y, const float &z, const f #if ENABLED(DELTA) - if ( ! position_is_reachable_xy( x, y )) return; + if (!position_is_reachable_xy(x, y)) return; feedrate_mm_s = fr_mm_s ? fr_mm_s : XY_PROBE_FEEDRATE_MM_S; @@ -1740,7 +1740,7 @@ void do_blocking_move_to(const float &x, const float &y, const float &z, const f #elif IS_SCARA - if ( ! position_is_reachable_xy( x, y )) return; + if (!position_is_reachable_xy(x, y)) return; set_destination_to_current(); @@ -2366,7 +2366,7 @@ static void clean_up_after_endstop_or_probe_move() { } #endif - if ( ! position_is_reachable_by_probe_xy( x, y )) return NAN; + if (!position_is_reachable_by_probe_xy(x, y)) return NAN; const float old_feedrate_mm_s = feedrate_mm_s; @@ -3713,7 +3713,7 @@ inline void gcode_G7( destination[Y_AXIS] -= Y_PROBE_OFFSET_FROM_EXTRUDER; #endif - if ( position_is_reachable_xy( destination[X_AXIS], destination[Y_AXIS] )) { + if (position_is_reachable_xy(destination[X_AXIS], destination[Y_AXIS])) { #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) DEBUG_POS("Z_SAFE_HOMING", destination); @@ -4639,7 +4639,8 @@ void home_all_axes() { gcode_G28(true); } indexIntoAB[xCount][yCount] = abl_probe_index; #endif - if (position_is_reachable_xy( xProbe, yProbe )) break; + // Keep looping till a reachable point is found + if (position_is_reachable_xy(xProbe, yProbe)) break; ++abl_probe_index; } @@ -4750,7 +4751,7 @@ void home_all_axes() { gcode_G28(true); } #if IS_KINEMATIC // Avoid probing outside the round or hexagonal area - if (!position_is_reachable_by_probe_xy( xProbe, yProbe )) continue; + if (!position_is_reachable_by_probe_xy(xProbe, yProbe)) continue; #endif measured_z = faux ? 0.001 * random(-100, 101) : probe_pt(xProbe, yProbe, stow_probe_after_each, verbose_level); @@ -5055,7 +5056,7 @@ void home_all_axes() { gcode_G28(true); } const float xpos = code_seen('X') ? code_value_linear_units() : current_position[X_AXIS] + X_PROBE_OFFSET_FROM_EXTRUDER, ypos = code_seen('Y') ? code_value_linear_units() : current_position[Y_AXIS] + Y_PROBE_OFFSET_FROM_EXTRUDER; - if (!position_is_reachable_by_probe_xy( xpos, ypos )) return; + if (!position_is_reachable_by_probe_xy(xpos, ypos)) return; // Disable leveling so the planner won't mess with us #if HAS_LEVELING @@ -6513,7 +6514,7 @@ inline void gcode_M42() { #else // If we have gone out too far, we can do a simple fix and scale the numbers // back in closer to the origin. - while ( ! position_is_reachable_by_probe_xy( X_current, Y_current )) { + while (!position_is_reachable_by_probe_xy(X_current, Y_current)) { X_current *= 0.8; Y_current *= 0.8; if (verbose_level > 3) { diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index b906a4760..b8b992baa 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -135,9 +135,9 @@ * a subsequent G or T leveling operation for backward compatibility. * * P1 Phase 1 Invalidate entire Mesh and continue with automatic generation of the Mesh data using - * the Z-Probe. Usually the probe can not reach all areas that the nozzle can reach. - * In Cartesian printers, mesh points within the X_OFFSET_FROM_EXTRUDER and Y_OFFSET_FROM_EXTRUDER - * area can not be automatically probed. For Delta printers the area in which DELTA_PROBEABLE_RADIUS + * the Z-Probe. Usually the probe can't reach all areas that the nozzle can reach. On + * Cartesian printers, points within the X_PROBE_OFFSET_FROM_EXTRUDER and Y_PROBE_OFFSET_FROM_EXTRUDER + * area cannot be automatically probed. For Delta printers the area in which DELTA_PROBEABLE_RADIUS * and DELTA_PRINTABLE_RADIUS do not overlap will not be automatically probed. * * These points will be handled in Phase 2 and Phase 3. If the Phase 1 command is given the @@ -186,20 +186,20 @@ * of the Mesh being built. * * P3 Phase 3 Fill the unpopulated regions of the Mesh with a fixed value. There are two different paths the - * user can go down. If the user specifies the value using the C parameter, the closest invalid - * mesh points to the nozzle will be filled. The user can specify a repeat count using the R + * user can go down. If the user specifies the value using the C parameter, the closest invalid + * mesh points to the nozzle will be filled. The user can specify a repeat count using the R * parameter with the C version of the command. * - * A second version of the fill command is available if no C constant is specified. Not - * specifying a C constant will invoke the 'Smart Fill' algorithm. The G29 P3 command will search - * from the edges of the mesh inward looking for invalid mesh points. It will look at the next - * several mesh points to determine if the print bed is sloped up or down. If the bed is sloped + * A second version of the fill command is available if no C constant is specified. Not + * specifying a C constant will invoke the 'Smart Fill' algorithm. The G29 P3 command will search + * from the edges of the mesh inward looking for invalid mesh points. It will look at the next + * several mesh points to determine if the print bed is sloped up or down. If the bed is sloped * upward from the invalid mesh point, it will be replaced with the value of the nearest mesh point. * If the bed is sloped downward from the invalid mesh point, it will be replaced with a value that - * puts all three points in a line. The second version of the G29 P3 command is a quick, easy and + * puts all three points in a line. The second version of the G29 P3 command is a quick, easy and * usually safe way to populate the unprobed regions of your mesh so you can continue to the G26 - * Mesh Validation Pattern phase. Please note that you are populating your mesh with unverified - * numbers. You should use some scrutiny and caution. + * Mesh Validation Pattern phase. Please note that you are populating your mesh with unverified + * numbers. You should use some scrutiny and caution. * * P4 Phase 4 Fine tune the Mesh. The Delta Mesh Compensation System assume the existence of * an LCD Panel. It is possible to fine tune the mesh without the use of an LCD Panel. @@ -242,7 +242,7 @@ * command is not anticipated to be of much value to the typical user. It is intended * for developers to help them verify correct operation of the Unified Bed Leveling System. * - * R # Repeat Repeat this command the specified number of times. If no number is specified the + * R # Repeat Repeat this command the specified number of times. If no number is specified the * command will be repeated GRID_MAX_POINTS_X * GRID_MAX_POINTS_Y times. * * S Store Store the current Mesh in the Activated area of the EEPROM. It will also store the @@ -497,7 +497,7 @@ if (code_seen('H') && code_has_value()) height = code_value_float(); - if ( !position_is_reachable_xy( x_pos, y_pos )) { + if (!position_is_reachable_xy(x_pos, y_pos)) { SERIAL_PROTOCOLLNPGM("(X,Y) outside printable radius."); return; } @@ -635,7 +635,7 @@ ubl.display_map(code_has_value() ? code_value_int() : 0); /* - * This code may not be needed... Prepare for its removal... + * This code may not be needed... Prepare for its removal... * if (code_seen('Z')) { if (code_has_value()) @@ -660,9 +660,9 @@ do_blocking_move_to_z(measured_z); } while (!ubl_lcd_clicked()); - ubl.has_control_of_lcd_panel = true; // There is a race condition for the Encoder Wheel getting clicked. + ubl.has_control_of_lcd_panel = true; // There is a race condition for the encoder click. // It could get detected in lcd_mesh_edit (actually _lcd_mesh_fine_tune) - // or here. So, until we are done looking for a long Encoder Wheel Press, + // or here. So, until we are done looking for a long encoder press, // we need to take control of the panel KEEPALIVE_STATE(IN_HANDLER); @@ -1346,10 +1346,10 @@ my = pgm_read_float(&ubl.mesh_index_to_ypos[j]); // If using the probe as the reference there are some unreachable locations. - // Also for round beds, there are grid points outside the bed that nozzle can't reach. + // Also for round beds, there are grid points outside the bed the nozzle can't reach. // Prune them from the list and ignore them till the next Phase (manual nozzle probing). - if ( ! (probe_as_reference ? position_is_reachable_by_probe_raw_xy(mx, my) : position_is_reachable_raw_xy(mx, my)) ) + if (probe_as_reference ? !position_is_reachable_by_probe_raw_xy(mx, my) : !position_is_reachable_raw_xy(mx, my)) continue; // Reachable. Check if it's the closest location to the nozzle. @@ -1390,14 +1390,14 @@ } void fine_tune_mesh(const float &lx, const float &ly, const bool do_ubl_mesh_map) { - if (!code_seen('R')) // fine_tune_mesh() is special. If no repetion count flag is specified - repetition_cnt = 1; // we know to do exactly one mesh location. Otherwise we use what the parser decided. + if (!code_seen('R')) // fine_tune_mesh() is special. If no repetition count flag is specified + repetition_cnt = 1; // do exactly one mesh location. Otherwise use what the parser decided. mesh_index_pair location; uint16_t not_done[16]; int32_t round_off; - if ( ! position_is_reachable_xy( lx, ly )) { + if (!position_is_reachable_xy(lx, ly)) { SERIAL_PROTOCOLLNPGM("(X,Y) outside printable radius."); return; } @@ -1413,7 +1413,7 @@ do { location = find_closest_mesh_point_of_type(SET_IN_BITMAP, lx, ly, USE_NOZZLE_AS_REFERENCE, not_done, false); - if (location.x_index < 0 ) break; // stop when we can't find any more reachable points. + if (location.x_index < 0) break; // stop when we can't find any more reachable points. bit_clear(not_done, location.x_index, location.y_index); // Mark this location as 'adjusted' so we will find a // different location the next time through the loop @@ -1421,9 +1421,8 @@ const float rawx = pgm_read_float(&ubl.mesh_index_to_xpos[location.x_index]), rawy = pgm_read_float(&ubl.mesh_index_to_ypos[location.y_index]); - if ( ! position_is_reachable_raw_xy( rawx, rawy )) { // SHOULD NOT OCCUR because find_closest_mesh_point_of_type will only return reachable + if (!position_is_reachable_raw_xy(rawx, rawy)) // SHOULD NOT OCCUR because find_closest_mesh_point_of_type will only return reachable break; - } float new_z = ubl.z_values[location.x_index][location.y_index]; @@ -1432,8 +1431,7 @@ do_blocking_move_to_z(Z_CLEARANCE_DEPLOY_PROBE); // Move the nozzle to where we are going to edit do_blocking_move_to_xy(LOGICAL_X_POSITION(rawx), LOGICAL_Y_POSITION(rawy)); - round_off = (int32_t)(new_z * 1000.0); // we chop off the last digits just to be clean. We are rounding to the - new_z = float(round_off) / 1000.0; + new_z = floor(new_z * 1000.0) * 0.001; // Chop off digits after the 1000ths place KEEPALIVE_STATE(PAUSED_FOR_USER); ubl.has_control_of_lcd_panel = true; @@ -1451,9 +1449,9 @@ lcd_return_to_status(); - // There is a race condition for the Encoder Wheel getting clicked. - // It could get detected in lcd_mesh_edit (actually _lcd_mesh_fine_tune) - // or here. + // The technique used here generates a race condition for the encoder click. + // It could get detected in lcd_mesh_edit (actually _lcd_mesh_fine_tune) or here. + // Let's work on specifying a proper API for the LCD ASAP, OK? ubl.has_control_of_lcd_panel = true; } @@ -1478,7 +1476,7 @@ lcd_implementation_clear(); - } while (( location.x_index >= 0 ) && (--repetition_cnt>0)); + } while (location.x_index >= 0 && --repetition_cnt > 0); FINE_TUNE_EXIT: From 49599caadeaa12c24b7358959bf23c6ab45d7383 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 21 May 2017 05:58:03 -0500 Subject: [PATCH 119/189] General cleanup to utf_mapper.h --- Marlin/utf_mapper.h | 24 ++++++++++++------------ 1 file changed, 12 insertions(+), 12 deletions(-) diff --git a/Marlin/utf_mapper.h b/Marlin/utf_mapper.h index ebaaaf085..4b7975a10 100644 --- a/Marlin/utf_mapper.h +++ b/Marlin/utf_mapper.h @@ -150,8 +150,8 @@ static uint8_t utf_hi_char; // UTF-8 high part static bool seen_c2 = false; uint8_t d = c; - if ( d >= 0x80u ) { // UTF-8 handling - if ( (d >= 0xC0u) && (!seen_c2) ) { + if (d >= 0x80u) { // UTF-8 handling + if (d >= 0xC0u && !seen_c2) { utf_hi_char = d - 0xC2u; seen_c2 = true; return 0; @@ -185,10 +185,10 @@ seen_c4 = false, seen_c5 = false; uint8_t d = c; - if ( d >= 0x80u ) { // UTF-8 handling - if ( d == 0xC4u ) {seen_c4 = true; return 0;} - else if ( d == 0xC5u ) {seen_c5 = true; return 0;} - else if ( (d >= 0xC0u) && (!seen_c2) ) { + if (d >= 0x80u) { // UTF-8 handling + if (d == 0xC4u) { seen_c4 = true; return 0; } + else if (d == 0xC5u) { seen_c5 = true; return 0; } + else if (d >= 0xC0u && !seen_c2) { utf_hi_char = d - 0xC2u; seen_c2 = true; return 0; @@ -236,8 +236,8 @@ static uint8_t utf_hi_char; // UTF-8 high part static bool seen_ce = false; uint8_t d = c; - if ( d >= 0x80 ) { // UTF-8 handling - if ( (d >= 0xC0) && (!seen_ce) ) { + if (d >= 0x80) { // UTF-8 handling + if (d >= 0xC0 && !seen_ce) { utf_hi_char = d - 0xCE; seen_ce = true; return 0; @@ -424,10 +424,10 @@ seen_c4 = false, seen_c5 = false; uint8_t d = c; - if ( d >= 0x80u ) { // UTF-8 handling - if ( d == 0xC4u ) {seen_c4 = true; return 0;} - else if ( d == 0xC5u ) {seen_c5 = true; return 0;} - else if ( d == 0xC3u ) {seen_c3 = true; return 0;} + if (d >= 0x80u) { // UTF-8 handling + if (d == 0xC4u) { seen_c4 = true; return 0; } + else if (d == 0xC5u) { seen_c5 = true; return 0; } + else if (d == 0xC3u) { seen_c3 = true; return 0; } else if (seen_c4) { switch(d) { case 0x84u ... 0x87u: d -= 4; break; //Ą - ć From 1519b0e7c1474dfac9c192705f8b8af7fa2456b9 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 21 May 2017 09:42:39 -0500 Subject: [PATCH 120/189] Split up fastio.h, document pin mappings --- Marlin/fastio.h | 3945 +------------------------------- Marlin/fastio_1280.h | 1115 +++++++++ Marlin/fastio_1281.h | 720 ++++++ Marlin/fastio_168.h | 362 +++ Marlin/fastio_644.h | 531 +++++ Marlin/fastio_AT90USB-Marlin.h | 681 ++++++ Marlin/fastio_AT90USB-Teensy.h | 683 ++++++ 7 files changed, 4119 insertions(+), 3918 deletions(-) create mode 100644 Marlin/fastio_1280.h create mode 100644 Marlin/fastio_1281.h create mode 100644 Marlin/fastio_168.h create mode 100644 Marlin/fastio_644.h create mode 100644 Marlin/fastio_AT90USB-Marlin.h create mode 100644 Marlin/fastio_AT90USB-Teensy.h diff --git a/Marlin/fastio.h b/Marlin/fastio.h index dd7d0012e..62daa409d 100644 --- a/Marlin/fastio.h +++ b/Marlin/fastio.h @@ -30,6 +30,33 @@ #include +/** + * Include Ports and Functions + */ + +/** + * Enable this option to use Teensy++ 2.0 assignments for AT90USB processors. + */ +//#define AT90USBxx_TEENSYPP_ASSIGNMENTS + +#if defined(__AVR_ATmega168__) || defined(__AVR_ATmega328__) || defined(__AVR_ATmega328P__) + #include "fastio_168.h" +#elif defined(__AVR_ATmega644__) || defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644PA__) || defined(__AVR_ATmega1284P__) + #include "fastio_644.h" +#elif defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) + #include "fastio_1280.h" +#elif defined(__AVR_AT90USB1287__) || defined(__AVR_AT90USB1286__) || defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB647__) + #ifdef AT90USBxx_TEENSYPP_ASSIGNMENTS + #include "fastio_AT90USB-Teensy.h" + #else + #include "fastio_AT90USB-Marlin.h" + #endif +#elif defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__) + #include "fastio_1281.h" +#else + #error "Pins for this chip not defined in Arduino.h! If you have a working pins definition, please contribute!" +#endif + #ifndef _BV #define _BV(PIN) (1 << PIN) #endif @@ -209,3922 +236,4 @@ typedef enum { #define SET_FOCB(T,V) SET_FOC(T,B,V) #define SET_FOCC(T,V) SET_FOC(T,C,V) -/** - * Ports and Functions - */ - -#if defined(__AVR_ATmega168__) || defined(__AVR_ATmega328__) || defined(__AVR_ATmega328P__) - // UART - #define RXD DIO0 - #define TXD DIO1 - - // SPI - #define SCK DIO13 - #define MISO DIO12 - #define MOSI DIO11 - #define SS DIO10 - - // TWI (I2C) - #define SCL AIO5 - #define SDA AIO4 - - // timers and PWM - #define OC0A DIO6 - #define OC0B DIO5 - #define OC1A DIO9 - #define OC1B DIO10 - #define OC2A DIO11 - #define OC2B DIO3 - - #define DEBUG_LED AIO5 - - /** - * Pins Info - */ - - #define DIO0_PIN PIND0 - #define DIO0_RPORT PIND - #define DIO0_WPORT PORTD - #define DIO0_DDR DDRD - #define DIO0_PWM NULL - - #define DIO1_PIN PIND1 - #define DIO1_RPORT PIND - #define DIO1_WPORT PORTD - #define DIO1_DDR DDRD - #define DIO1_PWM NULL - - #define DIO2_PIN PIND2 - #define DIO2_RPORT PIND - #define DIO2_WPORT PORTD - #define DIO2_DDR DDRD - #define DIO2_PWM NULL - - #define DIO3_PIN PIND3 - #define DIO3_RPORT PIND - #define DIO3_WPORT PORTD - #define DIO3_DDR DDRD - #define DIO3_PWM &OCR2B - - #define DIO4_PIN PIND4 - #define DIO4_RPORT PIND - #define DIO4_WPORT PORTD - #define DIO4_DDR DDRD - #define DIO4_PWM NULL - - #define DIO5_PIN PIND5 - #define DIO5_RPORT PIND - #define DIO5_WPORT PORTD - #define DIO5_DDR DDRD - #define DIO5_PWM &OCR0B - - #define DIO6_PIN PIND6 - #define DIO6_RPORT PIND - #define DIO6_WPORT PORTD - #define DIO6_DDR DDRD - #define DIO6_PWM &OCR0A - - #define DIO7_PIN PIND7 - #define DIO7_RPORT PIND - #define DIO7_WPORT PORTD - #define DIO7_DDR DDRD - #define DIO7_PWM NULL - - #define DIO8_PIN PINB0 - #define DIO8_RPORT PINB - #define DIO8_WPORT PORTB - #define DIO8_DDR DDRB - #define DIO8_PWM NULL - - #define DIO9_PIN PINB1 - #define DIO9_RPORT PINB - #define DIO9_WPORT PORTB - #define DIO9_DDR DDRB - #define DIO9_PWM NULL - - #define DIO10_PIN PINB2 - #define DIO10_RPORT PINB - #define DIO10_WPORT PORTB - #define DIO10_DDR DDRB - #define DIO10_PWM NULL - - #define DIO11_PIN PINB3 - #define DIO11_RPORT PINB - #define DIO11_WPORT PORTB - #define DIO11_DDR DDRB - #define DIO11_PWM &OCR2A - - #define DIO12_PIN PINB4 - #define DIO12_RPORT PINB - #define DIO12_WPORT PORTB - #define DIO12_DDR DDRB - #define DIO12_PWM NULL - - #define DIO13_PIN PINB5 - #define DIO13_RPORT PINB - #define DIO13_WPORT PORTB - #define DIO13_DDR DDRB - #define DIO13_PWM NULL - - - #define DIO14_PIN PINC0 - #define DIO14_RPORT PINC - #define DIO14_WPORT PORTC - #define DIO14_DDR DDRC - #define DIO14_PWM NULL - - #define DIO15_PIN PINC1 - #define DIO15_RPORT PINC - #define DIO15_WPORT PORTC - #define DIO15_DDR DDRC - #define DIO15_PWM NULL - - #define DIO16_PIN PINC2 - #define DIO16_RPORT PINC - #define DIO16_WPORT PORTC - #define DIO16_DDR DDRC - #define DIO16_PWM NULL - - #define DIO17_PIN PINC3 - #define DIO17_RPORT PINC - #define DIO17_WPORT PORTC - #define DIO17_DDR DDRC - #define DIO17_PWM NULL - - #define DIO18_PIN PINC4 - #define DIO18_RPORT PINC - #define DIO18_WPORT PORTC - #define DIO18_DDR DDRC - #define DIO18_PWM NULL - - #define DIO19_PIN PINC5 - #define DIO19_RPORT PINC - #define DIO19_WPORT PORTC - #define DIO19_DDR DDRC - #define DIO19_PWM NULL - - #define DIO20_PIN PINC6 - #define DIO20_RPORT PINC - #define DIO20_WPORT PORTC - #define DIO20_DDR DDRC - #define DIO20_PWM NULL - - #define DIO21_PIN PINC7 - #define DIO21_RPORT PINC - #define DIO21_WPORT PORTC - #define DIO21_DDR DDRC - #define DIO21_PWM NULL - - #undef PB0 - #define PB0_PIN PINB0 - #define PB0_RPORT PINB - #define PB0_WPORT PORTB - #define PB0_DDR DDRB - #define PB0_PWM NULL - - #undef PB1 - #define PB1_PIN PINB1 - #define PB1_RPORT PINB - #define PB1_WPORT PORTB - #define PB1_DDR DDRB - #define PB1_PWM NULL - - #undef PB2 - #define PB2_PIN PINB2 - #define PB2_RPORT PINB - #define PB2_WPORT PORTB - #define PB2_DDR DDRB - #define PB2_PWM NULL - - #undef PB3 - #define PB3_PIN PINB3 - #define PB3_RPORT PINB - #define PB3_WPORT PORTB - #define PB3_DDR DDRB - #define PB3_PWM &OCR2A - - #undef PB4 - #define PB4_PIN PINB4 - #define PB4_RPORT PINB - #define PB4_WPORT PORTB - #define PB4_DDR DDRB - #define PB4_PWM NULL - - #undef PB5 - #define PB5_PIN PINB5 - #define PB5_RPORT PINB - #define PB5_WPORT PORTB - #define PB5_DDR DDRB - #define PB5_PWM NULL - - #undef PB6 - #define PB6_PIN PINB6 - #define PB6_RPORT PINB - #define PB6_WPORT PORTB - #define PB6_DDR DDRB - #define PB6_PWM NULL - - #undef PB7 - #define PB7_PIN PINB7 - #define PB7_RPORT PINB - #define PB7_WPORT PORTB - #define PB7_DDR DDRB - #define PB7_PWM NULL - - - #undef PC0 - #define PC0_PIN PINC0 - #define PC0_RPORT PINC - #define PC0_WPORT PORTC - #define PC0_DDR DDRC - #define PC0_PWM NULL - - #undef PC1 - #define PC1_PIN PINC1 - #define PC1_RPORT PINC - #define PC1_WPORT PORTC - #define PC1_DDR DDRC - #define PC1_PWM NULL - - #undef PC2 - #define PC2_PIN PINC2 - #define PC2_RPORT PINC - #define PC2_WPORT PORTC - #define PC2_DDR DDRC - #define PC2_PWM NULL - - #undef PC3 - #define PC3_PIN PINC3 - #define PC3_RPORT PINC - #define PC3_WPORT PORTC - #define PC3_DDR DDRC - #define PC3_PWM NULL - - #undef PC4 - #define PC4_PIN PINC4 - #define PC4_RPORT PINC - #define PC4_WPORT PORTC - #define PC4_DDR DDRC - #define PC4_PWM NULL - - #undef PC5 - #define PC5_PIN PINC5 - #define PC5_RPORT PINC - #define PC5_WPORT PORTC - #define PC5_DDR DDRC - #define PC5_PWM NULL - - #undef PC6 - #define PC6_PIN PINC6 - #define PC6_RPORT PINC - #define PC6_WPORT PORTC - #define PC6_DDR DDRC - #define PC6_PWM NULL - - #undef PC7 - #define PC7_PIN PINC7 - #define PC7_RPORT PINC - #define PC7_WPORT PORTC - #define PC7_DDR DDRC - #define PC7_PWM NULL - - - #undef PD0 - #define PD0_PIN PIND0 - #define PD0_RPORT PIND - #define PD0_WPORT PORTD - #define PD0_DDR DDRD - #define PD0_PWM NULL - - #undef PD1 - #define PD1_PIN PIND1 - #define PD1_RPORT PIND - #define PD1_WPORT PORTD - #define PD1_DDR DDRD - #define PD1_PWM NULL - - #undef PD2 - #define PD2_PIN PIND2 - #define PD2_RPORT PIND - #define PD2_WPORT PORTD - #define PD2_DDR DDRD - #define PD2_PWM NULL - - #undef PD3 - #define PD3_PIN PIND3 - #define PD3_RPORT PIND - #define PD3_WPORT PORTD - #define PD3_DDR DDRD - #define PD3_PWM &OCR2B - - #undef PD4 - #define PD4_PIN PIND4 - #define PD4_RPORT PIND - #define PD4_WPORT PORTD - #define PD4_DDR DDRD - #define PD4_PWM NULL - - #undef PD5 - #define PD5_PIN PIND5 - #define PD5_RPORT PIND - #define PD5_WPORT PORTD - #define PD5_DDR DDRD - #define PD5_PWM &OCR0B - - #undef PD6 - #define PD6_PIN PIND6 - #define PD6_RPORT PIND - #define PD6_WPORT PORTD - #define PD6_DDR DDRD - #define PD6_PWM &OCR0A - - #undef PD7 - #define PD7_PIN PIND7 - #define PD7_RPORT PIND - #define PD7_WPORT PORTD - #define PD7_DDR DDRD - #define PD7_PWM NULL -#endif // __AVR_ATmega(168|328|328P)__ - -#if defined(__AVR_ATmega644__) || defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644PA__) || defined(__AVR_ATmega1284P__) - // UART - #define RXD DIO8 - #define TXD DIO9 - #define RXD0 DIO8 - #define TXD0 DIO9 - - #define RXD1 DIO10 - #define TXD1 DIO11 - - // SPI - #define SCK DIO7 - #define MISO DIO6 - #define MOSI DIO5 - #define SS DIO4 - - // TWI (I2C) - #define SCL DIO16 - #define SDA DIO17 - - // timers and PWM - #define OC0A DIO3 - #define OC0B DIO4 - #define OC1A DIO13 - #define OC1B DIO12 - #define OC2A DIO15 - #define OC2B DIO14 - - #define DEBUG_LED DIO0 - - /** - * Pins Info - */ - - #define DIO0_PIN PINB0 - #define DIO0_RPORT PINB - #define DIO0_WPORT PORTB - #define DIO0_DDR DDRB - #define DIO0_PWM NULL - - #define DIO1_PIN PINB1 - #define DIO1_RPORT PINB - #define DIO1_WPORT PORTB - #define DIO1_DDR DDRB - #define DIO1_PWM NULL - - #define DIO2_PIN PINB2 - #define DIO2_RPORT PINB - #define DIO2_WPORT PORTB - #define DIO2_DDR DDRB - #define DIO2_PWM NULL - - #define DIO3_PIN PINB3 - #define DIO3_RPORT PINB - #define DIO3_WPORT PORTB - #define DIO3_DDR DDRB - #define DIO3_PWM OCR0A - - #define DIO4_PIN PINB4 - #define DIO4_RPORT PINB - #define DIO4_WPORT PORTB - #define DIO4_DDR DDRB - #define DIO4_PWM OCR0B - - #define DIO5_PIN PINB5 - #define DIO5_RPORT PINB - #define DIO5_WPORT PORTB - #define DIO5_DDR DDRB - #define DIO5_PWM NULL - - #define DIO6_PIN PINB6 - #define DIO6_RPORT PINB - #define DIO6_WPORT PORTB - #define DIO6_DDR DDRB - #define DIO6_PWM NULL - - #define DIO7_PIN PINB7 - #define DIO7_RPORT PINB - #define DIO7_WPORT PORTB - #define DIO7_DDR DDRB - #define DIO7_PWM NULL - - #define DIO8_PIN PIND0 - #define DIO8_RPORT PIND - #define DIO8_WPORT PORTD - #define DIO8_DDR DDRD - #define DIO8_PWM NULL - - #define DIO9_PIN PIND1 - #define DIO9_RPORT PIND - #define DIO9_WPORT PORTD - #define DIO9_DDR DDRD - #define DIO9_PWM NULL - - #define DIO10_PIN PIND2 - #define DIO10_RPORT PIND - #define DIO10_WPORT PORTD - #define DIO10_DDR DDRD - #define DIO10_PWM NULL - - #define DIO11_PIN PIND3 - #define DIO11_RPORT PIND - #define DIO11_WPORT PORTD - #define DIO11_DDR DDRD - #define DIO11_PWM NULL - - #define DIO12_PIN PIND4 - #define DIO12_RPORT PIND - #define DIO12_WPORT PORTD - #define DIO12_DDR DDRD - #define DIO12_PWM OCR1B - - #define DIO13_PIN PIND5 - #define DIO13_RPORT PIND - #define DIO13_WPORT PORTD - #define DIO13_DDR DDRD - #define DIO13_PWM OCR1A - - #define DIO14_PIN PIND6 - #define DIO14_RPORT PIND - #define DIO14_WPORT PORTD - #define DIO14_DDR DDRD - #define DIO14_PWM OCR2B - - #define DIO15_PIN PIND7 - #define DIO15_RPORT PIND - #define DIO15_WPORT PORTD - #define DIO15_DDR DDRD - #define DIO15_PWM OCR2A - - #define DIO16_PIN PINC0 - #define DIO16_RPORT PINC - #define DIO16_WPORT PORTC - #define DIO16_DDR DDRC - #define DIO16_PWM NULL - - #define DIO17_PIN PINC1 - #define DIO17_RPORT PINC - #define DIO17_WPORT PORTC - #define DIO17_DDR DDRC - #define DIO17_PWM NULL - - #define DIO18_PIN PINC2 - #define DIO18_RPORT PINC - #define DIO18_WPORT PORTC - #define DIO18_DDR DDRC - #define DIO18_PWM NULL - - #define DIO19_PIN PINC3 - #define DIO19_RPORT PINC - #define DIO19_WPORT PORTC - #define DIO19_DDR DDRC - #define DIO19_PWM NULL - - #define DIO20_PIN PINC4 - #define DIO20_RPORT PINC - #define DIO20_WPORT PORTC - #define DIO20_DDR DDRC - #define DIO20_PWM NULL - - #define DIO21_PIN PINC5 - #define DIO21_RPORT PINC - #define DIO21_WPORT PORTC - #define DIO21_DDR DDRC - #define DIO21_PWM NULL - - #define DIO22_PIN PINC6 - #define DIO22_RPORT PINC - #define DIO22_WPORT PORTC - #define DIO22_DDR DDRC - #define DIO22_PWM NULL - - #define DIO23_PIN PINC7 - #define DIO23_RPORT PINC - #define DIO23_WPORT PORTC - #define DIO23_DDR DDRC - #define DIO23_PWM NULL - - #define DIO24_PIN PINA7 - #define DIO24_RPORT PINA - #define DIO24_WPORT PORTA - #define DIO24_DDR DDRA - #define DIO24_PWM NULL - - #define DIO25_PIN PINA6 - #define DIO25_RPORT PINA - #define DIO25_WPORT PORTA - #define DIO25_DDR DDRA - #define DIO25_PWM NULL - - #define DIO26_PIN PINA5 - #define DIO26_RPORT PINA - #define DIO26_WPORT PORTA - #define DIO26_DDR DDRA - #define DIO26_PWM NULL - - #define DIO27_PIN PINA4 - #define DIO27_RPORT PINA - #define DIO27_WPORT PORTA - #define DIO27_DDR DDRA - #define DIO27_PWM NULL - - #define DIO28_PIN PINA3 - #define DIO28_RPORT PINA - #define DIO28_WPORT PORTA - #define DIO28_DDR DDRA - #define DIO28_PWM NULL - - #define DIO29_PIN PINA2 - #define DIO29_RPORT PINA - #define DIO29_WPORT PORTA - #define DIO29_DDR DDRA - #define DIO29_PWM NULL - - #define DIO30_PIN PINA1 - #define DIO30_RPORT PINA - #define DIO30_WPORT PORTA - #define DIO30_DDR DDRA - #define DIO30_PWM NULL - - #define DIO31_PIN PINA0 - #define DIO31_RPORT PINA - #define DIO31_WPORT PORTA - #define DIO31_DDR DDRA - #define DIO31_PWM NULL - - #define AIO0_PIN PINA0 - #define AIO0_RPORT PINA - #define AIO0_WPORT PORTA - #define AIO0_DDR DDRA - #define AIO0_PWM NULL - - #define AIO1_PIN PINA1 - #define AIO1_RPORT PINA - #define AIO1_WPORT PORTA - #define AIO1_DDR DDRA - #define AIO1_PWM NULL - - #define AIO2_PIN PINA2 - #define AIO2_RPORT PINA - #define AIO2_WPORT PORTA - #define AIO2_DDR DDRA - #define AIO2_PWM NULL - - #define AIO3_PIN PINA3 - #define AIO3_RPORT PINA - #define AIO3_WPORT PORTA - #define AIO3_DDR DDRA - #define AIO3_PWM NULL - - #define AIO4_PIN PINA4 - #define AIO4_RPORT PINA - #define AIO4_WPORT PORTA - #define AIO4_DDR DDRA - #define AIO4_PWM NULL - - #define AIO5_PIN PINA5 - #define AIO5_RPORT PINA - #define AIO5_WPORT PORTA - #define AIO5_DDR DDRA - #define AIO5_PWM NULL - - #define AIO6_PIN PINA6 - #define AIO6_RPORT PINA - #define AIO6_WPORT PORTA - #define AIO6_DDR DDRA - #define AIO6_PWM NULL - - #define AIO7_PIN PINA7 - #define AIO7_RPORT PINA - #define AIO7_WPORT PORTA - #define AIO7_DDR DDRA - #define AIO7_PWM NULL - - #undef PA0 - #define PA0_PIN PINA0 - #define PA0_RPORT PINA - #define PA0_WPORT PORTA - #define PA0_DDR DDRA - #define PA0_PWM NULL - - #undef PA1 - #define PA1_PIN PINA1 - #define PA1_RPORT PINA - #define PA1_WPORT PORTA - #define PA1_DDR DDRA - #define PA1_PWM NULL - - #undef PA2 - #define PA2_PIN PINA2 - #define PA2_RPORT PINA - #define PA2_WPORT PORTA - #define PA2_DDR DDRA - #define PA2_PWM NULL - - #undef PA3 - #define PA3_PIN PINA3 - #define PA3_RPORT PINA - #define PA3_WPORT PORTA - #define PA3_DDR DDRA - #define PA3_PWM NULL - - #undef PA4 - #define PA4_PIN PINA4 - #define PA4_RPORT PINA - #define PA4_WPORT PORTA - #define PA4_DDR DDRA - #define PA4_PWM NULL - - #undef PA5 - #define PA5_PIN PINA5 - #define PA5_RPORT PINA - #define PA5_WPORT PORTA - #define PA5_DDR DDRA - #define PA5_PWM NULL - - #undef PA6 - #define PA6_PIN PINA6 - #define PA6_RPORT PINA - #define PA6_WPORT PORTA - #define PA6_DDR DDRA - #define PA6_PWM NULL - - #undef PA7 - #define PA7_PIN PINA7 - #define PA7_RPORT PINA - #define PA7_WPORT PORTA - #define PA7_DDR DDRA - #define PA7_PWM NULL - - - #undef PB0 - #define PB0_PIN PINB0 - #define PB0_RPORT PINB - #define PB0_WPORT PORTB - #define PB0_DDR DDRB - #define PB0_PWM NULL - - #undef PB1 - #define PB1_PIN PINB1 - #define PB1_RPORT PINB - #define PB1_WPORT PORTB - #define PB1_DDR DDRB - #define PB1_PWM NULL - - #undef PB2 - #define PB2_PIN PINB2 - #define PB2_RPORT PINB - #define PB2_WPORT PORTB - #define PB2_DDR DDRB - #define PB2_PWM NULL - - #undef PB3 - #define PB3_PIN PINB3 - #define PB3_RPORT PINB - #define PB3_WPORT PORTB - #define PB3_DDR DDRB - #define PB3_PWM OCR0A - - #undef PB4 - #define PB4_PIN PINB4 - #define PB4_RPORT PINB - #define PB4_WPORT PORTB - #define PB4_DDR DDRB - #define PB4_PWM OCR0B - - #undef PB5 - #define PB5_PIN PINB5 - #define PB5_RPORT PINB - #define PB5_WPORT PORTB - #define PB5_DDR DDRB - #define PB5_PWM NULL - - #undef PB6 - #define PB6_PIN PINB6 - #define PB6_RPORT PINB - #define PB6_WPORT PORTB - #define PB6_DDR DDRB - #define PB6_PWM NULL - - #undef PB7 - #define PB7_PIN PINB7 - #define PB7_RPORT PINB - #define PB7_WPORT PORTB - #define PB7_DDR DDRB - #define PB7_PWM NULL - - - #undef PC0 - #define PC0_PIN PINC0 - #define PC0_RPORT PINC - #define PC0_WPORT PORTC - #define PC0_DDR DDRC - #define PC0_PWM NULL - - #undef PC1 - #define PC1_PIN PINC1 - #define PC1_RPORT PINC - #define PC1_WPORT PORTC - #define PC1_DDR DDRC - #define PC1_PWM NULL - - #undef PC2 - #define PC2_PIN PINC2 - #define PC2_RPORT PINC - #define PC2_WPORT PORTC - #define PC2_DDR DDRC - #define PC2_PWM NULL - - #undef PC3 - #define PC3_PIN PINC3 - #define PC3_RPORT PINC - #define PC3_WPORT PORTC - #define PC3_DDR DDRC - #define PC3_PWM NULL - - #undef PC4 - #define PC4_PIN PINC4 - #define PC4_RPORT PINC - #define PC4_WPORT PORTC - #define PC4_DDR DDRC - #define PC4_PWM NULL - - #undef PC5 - #define PC5_PIN PINC5 - #define PC5_RPORT PINC - #define PC5_WPORT PORTC - #define PC5_DDR DDRC - #define PC5_PWM NULL - - #undef PC6 - #define PC6_PIN PINC6 - #define PC6_RPORT PINC - #define PC6_WPORT PORTC - #define PC6_DDR DDRC - #define PC6_PWM NULL - - #undef PC7 - #define PC7_PIN PINC7 - #define PC7_RPORT PINC - #define PC7_WPORT PORTC - #define PC7_DDR DDRC - #define PC7_PWM NULL - - - #undef PD0 - #define PD0_PIN PIND0 - #define PD0_RPORT PIND - #define PD0_WPORT PORTD - #define PD0_DDR DDRD - #define PD0_PWM NULL - - #undef PD1 - #define PD1_PIN PIND1 - #define PD1_RPORT PIND - #define PD1_WPORT PORTD - #define PD1_DDR DDRD - #define PD1_PWM NULL - - #undef PD2 - #define PD2_PIN PIND2 - #define PD2_RPORT PIND - #define PD2_WPORT PORTD - #define PD2_DDR DDRD - #define PD2_PWM NULL - - #undef PD3 - #define PD3_PIN PIND3 - #define PD3_RPORT PIND - #define PD3_WPORT PORTD - #define PD3_DDR DDRD - #define PD3_PWM NULL - - #undef PD4 - #define PD4_PIN PIND4 - #define PD4_RPORT PIND - #define PD4_WPORT PORTD - #define PD4_DDR DDRD - #define PD4_PWM NULL - - #undef PD5 - #define PD5_PIN PIND5 - #define PD5_RPORT PIND - #define PD5_WPORT PORTD - #define PD5_DDR DDRD - #define PD5_PWM NULL - - #undef PD6 - #define PD6_PIN PIND6 - #define PD6_RPORT PIND - #define PD6_WPORT PORTD - #define PD6_DDR DDRD - #define PD6_PWM OCR2B - - #undef PD7 - #define PD7_PIN PIND7 - #define PD7_RPORT PIND - #define PD7_WPORT PORTD - #define PD7_DDR DDRD - #define PD7_PWM OCR2A -#endif // __AVR_ATmega(644|644P|644PA)__ - -#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) - // UART - #define RXD DIO0 - #define TXD DIO1 - - // SPI - #define SCK DIO52 - #define MISO DIO50 - #define MOSI DIO51 - #define SS DIO53 - - // TWI (I2C) - #define SCL DIO21 - #define SDA DIO20 - - // timers and PWM - #define OC0A DIO13 - #define OC0B DIO4 - #define OC1A DIO11 - #define OC1B DIO12 - #define OC2A DIO10 - #define OC2B DIO9 - #define OC3A DIO5 - #define OC3B DIO2 - #define OC3C DIO3 - #define OC4A DIO6 - #define OC4B DIO7 - #define OC4C DIO8 - #define OC5A DIO46 - #define OC5B DIO45 - #define OC5C DIO44 - - // change for your board - #define DEBUG_LED DIO21 - - /** - * Pins Info - */ - - #define DIO0_PIN PINE0 - #define DIO0_RPORT PINE - #define DIO0_WPORT PORTE - #define DIO0_DDR DDRE - #define DIO0_PWM NULL - - #define DIO1_PIN PINE1 - #define DIO1_RPORT PINE - #define DIO1_WPORT PORTE - #define DIO1_DDR DDRE - #define DIO1_PWM NULL - - #define DIO2_PIN PINE4 - #define DIO2_RPORT PINE - #define DIO2_WPORT PORTE - #define DIO2_DDR DDRE - #define DIO2_PWM &OCR3BL - - #define DIO3_PIN PINE5 - #define DIO3_RPORT PINE - #define DIO3_WPORT PORTE - #define DIO3_DDR DDRE - #define DIO3_PWM &OCR3CL - - #define DIO4_PIN PING5 - #define DIO4_RPORT PING - #define DIO4_WPORT PORTG - #define DIO4_DDR DDRG - #define DIO4_PWM &OCR0B - - #define DIO5_PIN PINE3 - #define DIO5_RPORT PINE - #define DIO5_WPORT PORTE - #define DIO5_DDR DDRE - #define DIO5_PWM &OCR3AL - - #define DIO6_PIN PINH3 - #define DIO6_RPORT PINH - #define DIO6_WPORT PORTH - #define DIO6_DDR DDRH - #define DIO6_PWM &OCR4AL - - #define DIO7_PIN PINH4 - #define DIO7_RPORT PINH - #define DIO7_WPORT PORTH - #define DIO7_DDR DDRH - #define DIO7_PWM &OCR4BL - - #define DIO8_PIN PINH5 - #define DIO8_RPORT PINH - #define DIO8_WPORT PORTH - #define DIO8_DDR DDRH - #define DIO8_PWM &OCR4CL - - #define DIO9_PIN PINH6 - #define DIO9_RPORT PINH - #define DIO9_WPORT PORTH - #define DIO9_DDR DDRH - #define DIO9_PWM &OCR2B - - #define DIO10_PIN PINB4 - #define DIO10_RPORT PINB - #define DIO10_WPORT PORTB - #define DIO10_DDR DDRB - #define DIO10_PWM &OCR2A - - #define DIO11_PIN PINB5 - #define DIO11_RPORT PINB - #define DIO11_WPORT PORTB - #define DIO11_DDR DDRB - #define DIO11_PWM NULL - - #define DIO12_PIN PINB6 - #define DIO12_RPORT PINB - #define DIO12_WPORT PORTB - #define DIO12_DDR DDRB - #define DIO12_PWM NULL - - #define DIO13_PIN PINB7 - #define DIO13_RPORT PINB - #define DIO13_WPORT PORTB - #define DIO13_DDR DDRB - #define DIO13_PWM &OCR0A - - #define DIO14_PIN PINJ1 - #define DIO14_RPORT PINJ - #define DIO14_WPORT PORTJ - #define DIO14_DDR DDRJ - #define DIO14_PWM NULL - - #define DIO15_PIN PINJ0 - #define DIO15_RPORT PINJ - #define DIO15_WPORT PORTJ - #define DIO15_DDR DDRJ - #define DIO15_PWM NULL - - #define DIO16_PIN PINH1 - #define DIO16_RPORT PINH - #define DIO16_WPORT PORTH - #define DIO16_DDR DDRH - #define DIO16_PWM NULL - - #define DIO17_PIN PINH0 - #define DIO17_RPORT PINH - #define DIO17_WPORT PORTH - #define DIO17_DDR DDRH - #define DIO17_PWM NULL - - #define DIO18_PIN PIND3 - #define DIO18_RPORT PIND - #define DIO18_WPORT PORTD - #define DIO18_DDR DDRD - #define DIO18_PWM NULL - - #define DIO19_PIN PIND2 - #define DIO19_RPORT PIND - #define DIO19_WPORT PORTD - #define DIO19_DDR DDRD - #define DIO19_PWM NULL - - #define DIO20_PIN PIND1 - #define DIO20_RPORT PIND - #define DIO20_WPORT PORTD - #define DIO20_DDR DDRD - #define DIO20_PWM NULL - - #define DIO21_PIN PIND0 - #define DIO21_RPORT PIND - #define DIO21_WPORT PORTD - #define DIO21_DDR DDRD - #define DIO21_PWM NULL - - #define DIO22_PIN PINA0 - #define DIO22_RPORT PINA - #define DIO22_WPORT PORTA - #define DIO22_DDR DDRA - #define DIO22_PWM NULL - - #define DIO23_PIN PINA1 - #define DIO23_RPORT PINA - #define DIO23_WPORT PORTA - #define DIO23_DDR DDRA - #define DIO23_PWM NULL - - #define DIO24_PIN PINA2 - #define DIO24_RPORT PINA - #define DIO24_WPORT PORTA - #define DIO24_DDR DDRA - #define DIO24_PWM NULL - - #define DIO25_PIN PINA3 - #define DIO25_RPORT PINA - #define DIO25_WPORT PORTA - #define DIO25_DDR DDRA - #define DIO25_PWM NULL - - #define DIO26_PIN PINA4 - #define DIO26_RPORT PINA - #define DIO26_WPORT PORTA - #define DIO26_DDR DDRA - #define DIO26_PWM NULL - - #define DIO27_PIN PINA5 - #define DIO27_RPORT PINA - #define DIO27_WPORT PORTA - #define DIO27_DDR DDRA - #define DIO27_PWM NULL - - #define DIO28_PIN PINA6 - #define DIO28_RPORT PINA - #define DIO28_WPORT PORTA - #define DIO28_DDR DDRA - #define DIO28_PWM NULL - - #define DIO29_PIN PINA7 - #define DIO29_RPORT PINA - #define DIO29_WPORT PORTA - #define DIO29_DDR DDRA - #define DIO29_PWM NULL - - #define DIO30_PIN PINC7 - #define DIO30_RPORT PINC - #define DIO30_WPORT PORTC - #define DIO30_DDR DDRC - #define DIO30_PWM NULL - - #define DIO31_PIN PINC6 - #define DIO31_RPORT PINC - #define DIO31_WPORT PORTC - #define DIO31_DDR DDRC - #define DIO31_PWM NULL - - #define DIO32_PIN PINC5 - #define DIO32_RPORT PINC - #define DIO32_WPORT PORTC - #define DIO32_DDR DDRC - #define DIO32_PWM NULL - - #define DIO33_PIN PINC4 - #define DIO33_RPORT PINC - #define DIO33_WPORT PORTC - #define DIO33_DDR DDRC - #define DIO33_PWM NULL - - #define DIO34_PIN PINC3 - #define DIO34_RPORT PINC - #define DIO34_WPORT PORTC - #define DIO34_DDR DDRC - #define DIO34_PWM NULL - - #define DIO35_PIN PINC2 - #define DIO35_RPORT PINC - #define DIO35_WPORT PORTC - #define DIO35_DDR DDRC - #define DIO35_PWM NULL - - #define DIO36_PIN PINC1 - #define DIO36_RPORT PINC - #define DIO36_WPORT PORTC - #define DIO36_DDR DDRC - #define DIO36_PWM NULL - - #define DIO37_PIN PINC0 - #define DIO37_RPORT PINC - #define DIO37_WPORT PORTC - #define DIO37_DDR DDRC - #define DIO37_PWM NULL - - #define DIO38_PIN PIND7 - #define DIO38_RPORT PIND - #define DIO38_WPORT PORTD - #define DIO38_DDR DDRD - #define DIO38_PWM NULL - - #define DIO39_PIN PING2 - #define DIO39_RPORT PING - #define DIO39_WPORT PORTG - #define DIO39_DDR DDRG - #define DIO39_PWM NULL - - #define DIO40_PIN PING1 - #define DIO40_RPORT PING - #define DIO40_WPORT PORTG - #define DIO40_DDR DDRG - #define DIO40_PWM NULL - - #define DIO41_PIN PING0 - #define DIO41_RPORT PING - #define DIO41_WPORT PORTG - #define DIO41_DDR DDRG - #define DIO41_PWM NULL - - #define DIO42_PIN PINL7 - #define DIO42_RPORT PINL - #define DIO42_WPORT PORTL - #define DIO42_DDR DDRL - #define DIO42_PWM NULL - - #define DIO43_PIN PINL6 - #define DIO43_RPORT PINL - #define DIO43_WPORT PORTL - #define DIO43_DDR DDRL - #define DIO43_PWM NULL - - #define DIO44_PIN PINL5 - #define DIO44_RPORT PINL - #define DIO44_WPORT PORTL - #define DIO44_DDR DDRL - #define DIO44_PWM &OCR5CL - - #define DIO45_PIN PINL4 - #define DIO45_RPORT PINL - #define DIO45_WPORT PORTL - #define DIO45_DDR DDRL - #define DIO45_PWM &OCR5BL - - #define DIO46_PIN PINL3 - #define DIO46_RPORT PINL - #define DIO46_WPORT PORTL - #define DIO46_DDR DDRL - #define DIO46_PWM &OCR5AL - - #define DIO47_PIN PINL2 - #define DIO47_RPORT PINL - #define DIO47_WPORT PORTL - #define DIO47_DDR DDRL - #define DIO47_PWM NULL - - #define DIO48_PIN PINL1 - #define DIO48_RPORT PINL - #define DIO48_WPORT PORTL - #define DIO48_DDR DDRL - #define DIO48_PWM NULL - - #define DIO49_PIN PINL0 - #define DIO49_RPORT PINL - #define DIO49_WPORT PORTL - #define DIO49_DDR DDRL - #define DIO49_PWM NULL - - #define DIO50_PIN PINB3 - #define DIO50_RPORT PINB - #define DIO50_WPORT PORTB - #define DIO50_DDR DDRB - #define DIO50_PWM NULL - - #define DIO51_PIN PINB2 - #define DIO51_RPORT PINB - #define DIO51_WPORT PORTB - #define DIO51_DDR DDRB - #define DIO51_PWM NULL - - #define DIO52_PIN PINB1 - #define DIO52_RPORT PINB - #define DIO52_WPORT PORTB - #define DIO52_DDR DDRB - #define DIO52_PWM NULL - - #define DIO53_PIN PINB0 - #define DIO53_RPORT PINB - #define DIO53_WPORT PORTB - #define DIO53_DDR DDRB - #define DIO53_PWM NULL - - #define DIO54_PIN PINF0 - #define DIO54_RPORT PINF - #define DIO54_WPORT PORTF - #define DIO54_DDR DDRF - #define DIO54_PWM NULL - - #define DIO55_PIN PINF1 - #define DIO55_RPORT PINF - #define DIO55_WPORT PORTF - #define DIO55_DDR DDRF - #define DIO55_PWM NULL - - #define DIO56_PIN PINF2 - #define DIO56_RPORT PINF - #define DIO56_WPORT PORTF - #define DIO56_DDR DDRF - #define DIO56_PWM NULL - - #define DIO57_PIN PINF3 - #define DIO57_RPORT PINF - #define DIO57_WPORT PORTF - #define DIO57_DDR DDRF - #define DIO57_PWM NULL - - #define DIO58_PIN PINF4 - #define DIO58_RPORT PINF - #define DIO58_WPORT PORTF - #define DIO58_DDR DDRF - #define DIO58_PWM NULL - - #define DIO59_PIN PINF5 - #define DIO59_RPORT PINF - #define DIO59_WPORT PORTF - #define DIO59_DDR DDRF - #define DIO59_PWM NULL - - #define DIO60_PIN PINF6 - #define DIO60_RPORT PINF - #define DIO60_WPORT PORTF - #define DIO60_DDR DDRF - #define DIO60_PWM NULL - - #define DIO61_PIN PINF7 - #define DIO61_RPORT PINF - #define DIO61_WPORT PORTF - #define DIO61_DDR DDRF - #define DIO61_PWM NULL - - #define DIO62_PIN PINK0 - #define DIO62_RPORT PINK - #define DIO62_WPORT PORTK - #define DIO62_DDR DDRK - #define DIO62_PWM NULL - - #define DIO63_PIN PINK1 - #define DIO63_RPORT PINK - #define DIO63_WPORT PORTK - #define DIO63_DDR DDRK - #define DIO63_PWM NULL - - #define DIO64_PIN PINK2 - #define DIO64_RPORT PINK - #define DIO64_WPORT PORTK - #define DIO64_DDR DDRK - #define DIO64_PWM NULL - - #define DIO65_PIN PINK3 - #define DIO65_RPORT PINK - #define DIO65_WPORT PORTK - #define DIO65_DDR DDRK - #define DIO65_PWM NULL - - #define DIO66_PIN PINK4 - #define DIO66_RPORT PINK - #define DIO66_WPORT PORTK - #define DIO66_DDR DDRK - #define DIO66_PWM NULL - - #define DIO67_PIN PINK5 - #define DIO67_RPORT PINK - #define DIO67_WPORT PORTK - #define DIO67_DDR DDRK - #define DIO67_PWM NULL - - #define DIO68_PIN PINK6 - #define DIO68_RPORT PINK - #define DIO68_WPORT PORTK - #define DIO68_DDR DDRK - #define DIO68_PWM NULL - - #define DIO69_PIN PINK7 - #define DIO69_RPORT PINK - #define DIO69_WPORT PORTK - #define DIO69_DDR DDRK - #define DIO69_PWM NULL - - #define DIO70_PIN PING4 - #define DIO70_RPORT PING - #define DIO70_WPORT PORTG - #define DIO70_DDR DDRG - #define DIO70_PWM NULL - - #define DIO71_PIN PING3 - #define DIO71_RPORT PING - #define DIO71_WPORT PORTG - #define DIO71_DDR DDRG - #define DIO71_PWM NULL - - #define DIO72_PIN PINJ2 - #define DIO72_RPORT PINJ - #define DIO72_WPORT PORTJ - #define DIO72_DDR DDRJ - #define DIO72_PWM NULL - - #define DIO73_PIN PINJ3 - #define DIO73_RPORT PINJ - #define DIO73_WPORT PORTJ - #define DIO73_DDR DDRJ - #define DIO73_PWM NULL - - #define DIO74_PIN PINJ7 - #define DIO74_RPORT PINJ - #define DIO74_WPORT PORTJ - #define DIO74_DDR DDRJ - #define DIO74_PWM NULL - - #define DIO75_PIN PINJ4 - #define DIO75_RPORT PINJ - #define DIO75_WPORT PORTJ - #define DIO75_DDR DDRJ - #define DIO75_PWM NULL - - #define DIO76_PIN PINJ5 - #define DIO76_RPORT PINJ - #define DIO76_WPORT PORTJ - #define DIO76_DDR DDRJ - #define DIO76_PWM NULL - - #define DIO77_PIN PINJ6 - #define DIO77_RPORT PINJ - #define DIO77_WPORT PORTJ - #define DIO77_DDR DDRJ - #define DIO77_PWM NULL - - #define DIO78_PIN PINE2 - #define DIO78_RPORT PINE - #define DIO78_WPORT PORTE - #define DIO78_DDR DDRE - #define DIO78_PWM NULL - - #define DIO79_PIN PINE6 - #define DIO79_RPORT PINE - #define DIO79_WPORT PORTE - #define DIO79_DDR DDRE - #define DIO79_PWM NULL - - #define DIO80_PIN PINE7 - #define DIO80_RPORT PINE - #define DIO80_WPORT PORTE - #define DIO80_DDR DDRE - #define DIO80_PWM NULL - - #define DIO81_PIN PIND4 - #define DIO81_RPORT PIND - #define DIO81_WPORT PORTD - #define DIO81_DDR DDRD - #define DIO81_PWM NULL - - #define DIO82_PIN PIND5 - #define DIO82_RPORT PIND - #define DIO82_WPORT PORTD - #define DIO82_DDR DDRD - #define DIO82_PWM NULL - - #define DIO83_PIN PIND6 - #define DIO83_RPORT PIND - #define DIO83_WPORT PORTD - #define DIO83_DDR DDRD - #define DIO83_PWM NULL - - #define DIO84_PIN PINH2 - #define DIO84_RPORT PINH - #define DIO84_WPORT PORTH - #define DIO84_DDR DDRH - #define DIO84_PWM NULL - - #define DIO85_PIN PINH7 - #define DIO85_RPORT PINH - #define DIO85_WPORT PORTH - #define DIO85_DDR DDRH - #define DIO85_PWM NULL - - #undef PA0 - #define PA0_PIN PINA0 - #define PA0_RPORT PINA - #define PA0_WPORT PORTA - #define PA0_DDR DDRA - #define PA0_PWM NULL - #undef PA1 - #define PA1_PIN PINA1 - #define PA1_RPORT PINA - #define PA1_WPORT PORTA - #define PA1_DDR DDRA - #define PA1_PWM NULL - #undef PA2 - #define PA2_PIN PINA2 - #define PA2_RPORT PINA - #define PA2_WPORT PORTA - #define PA2_DDR DDRA - #define PA2_PWM NULL - #undef PA3 - #define PA3_PIN PINA3 - #define PA3_RPORT PINA - #define PA3_WPORT PORTA - #define PA3_DDR DDRA - #define PA3_PWM NULL - #undef PA4 - #define PA4_PIN PINA4 - #define PA4_RPORT PINA - #define PA4_WPORT PORTA - #define PA4_DDR DDRA - #define PA4_PWM NULL - #undef PA5 - #define PA5_PIN PINA5 - #define PA5_RPORT PINA - #define PA5_WPORT PORTA - #define PA5_DDR DDRA - #define PA5_PWM NULL - #undef PA6 - #define PA6_PIN PINA6 - #define PA6_RPORT PINA - #define PA6_WPORT PORTA - #define PA6_DDR DDRA - #define PA6_PWM NULL - #undef PA7 - #define PA7_PIN PINA7 - #define PA7_RPORT PINA - #define PA7_WPORT PORTA - #define PA7_DDR DDRA - #define PA7_PWM NULL - - #undef PB0 - #define PB0_PIN PINB0 - #define PB0_RPORT PINB - #define PB0_WPORT PORTB - #define PB0_DDR DDRB - #define PB0_PWM NULL - #undef PB1 - #define PB1_PIN PINB1 - #define PB1_RPORT PINB - #define PB1_WPORT PORTB - #define PB1_DDR DDRB - #define PB1_PWM NULL - #undef PB2 - #define PB2_PIN PINB2 - #define PB2_RPORT PINB - #define PB2_WPORT PORTB - #define PB2_DDR DDRB - #define PB2_PWM NULL - #undef PB3 - #define PB3_PIN PINB3 - #define PB3_RPORT PINB - #define PB3_WPORT PORTB - #define PB3_DDR DDRB - #define PB3_PWM NULL - #undef PB4 - #define PB4_PIN PINB4 - #define PB4_RPORT PINB - #define PB4_WPORT PORTB - #define PB4_DDR DDRB - #define PB4_PWM &OCR2A - #undef PB5 - #define PB5_PIN PINB5 - #define PB5_RPORT PINB - #define PB5_WPORT PORTB - #define PB5_DDR DDRB - #define PB5_PWM NULL - #undef PB6 - #define PB6_PIN PINB6 - #define PB6_RPORT PINB - #define PB6_WPORT PORTB - #define PB6_DDR DDRB - #define PB6_PWM NULL - #undef PB7 - #define PB7_PIN PINB7 - #define PB7_RPORT PINB - #define PB7_WPORT PORTB - #define PB7_DDR DDRB - #define PB7_PWM &OCR0A - - #undef PC0 - #define PC0_PIN PINC0 - #define PC0_RPORT PINC - #define PC0_WPORT PORTC - #define PC0_DDR DDRC - #define PC0_PWM NULL - #undef PC1 - #define PC1_PIN PINC1 - #define PC1_RPORT PINC - #define PC1_WPORT PORTC - #define PC1_DDR DDRC - #define PC1_PWM NULL - #undef PC2 - #define PC2_PIN PINC2 - #define PC2_RPORT PINC - #define PC2_WPORT PORTC - #define PC2_DDR DDRC - #define PC2_PWM NULL - #undef PC3 - #define PC3_PIN PINC3 - #define PC3_RPORT PINC - #define PC3_WPORT PORTC - #define PC3_DDR DDRC - #define PC3_PWM NULL - #undef PC4 - #define PC4_PIN PINC4 - #define PC4_RPORT PINC - #define PC4_WPORT PORTC - #define PC4_DDR DDRC - #define PC4_PWM NULL - #undef PC5 - #define PC5_PIN PINC5 - #define PC5_RPORT PINC - #define PC5_WPORT PORTC - #define PC5_DDR DDRC - #define PC5_PWM NULL - #undef PC6 - #define PC6_PIN PINC6 - #define PC6_RPORT PINC - #define PC6_WPORT PORTC - #define PC6_DDR DDRC - #define PC6_PWM NULL - #undef PC7 - #define PC7_PIN PINC7 - #define PC7_RPORT PINC - #define PC7_WPORT PORTC - #define PC7_DDR DDRC - #define PC7_PWM NULL - - #undef PD0 - #define PD0_PIN PIND0 - #define PD0_RPORT PIND - #define PD0_WPORT PORTD - #define PD0_DDR DDRD - #define PD0_PWM NULL - #undef PD1 - #define PD1_PIN PIND1 - #define PD1_RPORT PIND - #define PD1_WPORT PORTD - #define PD1_DDR DDRD - #define PD1_PWM NULL - #undef PD2 - #define PD2_PIN PIND2 - #define PD2_RPORT PIND - #define PD2_WPORT PORTD - #define PD2_DDR DDRD - #define PD2_PWM NULL - #undef PD3 - #define PD3_PIN PIND3 - #define PD3_RPORT PIND - #define PD3_WPORT PORTD - #define PD3_DDR DDRD - #define PD3_PWM NULL - #undef PD4 - #define PD4_PIN PIND4 - #define PD4_RPORT PIND - #define PD4_WPORT PORTD - #define PD4_DDR DDRD - #define PD4_PWM NULL - #undef PD5 - #define PD5_PIN PIND5 - #define PD5_RPORT PIND - #define PD5_WPORT PORTD - #define PD5_DDR DDRD - #define PD5_PWM NULL - #undef PD6 - #define PD6_PIN PIND6 - #define PD6_RPORT PIND - #define PD6_WPORT PORTD - #define PD6_DDR DDRD - #define PD6_PWM NULL - #undef PD7 - #define PD7_PIN PIND7 - #define PD7_RPORT PIND - #define PD7_WPORT PORTD - #define PD7_DDR DDRD - #define PD7_PWM NULL - - #undef PE0 - #define PE0_PIN PINE0 - #define PE0_RPORT PINE - #define PE0_WPORT PORTE - #define PE0_DDR DDRE - #define PE0_PWM NULL - #undef PE1 - #define PE1_PIN PINE1 - #define PE1_RPORT PINE - #define PE1_WPORT PORTE - #define PE1_DDR DDRE - #define PE1_PWM NULL - #undef PE2 - #define PE2_PIN PINE2 - #define PE2_RPORT PINE - #define PE2_WPORT PORTE - #define PE2_DDR DDRE - #define PE2_PWM NULL - #undef PE3 - #define PE3_PIN PINE3 - #define PE3_RPORT PINE - #define PE3_WPORT PORTE - #define PE3_DDR DDRE - #define PE3_PWM &OCR3AL - #undef PE4 - #define PE4_PIN PINE4 - #define PE4_RPORT PINE - #define PE4_WPORT PORTE - #define PE4_DDR DDRE - #define PE4_PWM &OCR3BL - #undef PE5 - #define PE5_PIN PINE5 - #define PE5_RPORT PINE - #define PE5_WPORT PORTE - #define PE5_DDR DDRE - #define PE5_PWM &OCR3CL - #undef PE6 - #define PE6_PIN PINE6 - #define PE6_RPORT PINE - #define PE6_WPORT PORTE - #define PE6_DDR DDRE - #define PE6_PWM NULL - #undef PE7 - #define PE7_PIN PINE7 - #define PE7_RPORT PINE - #define PE7_WPORT PORTE - #define PE7_DDR DDRE - #define PE7_PWM NULL - - #undef PF0 - #define PF0_PIN PINF0 - #define PF0_RPORT PINF - #define PF0_WPORT PORTF - #define PF0_DDR DDRF - #define PF0_PWM NULL - #undef PF1 - #define PF1_PIN PINF1 - #define PF1_RPORT PINF - #define PF1_WPORT PORTF - #define PF1_DDR DDRF - #define PF1_PWM NULL - #undef PF2 - #define PF2_PIN PINF2 - #define PF2_RPORT PINF - #define PF2_WPORT PORTF - #define PF2_DDR DDRF - #define PF2_PWM NULL - #undef PF3 - #define PF3_PIN PINF3 - #define PF3_RPORT PINF - #define PF3_WPORT PORTF - #define PF3_DDR DDRF - #define PF3_PWM NULL - #undef PF4 - #define PF4_PIN PINF4 - #define PF4_RPORT PINF - #define PF4_WPORT PORTF - #define PF4_DDR DDRF - #define PF4_PWM NULL - #undef PF5 - #define PF5_PIN PINF5 - #define PF5_RPORT PINF - #define PF5_WPORT PORTF - #define PF5_DDR DDRF - #define PF5_PWM NULL - #undef PF6 - #define PF6_PIN PINF6 - #define PF6_RPORT PINF - #define PF6_WPORT PORTF - #define PF6_DDR DDRF - #define PF6_PWM NULL - #undef PF7 - #define PF7_PIN PINF7 - #define PF7_RPORT PINF - #define PF7_WPORT PORTF - #define PF7_DDR DDRF - #define PF7_PWM NULL - - #undef PG0 - #define PG0_PIN PING0 - #define PG0_RPORT PING - #define PG0_WPORT PORTG - #define PG0_DDR DDRG - #define PG0_PWM NULL - #undef PG1 - #define PG1_PIN PING1 - #define PG1_RPORT PING - #define PG1_WPORT PORTG - #define PG1_DDR DDRG - #define PG1_PWM NULL - #undef PG2 - #define PG2_PIN PING2 - #define PG2_RPORT PING - #define PG2_WPORT PORTG - #define PG2_DDR DDRG - #define PG2_PWM NULL - #undef PG3 - #define PG3_PIN PING3 - #define PG3_RPORT PING - #define PG3_WPORT PORTG - #define PG3_DDR DDRG - #define PG3_PWM NULL - #undef PG4 - #define PG4_PIN PING4 - #define PG4_RPORT PING - #define PG4_WPORT PORTG - #define PG4_DDR DDRG - #define PG4_PWM NULL - #undef PG5 - #define PG5_PIN PING5 - #define PG5_RPORT PING - #define PG5_WPORT PORTG - #define PG5_DDR DDRG - #define PG5_PWM &OCR0B - - #undef PH0 - #define PH0_PIN PINH0 - #define PH0_RPORT PINH - #define PH0_WPORT PORTH - #define PH0_DDR DDRH - #define PH0_PWM NULL - #undef PH1 - #define PH1_PIN PINH1 - #define PH1_RPORT PINH - #define PH1_WPORT PORTH - #define PH1_DDR DDRH - #define PH1_PWM NULL - #undef PH2 - #define PH2_PIN PINH2 - #define PH2_RPORT PINH - #define PH2_WPORT PORTH - #define PH2_DDR DDRH - #define PH2_PWM NULL - #undef PH3 - #define PH3_PIN PINH3 - #define PH3_RPORT PINH - #define PH3_WPORT PORTH - #define PH3_DDR DDRH - #define PH3_PWM &OCR4AL - #undef PH4 - #define PH4_PIN PINH4 - #define PH4_RPORT PINH - #define PH4_WPORT PORTH - #define PH4_DDR DDRH - #define PH4_PWM &OCR4BL - #undef PH5 - #define PH5_PIN PINH5 - #define PH5_RPORT PINH - #define PH5_WPORT PORTH - #define PH5_DDR DDRH - #define PH5_PWM &OCR4CL - #undef PH6 - #define PH6_PIN PINH6 - #define PH6_RPORT PINH - #define PH6_WPORT PORTH - #define PH6_DDR DDRH - #define PH6_PWM &OCR2B - #undef PH7 - #define PH7_PIN PINH7 - #define PH7_RPORT PINH - #define PH7_WPORT PORTH - #define PH7_DDR DDRH - #define PH7_PWM NULL - - #undef PJ0 - #define PJ0_PIN PINJ0 - #define PJ0_RPORT PINJ - #define PJ0_WPORT PORTJ - #define PJ0_DDR DDRJ - #define PJ0_PWM NULL - #undef PJ1 - #define PJ1_PIN PINJ1 - #define PJ1_RPORT PINJ - #define PJ1_WPORT PORTJ - #define PJ1_DDR DDRJ - #define PJ1_PWM NULL - #undef PJ2 - #define PJ2_PIN PINJ2 - #define PJ2_RPORT PINJ - #define PJ2_WPORT PORTJ - #define PJ2_DDR DDRJ - #define PJ2_PWM NULL - #undef PJ3 - #define PJ3_PIN PINJ3 - #define PJ3_RPORT PINJ - #define PJ3_WPORT PORTJ - #define PJ3_DDR DDRJ - #define PJ3_PWM NULL - #undef PJ4 - #define PJ4_PIN PINJ4 - #define PJ4_RPORT PINJ - #define PJ4_WPORT PORTJ - #define PJ4_DDR DDRJ - #define PJ4_PWM NULL - #undef PJ5 - #define PJ5_PIN PINJ5 - #define PJ5_RPORT PINJ - #define PJ5_WPORT PORTJ - #define PJ5_DDR DDRJ - #define PJ5_PWM NULL - #undef PJ6 - #define PJ6_PIN PINJ6 - #define PJ6_RPORT PINJ - #define PJ6_WPORT PORTJ - #define PJ6_DDR DDRJ - #define PJ6_PWM NULL - #undef PJ7 - #define PJ7_PIN PINJ7 - #define PJ7_RPORT PINJ - #define PJ7_WPORT PORTJ - #define PJ7_DDR DDRJ - #define PJ7_PWM NULL - - #undef PK0 - #define PK0_PIN PINK0 - #define PK0_RPORT PINK - #define PK0_WPORT PORTK - #define PK0_DDR DDRK - #define PK0_PWM NULL - #undef PK1 - #define PK1_PIN PINK1 - #define PK1_RPORT PINK - #define PK1_WPORT PORTK - #define PK1_DDR DDRK - #define PK1_PWM NULL - #undef PK2 - #define PK2_PIN PINK2 - #define PK2_RPORT PINK - #define PK2_WPORT PORTK - #define PK2_DDR DDRK - #define PK2_PWM NULL - #undef PK3 - #define PK3_PIN PINK3 - #define PK3_RPORT PINK - #define PK3_WPORT PORTK - #define PK3_DDR DDRK - #define PK3_PWM NULL - #undef PK4 - #define PK4_PIN PINK4 - #define PK4_RPORT PINK - #define PK4_WPORT PORTK - #define PK4_DDR DDRK - #define PK4_PWM NULL - #undef PK5 - #define PK5_PIN PINK5 - #define PK5_RPORT PINK - #define PK5_WPORT PORTK - #define PK5_DDR DDRK - #define PK5_PWM NULL - #undef PK6 - #define PK6_PIN PINK6 - #define PK6_RPORT PINK - #define PK6_WPORT PORTK - #define PK6_DDR DDRK - #define PK6_PWM NULL - #undef PK7 - #define PK7_PIN PINK7 - #define PK7_RPORT PINK - #define PK7_WPORT PORTK - #define PK7_DDR DDRK - #define PK7_PWM NULL - - #undef PL0 - #define PL0_PIN PINL0 - #define PL0_RPORT PINL - #define PL0_WPORT PORTL - #define PL0_DDR DDRL - #define PL0_PWM NULL - #undef PL1 - #define PL1_PIN PINL1 - #define PL1_RPORT PINL - #define PL1_WPORT PORTL - #define PL1_DDR DDRL - #define PL1_PWM NULL - #undef PL2 - #define PL2_PIN PINL2 - #define PL2_RPORT PINL - #define PL2_WPORT PORTL - #define PL2_DDR DDRL - #define PL2_PWM NULL - #undef PL3 - #define PL3_PIN PINL3 - #define PL3_RPORT PINL - #define PL3_WPORT PORTL - #define PL3_DDR DDRL - #define PL3_PWM &OCR5AL - #undef PL4 - #define PL4_PIN PINL4 - #define PL4_RPORT PINL - #define PL4_WPORT PORTL - #define PL4_DDR DDRL - #define PL4_PWM &OCR5BL - #undef PL5 - #define PL5_PIN PINL5 - #define PL5_RPORT PINL - #define PL5_WPORT PORTL - #define PL5_DDR DDRL - #define PL5_PWM &OCR5CL - #undef PL6 - #define PL6_PIN PINL6 - #define PL6_RPORT PINL - #define PL6_WPORT PORTL - #define PL6_DDR DDRL - #define PL6_PWM NULL - #undef PL7 - #define PL7_PIN PINL7 - #define PL7_RPORT PINL - #define PL7_WPORT PORTL - #define PL7_DDR DDRL - #define PL7_PWM NULL -#endif // __AVR_ATmega(1280|2560)__ - -#if defined(__AVR_AT90USB1287__) || defined(__AVR_AT90USB1286__) || defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB647__) - - // change for your board - #define DEBUG_LED DIO31 /* led D5 red */ - - /** - * Pins Info - */ - - //#define AT90USBxx_TEENSYPP_ASSIGNMENTS // Use Teensy++ 2.0 assignments - #ifndef AT90USBxx_TEENSYPP_ASSIGNMENTS // Use traditional Marlin pin assignments - - // SPI - #define SCK DIO9 // 21 - #define MISO DIO11 // 23 - #define MOSI DIO10 // 22 - #define SS DIO8 // 20 - - #define DIO0_PIN PINA0 - #define DIO0_RPORT PINA - #define DIO0_WPORT PORTA - #define DIO0_PWM NULL - #define DIO0_DDR DDRA - - #define DIO1_PIN PINA1 - #define DIO1_RPORT PINA - #define DIO1_WPORT PORTA - #define DIO1_PWM NULL - #define DIO1_DDR DDRA - - #define DIO2_PIN PINA2 - #define DIO2_RPORT PINA - #define DIO2_WPORT PORTA - #define DIO2_PWM NULL - #define DIO2_DDR DDRA - - #define DIO3_PIN PINA3 - #define DIO3_RPORT PINA - #define DIO3_WPORT PORTA - #define DIO3_PWM NULL - #define DIO3_DDR DDRA - - #define DIO4_PIN PINA4 - #define DIO4_RPORT PINA - #define DIO4_WPORT PORTA - #define DIO4_PWM NULL - #define DIO4_DDR DDRA - - #define DIO5_PIN PINA5 - #define DIO5_RPORT PINA - #define DIO5_WPORT PORTA - #define DIO5_PWM NULL - #define DIO5_DDR DDRA - - #define DIO6_PIN PINA6 - #define DIO6_RPORT PINA - #define DIO6_WPORT PORTA - #define DIO6_PWM NULL - #define DIO6_DDR DDRA - - #define DIO7_PIN PINA7 - #define DIO7_RPORT PINA - #define DIO7_WPORT PORTA - #define DIO7_PWM NULL - #define DIO7_DDR DDRA - - #define DIO8_PIN PINB0 - #define DIO8_RPORT PINB - #define DIO8_WPORT PORTB - #define DIO8_PWM NULL - #define DIO8_DDR DDRB - - #define DIO9_PIN PINB1 - #define DIO9_RPORT PINB - #define DIO9_WPORT PORTB - #define DIO9_PWM NULL - #define DIO9_DDR DDRB - - #define DIO10_PIN PINB2 - #define DIO10_RPORT PINB - #define DIO10_WPORT PORTB - #define DIO10_PWM NULL - #define DIO10_DDR DDRB - - #define DIO11_PIN PINB3 - #define DIO11_RPORT PINB - #define DIO11_WPORT PORTB - #define DIO11_PWM NULL - #define DIO11_DDR DDRB - - #define DIO12_PIN PINB4 - #define DIO12_RPORT PINB - #define DIO12_WPORT PORTB - #define DIO12_PWM NULL - #define DIO12_DDR DDRB - - #define DIO13_PIN PINB5 - #define DIO13_RPORT PINB - #define DIO13_WPORT PORTB - #define DIO13_PWM NULL - #define DIO13_DDR DDRB - - #define DIO14_PIN PINB6 - #define DIO14_RPORT PINB - #define DIO14_WPORT PORTB - #define DIO14_PWM NULL - #define DIO14_DDR DDRB - - #define DIO15_PIN PINB7 - #define DIO15_RPORT PINB - #define DIO15_WPORT PORTB - #define DIO15_PWM NULL - #define DIO15_DDR DDRB - - #define DIO16_PIN PINC0 - #define DIO16_RPORT PINC - #define DIO16_WPORT PORTC - #define DIO16_PWM NULL - #define DIO16_DDR DDRC - - #define DIO17_PIN PINC1 - #define DIO17_RPORT PINC - #define DIO17_WPORT PORTC - #define DIO17_PWM NULL - #define DIO17_DDR DDRC - - #define DIO18_PIN PINC2 - #define DIO18_RPORT PINC - #define DIO18_WPORT PORTC - #define DIO18_PWM NULL - #define DIO18_DDR DDRC - - #define DIO19_PIN PINC3 - #define DIO19_RPORT PINC - #define DIO19_WPORT PORTC - #define DIO19_PWM NULL - #define DIO19_DDR DDRC - - #define DIO20_PIN PINC4 - #define DIO20_RPORT PINC - #define DIO20_WPORT PORTC - #define DIO20_PWM NULL - #define DIO20_DDR DDRC - - #define DIO21_PIN PINC5 - #define DIO21_RPORT PINC - #define DIO21_WPORT PORTC - #define DIO21_PWM NULL - #define DIO21_DDR DDRC - - #define DIO22_PIN PINC6 - #define DIO22_RPORT PINC - #define DIO22_WPORT PORTC - #define DIO22_PWM NULL - #define DIO22_DDR DDRC - - #define DIO23_PIN PINC7 - #define DIO23_RPORT PINC - #define DIO23_WPORT PORTC - #define DIO23_PWM NULL - #define DIO23_DDR DDRC - - #define DIO24_PIN PIND0 - #define DIO24_RPORT PIND - #define DIO24_WPORT PORTD - #define DIO24_PWM NULL - #define DIO24_DDR DDRD - - #define DIO25_PIN PIND1 - #define DIO25_RPORT PIND - #define DIO25_WPORT PORTD - #define DIO25_PWM NULL - #define DIO25_DDR DDRD - - #define DIO26_PIN PIND2 - #define DIO26_RPORT PIND - #define DIO26_WPORT PORTD - #define DIO26_PWM NULL - #define DIO26_DDR DDRD - - #define DIO27_PIN PIND3 - #define DIO27_RPORT PIND - #define DIO27_WPORT PORTD - #define DIO27_PWM NULL - #define DIO27_DDR DDRD - - #define DIO28_PIN PIND4 - #define DIO28_RPORT PIND - #define DIO28_WPORT PORTD - #define DIO28_PWM NULL - #define DIO28_DDR DDRD - - #define DIO29_PIN PIND5 - #define DIO29_RPORT PIND - #define DIO29_WPORT PORTD - #define DIO29_PWM NULL - #define DIO29_DDR DDRD - - #define DIO30_PIN PIND6 - #define DIO30_RPORT PIND - #define DIO30_WPORT PORTD - #define DIO30_PWM NULL - #define DIO30_DDR DDRD - - #define DIO31_PIN PIND7 - #define DIO31_RPORT PIND - #define DIO31_WPORT PORTD - #define DIO31_PWM NULL - #define DIO31_DDR DDRD - - - #define DIO32_PIN PINE0 - #define DIO32_RPORT PINE - #define DIO32_WPORT PORTE - #define DIO32_PWM NULL - #define DIO32_DDR DDRE - - #define DIO33_PIN PINE1 - #define DIO33_RPORT PINE - #define DIO33_WPORT PORTE - #define DIO33_PWM NULL - #define DIO33_DDR DDRE - - #define DIO34_PIN PINE2 - #define DIO34_RPORT PINE - #define DIO34_WPORT PORTE - #define DIO34_PWM NULL - #define DIO34_DDR DDRE - - #define DIO35_PIN PINE3 - #define DIO35_RPORT PINE - #define DIO35_WPORT PORTE - #define DIO35_PWM NULL - #define DIO35_DDR DDRE - - #define DIO36_PIN PINE4 - #define DIO36_RPORT PINE - #define DIO36_WPORT PORTE - #define DIO36_PWM NULL - #define DIO36_DDR DDRE - - #define DIO37_PIN PINE5 - #define DIO37_RPORT PINE - #define DIO37_WPORT PORTE - #define DIO37_PWM NULL - #define DIO37_DDR DDRE - - #define DIO38_PIN PINE6 - #define DIO38_RPORT PINE - #define DIO38_WPORT PORTE - #define DIO38_PWM NULL - #define DIO38_DDR DDRE - - #define DIO39_PIN PINE7 - #define DIO39_RPORT PINE - #define DIO39_WPORT PORTE - #define DIO39_PWM NULL - #define DIO39_DDR DDRE - - #define AIO0_PIN PINF0 - #define AIO0_RPORT PINF - #define AIO0_WPORT PORTF - #define AIO0_PWM NULL - #define AIO0_DDR DDRF - - #define AIO1_PIN PINF1 - #define AIO1_RPORT PINF - #define AIO1_WPORT PORTF - #define AIO1_PWM NULL - #define AIO1_DDR DDRF - - #define AIO2_PIN PINF2 - #define AIO2_RPORT PINF - #define AIO2_WPORT PORTF - #define AIO2_PWM NULL - #define AIO2_DDR DDRF - - #define AIO3_PIN PINF3 - #define AIO3_RPORT PINF - #define AIO3_WPORT PORTF - #define AIO3_PWM NULL - #define AIO3_DDR DDRF - - #define AIO4_PIN PINF4 - #define AIO4_RPORT PINF - #define AIO4_WPORT PORTF - #define AIO4_PWM NULL - #define AIO4_DDR DDRF - - #define AIO5_PIN PINF5 - #define AIO5_RPORT PINF - #define AIO5_WPORT PORTF - #define AIO5_PWM NULL - #define AIO5_DDR DDRF - - #define AIO6_PIN PINF6 - #define AIO6_RPORT PINF - #define AIO6_WPORT PORTF - #define AIO6_PWM NULL - #define AIO6_DDR DDRF - - #define AIO7_PIN PINF7 - #define AIO7_RPORT PINF - #define AIO7_WPORT PORTF - #define AIO7_PWM NULL - #define AIO7_DDR DDRF - - #define DIO40_PIN PINF0 - #define DIO40_RPORT PINF - #define DIO40_WPORT PORTF - #define DIO40_PWM NULL - #define DIO40_DDR DDRF - - #define DIO41_PIN PINF1 - #define DIO41_RPORT PINF - #define DIO41_WPORT PORTF - #define DIO41_PWM NULL - #define DIO41_DDR DDRF - - #define DIO42_PIN PINF2 - #define DIO42_RPORT PINF - #define DIO42_WPORT PORTF - #define DIO42_PWM NULL - #define DIO42_DDR DDRF - - #define DIO43_PIN PINF3 - #define DIO43_RPORT PINF - #define DIO43_WPORT PORTF - #define DIO43_PWM NULL - #define DIO43_DDR DDRF - - #define DIO44_PIN PINF4 - #define DIO44_RPORT PINF - #define DIO44_WPORT PORTF - #define DIO44_PWM NULL - #define DIO44_DDR DDRF - - #define DIO45_PIN PINF5 - #define DIO45_RPORT PINF - #define DIO45_WPORT PORTF - #define DIO45_PWM NULL - #define DIO45_DDR DDRF - - #define DIO46_PIN PINF6 - #define DIO46_RPORT PINF - #define DIO46_WPORT PORTF - #define DIO46_PWM NULL - #define DIO46_DDR DDRF - - #define DIO47_PIN PINF7 - #define DIO47_RPORT PINF - #define DIO47_WPORT PORTF - #define DIO47_PWM NULL - #define DIO47_DDR DDRF - - - #undef PA0 - #define PA0_PIN PINA0 - #define PA0_RPORT PINA - #define PA0_WPORT PORTA - #define PA0_PWM NULL - #define PA0_DDR DDRA - #undef PA1 - #define PA1_PIN PINA1 - #define PA1_RPORT PINA - #define PA1_WPORT PORTA - #define PA1_PWM NULL - #define PA1_DDR DDRA - #undef PA2 - #define PA2_PIN PINA2 - #define PA2_RPORT PINA - #define PA2_WPORT PORTA - #define PA2_PWM NULL - #define PA2_DDR DDRA - #undef PA3 - #define PA3_PIN PINA3 - #define PA3_RPORT PINA - #define PA3_WPORT PORTA - #define PA3_PWM NULL - #define PA3_DDR DDRA - #undef PA4 - #define PA4_PIN PINA4 - #define PA4_RPORT PINA - #define PA4_WPORT PORTA - #define PA4_PWM NULL - #define PA4_DDR DDRA - #undef PA5 - #define PA5_PIN PINA5 - #define PA5_RPORT PINA - #define PA5_WPORT PORTA - #define PA5_PWM NULL - #define PA5_DDR DDRA - #undef PA6 - #define PA6_PIN PINA6 - #define PA6_RPORT PINA - #define PA6_WPORT PORTA - #define PA6_PWM NULL - #define PA6_DDR DDRA - #undef PA7 - #define PA7_PIN PINA7 - #define PA7_RPORT PINA - #define PA7_WPORT PORTA - #define PA7_PWM NULL - #define PA7_DDR DDRA - - #undef PB0 - #define PB0_PIN PINB0 - #define PB0_RPORT PINB - #define PB0_WPORT PORTB - #define PB0_PWM NULL - #define PB0_DDR DDRB - #undef PB1 - #define PB1_PIN PINB1 - #define PB1_RPORT PINB - #define PB1_WPORT PORTB - #define PB1_PWM NULL - #define PB1_DDR DDRB - #undef PB2 - #define PB2_PIN PINB2 - #define PB2_RPORT PINB - #define PB2_WPORT PORTB - #define PB2_PWM NULL - #define PB2_DDR DDRB - #undef PB3 - #define PB3_PIN PINB3 - #define PB3_RPORT PINB - #define PB3_WPORT PORTB - #define PB3_PWM NULL - #define PB3_DDR DDRB - #undef PB4 - #define PB4_PIN PINB4 - #define PB4_RPORT PINB - #define PB4_WPORT PORTB - #define PB4_PWM NULL - #define PB4_DDR DDRB - #undef PB5 - #define PB5_PIN PINB5 - #define PB5_RPORT PINB - #define PB5_WPORT PORTB - #define PB5_PWM NULL - #define PB5_DDR DDRB - #undef PB6 - #define PB6_PIN PINB6 - #define PB6_RPORT PINB - #define PB6_WPORT PORTB - #define PB6_PWM NULL - #define PB6_DDR DDRB - #undef PB7 - #define PB7_PIN PINB7 - #define PB7_RPORT PINB - #define PB7_WPORT PORTB - #define PB7_PWM NULL - #define PB7_DDR DDRB - - #undef PC0 - #define PC0_PIN PINC0 - #define PC0_RPORT PINC - #define PC0_WPORT PORTC - #define PC0_PWM NULL - #define PC0_DDR DDRC - #undef PC1 - #define PC1_PIN PINC1 - #define PC1_RPORT PINC - #define PC1_WPORT PORTC - #define PC1_PWM NULL - #define PC1_DDR DDRC - #undef PC2 - #define PC2_PIN PINC2 - #define PC2_RPORT PINC - #define PC2_WPORT PORTC - #define PC2_PWM NULL - #define PC2_DDR DDRC - #undef PC3 - #define PC3_PIN PINC3 - #define PC3_RPORT PINC - #define PC3_WPORT PORTC - #define PC3_PWM NULL - #define PC3_DDR DDRC - #undef PC4 - #define PC4_PIN PINC4 - #define PC4_RPORT PINC - #define PC4_WPORT PORTC - #define PC4_PWM NULL - #define PC4_DDR DDRC - #undef PC5 - #define PC5_PIN PINC5 - #define PC5_RPORT PINC - #define PC5_WPORT PORTC - #define PC5_PWM NULL - #define PC5_DDR DDRC - #undef PC6 - #define PC6_PIN PINC6 - #define PC6_RPORT PINC - #define PC6_WPORT PORTC - #define PC6_PWM NULL - #define PC6_DDR DDRC - #undef PC7 - #define PC7_PIN PINC7 - #define PC7_RPORT PINC - #define PC7_WPORT PORTC - #define PC7_PWM NULL - #define PC7_DDR DDRC - - #undef PD0 - #define PD0_PIN PIND0 - #define PD0_RPORT PIND - #define PD0_WPORT PORTD - #define PD0_PWM NULL - #define PD0_DDR DDRD - #undef PD1 - #define PD1_PIN PIND1 - #define PD1_RPORT PIND - #define PD1_WPORT PORTD - #define PD1_PWM NULL - #define PD1_DDR DDRD - #undef PD2 - #define PD2_PIN PIND2 - #define PD2_RPORT PIND - #define PD2_WPORT PORTD - #define PD2_PWM NULL - #define PD2_DDR DDRD - #undef PD3 - #define PD3_PIN PIND3 - #define PD3_RPORT PIND - #define PD3_WPORT PORTD - #define PD3_PWM NULL - #define PD3_DDR DDRD - #undef PD4 - #define PD4_PIN PIND4 - #define PD4_RPORT PIND - #define PD4_WPORT PORTD - #define PD4_PWM NULL - #define PD4_DDR DDRD - #undef PD5 - #define PD5_PIN PIND5 - #define PD5_RPORT PIND - #define PD5_WPORT PORTD - #define PD5_PWM NULL - #define PD5_DDR DDRD - #undef PD6 - #define PD6_PIN PIND6 - #define PD6_RPORT PIND - #define PD6_WPORT PORTD - #define PD6_PWM NULL - #define PD6_DDR DDRD - #undef PD7 - #define PD7_PIN PIND7 - #define PD7_RPORT PIND - #define PD7_WPORT PORTD - #define PD7_PWM NULL - #define PD7_DDR DDRD - - #undef PE0 - #define PE0_PIN PINE0 - #define PE0_RPORT PINE - #define PE0_WPORT PORTE - #define PE0_PWM NULL - #define PE0_DDR DDRE - #undef PE1 - #define PE1_PIN PINE1 - #define PE1_RPORT PINE - #define PE1_WPORT PORTE - #define PE1_PWM NULL - #define PE1_DDR DDRE - #undef PE2 - #define PE2_PIN PINE2 - #define PE2_RPORT PINE - #define PE2_WPORT PORTE - #define PE2_PWM NULL - #define PE2_DDR DDRE - #undef PE3 - #define PE3_PIN PINE3 - #define PE3_RPORT PINE - #define PE3_WPORT PORTE - #define PE3_PWM NULL - #define PE3_DDR DDRE - #undef PE4 - #define PE4_PIN PINE4 - #define PE4_RPORT PINE - #define PE4_WPORT PORTE - #define PE4_PWM NULL - #define PE4_DDR DDRE - #undef PE5 - #define PE5_PIN PINE5 - #define PE5_RPORT PINE - #define PE5_WPORT PORTE - #define PE5_PWM NULL - #define PE5_DDR DDRE - #undef PE6 - #define PE6_PIN PINE6 - #define PE6_RPORT PINE - #define PE6_WPORT PORTE - #define PE6_PWM NULL - #define PE6_DDR DDRE - #undef PE7 - #define PE7_PIN PINE7 - #define PE7_RPORT PINE - #define PE7_WPORT PORTE - #define PE7_PWM NULL - #define PE7_DDR DDRE - - #undef PF0 - #define PF0_PIN PINF0 - #define PF0_RPORT PINF - #define PF0_WPORT PORTF - #define PF0_PWM NULL - #define PF0_DDR DDRF - #undef PF1 - #define PF1_PIN PINF1 - #define PF1_RPORT PINF - #define PF1_WPORT PORTF - #define PF1_PWM NULL - #define PF1_DDR DDRF - #undef PF2 - #define PF2_PIN PINF2 - #define PF2_RPORT PINF - #define PF2_WPORT PORTF - #define PF2_PWM NULL - #define PF2_DDR DDRF - #undef PF3 - #define PF3_PIN PINF3 - #define PF3_RPORT PINF - #define PF3_WPORT PORTF - #define PF3_PWM NULL - #define PF3_DDR DDRF - #undef PF4 - #define PF4_PIN PINF4 - #define PF4_RPORT PINF - #define PF4_WPORT PORTF - #define PF4_PWM NULL - #define PF4_DDR DDRF - #undef PF5 - #define PF5_PIN PINF5 - #define PF5_RPORT PINF - #define PF5_WPORT PORTF - #define PF5_PWM NULL - #define PF5_DDR DDRF - #undef PF6 - #define PF6_PIN PINF6 - #define PF6_RPORT PINF - #define PF6_WPORT PORTF - #define PF6_PWM NULL - #define PF6_DDR DDRF - #undef PF7 - #define PF7_PIN PINF7 - #define PF7_RPORT PINF - #define PF7_WPORT PORTF - #define PF7_PWM NULL - #define PF7_DDR DDRF - - #else // AT90USBxx_TEENSYPP_ASSIGNMENTS -- Use Teensyduino Teensy++2.0 assignments. - - /** - - AT90USB 51 50 49 48 47 46 45 44 10 11 12 13 14 15 16 17 35 36 37 38 39 40 41 42 25 26 27 28 29 30 31 32 33 34 43 09 18 19 01 02 61 60 59 58 57 56 55 54 - Port A0 A1 A2 A3 A4 A5 A6 A7 B0 B1 B2 B3 B4 B5 B6 B7 C0 C1 C2 C3 C4 C5 C6 C7 D0 D1 D2 D3 D4 D5 D6 D7 E0 E1 E2 E3 E4 E5 E6 E7 F0 F1 F2 F3 F4 F5 F6 F7 - Marlin 00 01 02 03 04 05 06 07 08 09 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 - Teensy 28 29 30 31 32 33 34 35 20 21 22 23 24 25 26 27 10 11 12 13 14 15 16 17 00 01 02 03 04 05 06 07 08 09(46*47)36 37 18 19 38 39 40 41 42 43 44 45 - The pins 46 and 47 are not supported by Teensyduino, but are supported below. - */ - - // SPI - #define SCK DIO21 // 9 - #define MISO DIO23 // 11 - #define MOSI DIO22 // 10 - #define SS DIO20 // 8 - - #define DIO0_PIN PIND0 - #define DIO0_RPORT PIND - #define DIO0_WPORT PORTD - #define DIO0_PWM NULL - #define DIO0_DDR DDRD - - #define DIO1_PIN PIND1 - #define DIO1_RPORT PIND - #define DIO1_WPORT PORTD - #define DIO1_PWM NULL - #define DIO1_DDR DDRD - - #define DIO2_PIN PIND2 - #define DIO2_RPORT PIND - #define DIO2_WPORT PORTD - #define DIO2_PWM NULL - #define DIO2_DDR DDRD - - #define DIO3_PIN PIND3 - #define DIO3_RPORT PIND - #define DIO3_WPORT PORTD - #define DIO3_PWM NULL - #define DIO3_DDR DDRD - - #define DIO4_PIN PIND4 - #define DIO4_RPORT PIND - #define DIO4_WPORT PORTD - #define DIO4_PWM NULL - #define DIO4_DDR DDRD - - #define DIO5_PIN PIND5 - #define DIO5_RPORT PIND - #define DIO5_WPORT PORTD - #define DIO5_PWM NULL - #define DIO5_DDR DDRD - - #define DIO6_PIN PIND6 - #define DIO6_RPORT PIND - #define DIO6_WPORT PORTD - #define DIO6_PWM NULL - #define DIO6_DDR DDRD - - #define DIO7_PIN PIND7 - #define DIO7_RPORT PIND - #define DIO7_WPORT PORTD - #define DIO7_PWM NULL - #define DIO7_DDR DDRD - - #define DIO8_PIN PINE0 - #define DIO8_RPORT PINE - #define DIO8_WPORT PORTE - #define DIO8_PWM NULL - #define DIO8_DDR DDRE - - #define DIO9_PIN PINE1 - #define DIO9_RPORT PINE - #define DIO9_WPORT PORTE - #define DIO9_PWM NULL - #define DIO9_DDR DDRE - - #define DIO10_PIN PINC0 - #define DIO10_RPORT PINC - #define DIO10_WPORT PORTC - #define DIO10_PWM NULL - #define DIO10_DDR DDRC - - #define DIO11_PIN PINC1 - #define DIO11_RPORT PINC - #define DIO11_WPORT PORTC - #define DIO11_PWM NULL - #define DIO11_DDR DDRC - - #define DIO12_PIN PINC2 - #define DIO12_RPORT PINC - #define DIO12_WPORT PORTC - #define DIO12_PWM NULL - #define DIO12_DDR DDRC - - #define DIO13_PIN PINC3 - #define DIO13_RPORT PINC - #define DIO13_WPORT PORTC - #define DIO13_PWM NULL - #define DIO13_DDR DDRC - - #define DIO14_PIN PINC4 - #define DIO14_RPORT PINC - #define DIO14_WPORT PORTC - #define DIO14_PWM NULL - #define DIO14_DDR DDRC - - #define DIO15_PIN PINC5 - #define DIO15_RPORT PINC - #define DIO15_WPORT PORTC - #define DIO15_PWM NULL - #define DIO15_DDR DDRC - - #define DIO16_PIN PINC6 - #define DIO16_RPORT PINC - #define DIO16_WPORT PORTC - #define DIO16_PWM NULL - #define DIO16_DDR DDRC - - #define DIO17_PIN PINC7 - #define DIO17_RPORT PINC - #define DIO17_WPORT PORTC - #define DIO17_PWM NULL - #define DIO17_DDR DDRC - - #define DIO18_PIN PINE6 - #define DIO18_RPORT PINE - #define DIO18_WPORT PORTE - #define DIO18_PWM NULL - #define DIO18_DDR DDRE - - #define DIO19_PIN PINE7 - #define DIO19_RPORT PINE - #define DIO19_WPORT PORTE - #define DIO19_PWM NULL - #define DIO19_DDR DDRE - - #define DIO20_PIN PINB0 - #define DIO20_RPORT PINB - #define DIO20_WPORT PORTB - #define DIO20_PWM NULL - #define DIO20_DDR DDRB - - #define DIO21_PIN PINB1 - #define DIO21_RPORT PINB - #define DIO21_WPORT PORTB - #define DIO21_PWM NULL - #define DIO21_DDR DDRB - - #define DIO22_PIN PINB2 - #define DIO22_RPORT PINB - #define DIO22_WPORT PORTB - #define DIO22_PWM NULL - #define DIO22_DDR DDRB - - #define DIO23_PIN PINB3 - #define DIO23_RPORT PINB - #define DIO23_WPORT PORTB - #define DIO23_PWM NULL - #define DIO23_DDR DDRB - - #define DIO24_PIN PINB4 - #define DIO24_RPORT PINB - #define DIO24_WPORT PORTB - #define DIO24_PWM NULL - #define DIO24_DDR DDRB - - #define DIO25_PIN PINB5 - #define DIO25_RPORT PINB - #define DIO25_WPORT PORTB - #define DIO25_PWM NULL - #define DIO25_DDR DDRB - - #define DIO26_PIN PINB6 - #define DIO26_RPORT PINB - #define DIO26_WPORT PORTB - #define DIO26_PWM NULL - #define DIO26_DDR DDRB - - #define DIO27_PIN PINB7 - #define DIO27_RPORT PINB - #define DIO27_WPORT PORTB - #define DIO27_PWM NULL - #define DIO27_DDR DDRB - - #define DIO28_PIN PINA0 - #define DIO28_RPORT PINA - #define DIO28_WPORT PORTA - #define DIO28_PWM NULL - #define DIO28_DDR DDRA - - #define DIO29_PIN PINA1 - #define DIO29_RPORT PINA - #define DIO29_WPORT PORTA - #define DIO29_PWM NULL - #define DIO29_DDR DDRA - - #define DIO30_PIN PINA2 - #define DIO30_RPORT PINA - #define DIO30_WPORT PORTA - #define DIO30_PWM NULL - #define DIO30_DDR DDRA - - #define DIO31_PIN PINA3 - #define DIO31_RPORT PINA - #define DIO31_WPORT PORTA - #define DIO31_PWM NULL - #define DIO31_DDR DDRA - - #define DIO32_PIN PINA4 - #define DIO32_RPORT PINA - #define DIO32_WPORT PORTA - #define DIO32_PWM NULL - #define DIO32_DDR DDRA - - #define DIO33_PIN PINA5 - #define DIO33_RPORT PINA - #define DIO33_WPORT PORTA - #define DIO33_PWM NULL - #define DIO33_DDR DDRA - - #define DIO34_PIN PINA6 - #define DIO34_RPORT PINA - #define DIO34_WPORT PORTA - #define DIO34_PWM NULL - #define DIO34_DDR DDRA - - #define DIO35_PIN PINA7 - #define DIO35_RPORT PINA - #define DIO35_WPORT PORTA - #define DIO35_PWM NULL - #define DIO35_DDR DDRA - - #define DIO36_PIN PINE4 - #define DIO36_RPORT PINE - #define DIO36_WPORT PORTE - #define DIO36_PWM NULL - #define DIO36_DDR DDRE - - #define DIO37_PIN PINE5 - #define DIO37_RPORT PINE - #define DIO37_WPORT PORTE - #define DIO37_PWM NULL - #define DIO37_DDR DDRE - - #define DIO38_PIN PINF0 - #define DIO38_RPORT PINF - #define DIO38_WPORT PORTF - #define DIO38_PWM NULL - #define DIO38_DDR DDRF - - #define DIO39_PIN PINF1 - #define DIO39_RPORT PINF - #define DIO39_WPORT PORTF - #define DIO39_PWM NULL - #define DIO39_DDR DDRF - - #define DIO40_PIN PINF2 - #define DIO40_RPORT PINF - #define DIO40_WPORT PORTF - #define DIO40_PWM NULL - #define DIO40_DDR DDRF - - #define DIO41_PIN PINF3 - #define DIO41_RPORT PINF - #define DIO41_WPORT PORTF - #define DIO41_PWM NULL - #define DIO41_DDR DDRF - - #define DIO42_PIN PINF4 - #define DIO42_RPORT PINF - #define DIO42_WPORT PORTF - #define DIO42_PWM NULL - #define DIO42_DDR DDRF - - #define DIO43_PIN PINF5 - #define DIO43_RPORT PINF - #define DIO43_WPORT PORTF - #define DIO43_PWM NULL - #define DIO43_DDR DDRF - - #define DIO44_PIN PINF6 - #define DIO44_RPORT PINF - #define DIO44_WPORT PORTF - #define DIO44_PWM NULL - #define DIO44_DDR DDRF - - #define DIO45_PIN PINF7 - #define DIO45_RPORT PINF - #define DIO45_WPORT PORTF - #define DIO45_PWM NULL - #define DIO45_DDR DDRF - - #define AIO0_PIN PINF0 - #define AIO0_RPORT PINF - #define AIO0_WPORT PORTF - #define AIO0_PWM NULL - #define AIO0_DDR DDRF - - #define AIO1_PIN PINF1 - #define AIO1_RPORT PINF - #define AIO1_WPORT PORTF - #define AIO1_PWM NULL - #define AIO1_DDR DDRF - - #define AIO2_PIN PINF2 - #define AIO2_RPORT PINF - #define AIO2_WPORT PORTF - #define AIO2_PWM NULL - #define AIO2_DDR DDRF - - #define AIO3_PIN PINF3 - #define AIO3_RPORT PINF - #define AIO3_WPORT PORTF - #define AIO3_PWM NULL - #define AIO3_DDR DDRF - - #define AIO4_PIN PINF4 - #define AIO4_RPORT PINF - #define AIO4_WPORT PORTF - #define AIO4_PWM NULL - #define AIO4_DDR DDRF - - #define AIO5_PIN PINF5 - #define AIO5_RPORT PINF - #define AIO5_WPORT PORTF - #define AIO5_PWM NULL - #define AIO5_DDR DDRF - - #define AIO6_PIN PINF6 - #define AIO6_RPORT PINF - #define AIO6_WPORT PORTF - #define AIO6_PWM NULL - #define AIO6_DDR DDRF - - #define AIO7_PIN PINF7 - #define AIO7_RPORT PINF - #define AIO7_WPORT PORTF - #define AIO7_PWM NULL - #define AIO7_DDR DDRF - - //-- Begin not supported by Teensyduino - //-- don't use Arduino functions on these pins pinMode/digitalWrite/etc - #define DIO46_PIN PINE2 - #define DIO46_RPORT PINE - #define DIO46_WPORT PORTE - #define DIO46_PWM NULL - #define DIO46_DDR DDRE - - #define DIO47_PIN PINE3 - #define DIO47_RPORT PINE - #define DIO47_WPORT PORTE - #define DIO47_PWM NULL - #define DIO47_DDR DDRE - //-- end not supported by Teensyduino - - #undef PA0 - #define PA0_PIN PINA0 - #define PA0_RPORT PINA - #define PA0_WPORT PORTA - #define PA0_PWM NULL - #define PA0_DDR DDRA - #undef PA1 - #define PA1_PIN PINA1 - #define PA1_RPORT PINA - #define PA1_WPORT PORTA - #define PA1_PWM NULL - #define PA1_DDR DDRA - #undef PA2 - #define PA2_PIN PINA2 - #define PA2_RPORT PINA - #define PA2_WPORT PORTA - #define PA2_PWM NULL - #define PA2_DDR DDRA - #undef PA3 - #define PA3_PIN PINA3 - #define PA3_RPORT PINA - #define PA3_WPORT PORTA - #define PA3_PWM NULL - #define PA3_DDR DDRA - #undef PA4 - #define PA4_PIN PINA4 - #define PA4_RPORT PINA - #define PA4_WPORT PORTA - #define PA4_PWM NULL - #define PA4_DDR DDRA - #undef PA5 - #define PA5_PIN PINA5 - #define PA5_RPORT PINA - #define PA5_WPORT PORTA - #define PA5_PWM NULL - #define PA5_DDR DDRA - #undef PA6 - #define PA6_PIN PINA6 - #define PA6_RPORT PINA - #define PA6_WPORT PORTA - #define PA6_PWM NULL - #define PA6_DDR DDRA - #undef PA7 - #define PA7_PIN PINA7 - #define PA7_RPORT PINA - #define PA7_WPORT PORTA - #define PA7_PWM NULL - #define PA7_DDR DDRA - - #undef PB0 - #define PB0_PIN PINB0 - #define PB0_RPORT PINB - #define PB0_WPORT PORTB - #define PB0_PWM NULL - #define PB0_DDR DDRB - #undef PB1 - #define PB1_PIN PINB1 - #define PB1_RPORT PINB - #define PB1_WPORT PORTB - #define PB1_PWM NULL - #define PB1_DDR DDRB - #undef PB2 - #define PB2_PIN PINB2 - #define PB2_RPORT PINB - #define PB2_WPORT PORTB - #define PB2_PWM NULL - #define PB2_DDR DDRB - #undef PB3 - #define PB3_PIN PINB3 - #define PB3_RPORT PINB - #define PB3_WPORT PORTB - #define PB3_PWM NULL - #define PB3_DDR DDRB - #undef PB4 - #define PB4_PIN PINB4 - #define PB4_RPORT PINB - #define PB4_WPORT PORTB - #define PB4_PWM NULL - #define PB4_DDR DDRB - #undef PB5 - #define PB5_PIN PINB5 - #define PB5_RPORT PINB - #define PB5_WPORT PORTB - #define PB5_PWM NULL - #define PB5_DDR DDRB - #undef PB6 - #define PB6_PIN PINB6 - #define PB6_RPORT PINB - #define PB6_WPORT PORTB - #define PB6_PWM NULL - #define PB6_DDR DDRB - #undef PB7 - #define PB7_PIN PINB7 - #define PB7_RPORT PINB - #define PB7_WPORT PORTB - #define PB7_PWM NULL - #define PB7_DDR DDRB - - #undef PC0 - #define PC0_PIN PINC0 - #define PC0_RPORT PINC - #define PC0_WPORT PORTC - #define PC0_PWM NULL - #define PC0_DDR DDRC - #undef PC1 - #define PC1_PIN PINC1 - #define PC1_RPORT PINC - #define PC1_WPORT PORTC - #define PC1_PWM NULL - #define PC1_DDR DDRC - #undef PC2 - #define PC2_PIN PINC2 - #define PC2_RPORT PINC - #define PC2_WPORT PORTC - #define PC2_PWM NULL - #define PC2_DDR DDRC - #undef PC3 - #define PC3_PIN PINC3 - #define PC3_RPORT PINC - #define PC3_WPORT PORTC - #define PC3_PWM NULL - #define PC3_DDR DDRC - #undef PC4 - #define PC4_PIN PINC4 - #define PC4_RPORT PINC - #define PC4_WPORT PORTC - #define PC4_PWM NULL - #define PC4_DDR DDRC - #undef PC5 - #define PC5_PIN PINC5 - #define PC5_RPORT PINC - #define PC5_WPORT PORTC - #define PC5_PWM NULL - #define PC5_DDR DDRC - #undef PC6 - #define PC6_PIN PINC6 - #define PC6_RPORT PINC - #define PC6_WPORT PORTC - #define PC6_PWM NULL - #define PC6_DDR DDRC - #undef PC7 - #define PC7_PIN PINC7 - #define PC7_RPORT PINC - #define PC7_WPORT PORTC - #define PC7_PWM NULL - #define PC7_DDR DDRC - - #undef PD0 - #define PD0_PIN PIND0 - #define PD0_RPORT PIND - #define PD0_WPORT PORTD - #define PD0_PWM NULL - #define PD0_DDR DDRD - #undef PD1 - #define PD1_PIN PIND1 - #define PD1_RPORT PIND - #define PD1_WPORT PORTD - #define PD1_PWM NULL - #define PD1_DDR DDRD - #undef PD2 - #define PD2_PIN PIND2 - #define PD2_RPORT PIND - #define PD2_WPORT PORTD - #define PD2_PWM NULL - #define PD2_DDR DDRD - #undef PD3 - #define PD3_PIN PIND3 - #define PD3_RPORT PIND - #define PD3_WPORT PORTD - #define PD3_PWM NULL - #define PD3_DDR DDRD - #undef PD4 - #define PD4_PIN PIND4 - #define PD4_RPORT PIND - #define PD4_WPORT PORTD - #define PD4_PWM NULL - #define PD4_DDR DDRD - #undef PD5 - #define PD5_PIN PIND5 - #define PD5_RPORT PIND - #define PD5_WPORT PORTD - #define PD5_PWM NULL - #define PD5_DDR DDRD - #undef PD6 - #define PD6_PIN PIND6 - #define PD6_RPORT PIND - #define PD6_WPORT PORTD - #define PD6_PWM NULL - #define PD6_DDR DDRD - #undef PD7 - #define PD7_PIN PIND7 - #define PD7_RPORT PIND - #define PD7_WPORT PORTD - #define PD7_PWM NULL - #define PD7_DDR DDRD - - #undef PE0 - #define PE0_PIN PINE0 - #define PE0_RPORT PINE - #define PE0_WPORT PORTE - #define PE0_PWM NULL - #define PE0_DDR DDRE - #undef PE1 - #define PE1_PIN PINE1 - #define PE1_RPORT PINE - #define PE1_WPORT PORTE - #define PE1_PWM NULL - #define PE1_DDR DDRE - #undef PE2 - #define PE2_PIN PINE2 - #define PE2_RPORT PINE - #define PE2_WPORT PORTE - #define PE2_PWM NULL - #define PE2_DDR DDRE - #undef PE3 - #define PE3_PIN PINE3 - #define PE3_RPORT PINE - #define PE3_WPORT PORTE - #define PE3_PWM NULL - #define PE3_DDR DDRE - #undef PE4 - #define PE4_PIN PINE4 - #define PE4_RPORT PINE - #define PE4_WPORT PORTE - #define PE4_PWM NULL - #define PE4_DDR DDRE - #undef PE5 - #define PE5_PIN PINE5 - #define PE5_RPORT PINE - #define PE5_WPORT PORTE - #define PE5_PWM NULL - #define PE5_DDR DDRE - #undef PE6 - #define PE6_PIN PINE6 - #define PE6_RPORT PINE - #define PE6_WPORT PORTE - #define PE6_PWM NULL - #define PE6_DDR DDRE - #undef PE7 - #define PE7_PIN PINE7 - #define PE7_RPORT PINE - #define PE7_WPORT PORTE - #define PE7_PWM NULL - #define PE7_DDR DDRE - - #undef PF0 - #define PF0_PIN PINF0 - #define PF0_RPORT PINF - #define PF0_WPORT PORTF - #define PF0_PWM NULL - #define PF0_DDR DDRF - #undef PF1 - #define PF1_PIN PINF1 - #define PF1_RPORT PINF - #define PF1_WPORT PORTF - #define PF1_PWM NULL - #define PF1_DDR DDRF - #undef PF2 - #define PF2_PIN PINF2 - #define PF2_RPORT PINF - #define PF2_WPORT PORTF - #define PF2_PWM NULL - #define PF2_DDR DDRF - #undef PF3 - #define PF3_PIN PINF3 - #define PF3_RPORT PINF - #define PF3_WPORT PORTF - #define PF3_PWM NULL - #define PF3_DDR DDRF - #undef PF4 - #define PF4_PIN PINF4 - #define PF4_RPORT PINF - #define PF4_WPORT PORTF - #define PF4_PWM NULL - #define PF4_DDR DDRF - #undef PF5 - #define PF5_PIN PINF5 - #define PF5_RPORT PINF - #define PF5_WPORT PORTF - #define PF5_PWM NULL - #define PF5_DDR DDRF - #undef PF6 - #define PF6_PIN PINF6 - #define PF6_RPORT PINF - #define PF6_WPORT PORTF - #define PF6_PWM NULL - #define PF6_DDR DDRF - #undef PF7 - #define PF7_PIN PINF7 - #define PF7_RPORT PINF - #define PF7_WPORT PORTF - #define PF7_PWM NULL - #define PF7_DDR DDRF - - #endif // AT90USBxx_TEENSYPP_ASSIGNMENTS Teensyduino assignments -#endif // __AVR_AT90USB(1287|1286|646|647)__ - -#if defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__) - // UART - #define RXD DIO0 - #define TXD DIO1 - - // SPI - #define SCK DIO10 - #define MISO DIO12 - #define MOSI DIO11 - #define SS DIO16 - - // TWI (I2C) - #define SCL DIO17 - #define SDA DIO18 - - // timers and PWM - #define OC0A DIO9 - #define OC0B DIO4 - #define OC1A DIO7 - #define OC1B DIO8 - #define OC2A DIO6 - #define OC3A DIO5 - #define OC3B DIO2 - #define OC3C DIO3 - - - // change for your board - #define DEBUG_LED DIO46 - - /** - * Pins Info - */ - - #define DIO0_PIN PINE0 - #define DIO0_RPORT PINE - #define DIO0_WPORT PORTE - #define DIO0_DDR DDRE - #define DIO0_PWM NULL - - #define DIO1_PIN PINE1 - #define DIO1_RPORT PINE - #define DIO1_WPORT PORTE - #define DIO1_DDR DDRE - #define DIO1_PWM NULL - - #define DIO2_PIN PINE4 - #define DIO2_RPORT PINE - #define DIO2_WPORT PORTE - #define DIO2_DDR DDRE - #define DIO2_PWM &OCR3BL - - #define DIO3_PIN PINE5 - #define DIO3_RPORT PINE - #define DIO3_WPORT PORTE - #define DIO3_DDR DDRE - #define DIO3_PWM &OCR3CL - - #define DIO4_PIN PING5 - #define DIO4_RPORT PING - #define DIO4_WPORT PORTG - #define DIO4_DDR DDRG - #define DIO4_PWM &OCR0B - - #define DIO5_PIN PINE3 - #define DIO5_RPORT PINE - #define DIO5_WPORT PORTE - #define DIO5_DDR DDRE - #define DIO5_PWM &OCR3AL - - #define DIO6_PIN PINB4 - #define DIO6_RPORT PINB - #define DIO6_WPORT PORTB - #define DIO6_DDR DDRB - #define DIO6_PWM &OCR2AL - - #define DIO7_PIN PINB5 - #define DIO7_RPORT PINB - #define DIO7_WPORT PORTB - #define DIO7_DDR DDRB - #define DIO7_PWM &OCR1AL - - #define DIO8_PIN PINB6 - #define DIO8_RPORT PINB - #define DIO8_WPORT PORTB - #define DIO8_DDR DDRB - #define DIO8_PWM &OCR1BL - - #define DIO9_PIN PINB7 - #define DIO9_RPORT PINB - #define DIO9_WPORT PORTB - #define DIO9_DDR DDRB - #define DIO9_PWM &OCR0AL - - #define DIO10_PIN PINB1 - #define DIO10_RPORT PINB - #define DIO10_WPORT PORTB - #define DIO10_DDR DDRB - #define DIO10_PWM NULL - - #define DIO11_PIN PINB2 - #define DIO11_RPORT PINB - #define DIO11_WPORT PORTB - #define DIO11_DDR DDRB - #define DIO11_PWM NULL - - #define DIO12_PIN PINB3 - #define DIO12_RPORT PINB - #define DIO12_WPORT PORTB - #define DIO12_DDR DDRB - #define DIO12_PWM NULL - - #define DIO13_PIN PINE2 - #define DIO13_RPORT PINE - #define DIO13_WPORT PORTE - #define DIO13_DDR DDRE - #define DIO13_PWM NULL - - #define DIO14_PIN PINE6 - #define DIO14_RPORT PINE - #define DIO14_WPORT PORTE - #define DIO14_DDR DDRE - #define DIO14_PWM NULL - - #define DIO15_PIN PINE7 - #define DIO15_RPORT PINE - #define DIO15_WPORT PORTE - #define DIO15_DDR DDRE - #define DIO15_PWM NULL - - #define DIO16_PIN PINB0 - #define DIO16_RPORT PINB - #define DIO16_WPORT PORTB - #define DIO16_DDR DDRB - #define DIO16_PWM NULL - - #define DIO17_PIN PIND0 - #define DIO17_RPORT PIND - #define DIO17_WPORT PORTD - #define DIO17_DDR DDRD - #define DIO17_PWM NULL - - #define DIO18_PIN PIND1 - #define DIO18_RPORT PIND - #define DIO18_WPORT PORTD - #define DIO18_DDR DDRD - #define DIO18_PWM NULL - - #define DIO19_PIN PIND2 - #define DIO19_RPORT PIND - #define DIO19_WPORT PORTD - #define DIO19_DDR DDRD - #define DIO19_PWM NULL - - #define DIO20_PIN PIND3 - #define DIO20_RPORT PIND - #define DIO20_WPORT PORTD - #define DIO20_DDR DDRD - #define DIO20_PWM NULL - - #define DIO21_PIN PIND4 - #define DIO21_RPORT PIND - #define DIO21_WPORT PORTD - #define DIO21_DDR DDRD - #define DIO21_PWM NULL - - #define DIO22_PIN PIND5 - #define DIO22_RPORT PIND - #define DIO22_WPORT PORTD - #define DIO22_DDR DDRD - #define DIO22_PWM NULL - - #define DIO23_PIN PIND6 - #define DIO23_RPORT PIND - #define DIO23_WPORT PORTD - #define DIO23_DDR DDRD - #define DIO23_PWM NULL - - #define DIO24_PIN PIND7 - #define DIO24_RPORT PIND - #define DIO24_WPORT PORTD - #define DIO24_DDR DDRD - #define DIO24_PWM NULL - - #define DIO25_PIN PING0 - #define DIO25_RPORT PING - #define DIO25_WPORT PORTG - #define DIO25_DDR DDRG - #define DIO25_PWM NULL - - #define DIO26_PIN PING1 - #define DIO26_RPORT PING - #define DIO26_WPORT PORTG - #define DIO26_DDR DDRG - #define DIO26_PWM NULL - - #define DIO27_PIN PING2 - #define DIO27_RPORT PING - #define DIO27_WPORT PORTG - #define DIO27_DDR DDRG - #define DIO27_PWM NULL - - #define DIO28_PIN PING3 - #define DIO28_RPORT PING - #define DIO28_WPORT PORTG - #define DIO28_DDR DDRG - #define DIO28_PWM NULL - - #define DIO29_PIN PING4 - #define DIO29_RPORT PING - #define DIO29_WPORT PORTG - #define DIO29_DDR DDRG - #define DIO29_PWM NULL - - #define DIO30_PIN PINC0 - #define DIO30_RPORT PINC - #define DIO30_WPORT PORTC - #define DIO30_DDR DDRC - #define DIO30_PWM NULL - - #define DIO31_PIN PINC1 - #define DIO31_RPORT PINC - #define DIO31_WPORT PORTC - #define DIO31_DDR DDRC - #define DIO31_PWM NULL - - #define DIO32_PIN PINC2 - #define DIO32_RPORT PINC - #define DIO32_WPORT PORTC - #define DIO32_DDR DDRC - #define DIO32_PWM NULL - - #define DIO33_PIN PINC3 - #define DIO33_RPORT PINC - #define DIO33_WPORT PORTC - #define DIO33_DDR DDRC - #define DIO33_PWM NULL - - #define DIO34_PIN PINC4 - #define DIO34_RPORT PINC - #define DIO34_WPORT PORTC - #define DIO34_DDR DDRC - #define DIO34_PWM NULL - - #define DIO35_PIN PINC5 - #define DIO35_RPORT PINC - #define DIO35_WPORT PORTC - #define DIO35_DDR DDRC - #define DIO35_PWM NULL - - #define DIO36_PIN PINC6 - #define DIO36_RPORT PINC - #define DIO36_WPORT PORTC - #define DIO36_DDR DDRC - #define DIO36_PWM NULL - - #define DIO37_PIN PINC7 - #define DIO37_RPORT PINC - #define DIO37_WPORT PORTC - #define DIO37_DDR DDRC - #define DIO37_PWM NULL - - #define DIO38_PIN PINA0 - #define DIO38_RPORT PINA - #define DIO38_WPORT PORTA - #define DIO38_DDR DDRA - #define DIO38_PWM NULL - - #define DIO39_PIN PINA1 - #define DIO39_RPORT PINA - #define DIO39_WPORT PORTA - #define DIO39_DDR DDRA - #define DIO39_PWM NULL - - #define DIO40_PIN PINA2 - #define DIO40_RPORT PINA - #define DIO40_WPORT PORTA - #define DIO40_DDR DDRA - #define DIO40_PWM NULL - - #define DIO41_PIN PINA3 - #define DIO41_RPORT PINA - #define DIO41_WPORT PORTA - #define DIO41_DDR DDRA - #define DIO41_PWM NULL - - #define DIO42_PIN PINA4 - #define DIO42_RPORT PINA - #define DIO42_WPORT PORTA - #define DIO42_DDR DDRA - #define DIO42_PWM NULL - - #define DIO43_PIN PINA5 - #define DIO43_RPORT PINA - #define DIO43_WPORT PORTA - #define DIO43_DDR DDRA - #define DIO43_PWM NULL - - #define DIO44_PIN PINA6 - #define DIO44_RPORT PINA - #define DIO44_WPORT PORTA - #define DIO44_DDR DDRA - #define DIO44_PWM NULL - - #define DIO45_PIN PINA7 - #define DIO45_RPORT PINA - #define DIO45_WPORT PORTA - #define DIO45_DDR DDRA - #define DIO45_PWM NULL - - #define DIO46_PIN PINF0 - #define DIO46_RPORT PINF - #define DIO46_WPORT PORTF - #define DIO46_DDR DDRF - #define DIO46_PWM NULL - - #define DIO47_PIN PINF1 - #define DIO47_RPORT PINF - #define DIO47_WPORT PORTF - #define DIO47_DDR DDRF - #define DIO47_PWM NULL - - #define DIO48_PIN PINF2 - #define DIO48_RPORT PINF - #define DIO48_WPORT PORTF - #define DIO48_DDR DDRF - #define DIO48_PWM NULL - - #define DIO49_PIN PINF3 - #define DIO49_RPORT PINF - #define DIO49_WPORT PORTF - #define DIO49_DDR DDRF - #define DIO49_PWM NULL - - #define DIO50_PIN PINF4 - #define DIO50_RPORT PINF - #define DIO50_WPORT PORTF - #define DIO50_DDR DDRF - #define DIO50_PWM NULL - - #define DIO51_PIN PINF5 - #define DIO51_RPORT PINF - #define DIO51_WPORT PORTF - #define DIO51_DDR DDRF - #define DIO51_PWM NULL - - #define DIO52_PIN PINF6 - #define DIO52_RPORT PINF - #define DIO52_WPORT PORTF - #define DIO52_DDR DDRF - #define DIO52_PWM NULL - - #define DIO53_PIN PINF7 - #define DIO53_RPORT PINF - #define DIO53_WPORT PORTF - #define DIO53_DDR DDRF - #define DIO53_PWM NULL - - #undef PA0 - #define PA0_PIN PINA0 - #define PA0_RPORT PINA - #define PA0_WPORT PORTA - #define PA0_DDR DDRA - #define PA0_PWM NULL - #undef PA1 - #define PA1_PIN PINA1 - #define PA1_RPORT PINA - #define PA1_WPORT PORTA - #define PA1_DDR DDRA - #define PA1_PWM NULL - #undef PA2 - #define PA2_PIN PINA2 - #define PA2_RPORT PINA - #define PA2_WPORT PORTA - #define PA2_DDR DDRA - #define PA2_PWM NULL - #undef PA3 - #define PA3_PIN PINA3 - #define PA3_RPORT PINA - #define PA3_WPORT PORTA - #define PA3_DDR DDRA - #define PA3_PWM NULL - #undef PA4 - #define PA4_PIN PINA4 - #define PA4_RPORT PINA - #define PA4_WPORT PORTA - #define PA4_DDR DDRA - #define PA4_PWM NULL - #undef PA5 - #define PA5_PIN PINA5 - #define PA5_RPORT PINA - #define PA5_WPORT PORTA - #define PA5_DDR DDRA - #define PA5_PWM NULL - #undef PA6 - #define PA6_PIN PINA6 - #define PA6_RPORT PINA - #define PA6_WPORT PORTA - #define PA6_DDR DDRA - #define PA6_PWM NULL - #undef PA7 - #define PA7_PIN PINA7 - #define PA7_RPORT PINA - #define PA7_WPORT PORTA - #define PA7_DDR DDRA - #define PA7_PWM NULL - - #undef PB0 - #define PB0_PIN PINB0 - #define PB0_RPORT PINB - #define PB0_WPORT PORTB - #define PB0_DDR DDRB - #define PB0_PWM NULL - #undef PB1 - #define PB1_PIN PINB1 - #define PB1_RPORT PINB - #define PB1_WPORT PORTB - #define PB1_DDR DDRB - #define PB1_PWM NULL - #undef PB2 - #define PB2_PIN PINB2 - #define PB2_RPORT PINB - #define PB2_WPORT PORTB - #define PB2_DDR DDRB - #define PB2_PWM NULL - #undef PB3 - #define PB3_PIN PINB3 - #define PB3_RPORT PINB - #define PB3_WPORT PORTB - #define PB3_DDR DDRB - #define PB3_PWM NULL - #undef PB4 - #define PB4_PIN PINB4 - #define PB4_RPORT PINB - #define PB4_WPORT PORTB - #define PB4_DDR DDRB - #define PB4_PWM &OCR2A - #undef PB5 - #define PB5_PIN PINB5 - #define PB5_RPORT PINB - #define PB5_WPORT PORTB - #define PB5_DDR DDRB - #define PB5_PWM NULL - #undef PB6 - #define PB6_PIN PINB6 - #define PB6_RPORT PINB - #define PB6_WPORT PORTB - #define PB6_DDR DDRB - #define PB6_PWM NULL - #undef PB7 - #define PB7_PIN PINB7 - #define PB7_RPORT PINB - #define PB7_WPORT PORTB - #define PB7_DDR DDRB - #define PB7_PWM &OCR0A - - #undef PC0 - #define PC0_PIN PINC0 - #define PC0_RPORT PINC - #define PC0_WPORT PORTC - #define PC0_DDR DDRC - #define PC0_PWM NULL - #undef PC1 - #define PC1_PIN PINC1 - #define PC1_RPORT PINC - #define PC1_WPORT PORTC - #define PC1_DDR DDRC - #define PC1_PWM NULL - #undef PC2 - #define PC2_PIN PINC2 - #define PC2_RPORT PINC - #define PC2_WPORT PORTC - #define PC2_DDR DDRC - #define PC2_PWM NULL - #undef PC3 - #define PC3_PIN PINC3 - #define PC3_RPORT PINC - #define PC3_WPORT PORTC - #define PC3_DDR DDRC - #define PC3_PWM NULL - #undef PC4 - #define PC4_PIN PINC4 - #define PC4_RPORT PINC - #define PC4_WPORT PORTC - #define PC4_DDR DDRC - #define PC4_PWM NULL - #undef PC5 - #define PC5_PIN PINC5 - #define PC5_RPORT PINC - #define PC5_WPORT PORTC - #define PC5_DDR DDRC - #define PC5_PWM NULL - #undef PC6 - #define PC6_PIN PINC6 - #define PC6_RPORT PINC - #define PC6_WPORT PORTC - #define PC6_DDR DDRC - #define PC6_PWM NULL - #undef PC7 - #define PC7_PIN PINC7 - #define PC7_RPORT PINC - #define PC7_WPORT PORTC - #define PC7_DDR DDRC - #define PC7_PWM NULL - - #undef PD0 - #define PD0_PIN PIND0 - #define PD0_RPORT PIND - #define PD0_WPORT PORTD - #define PD0_DDR DDRD - #define PD0_PWM NULL - #undef PD1 - #define PD1_PIN PIND1 - #define PD1_RPORT PIND - #define PD1_WPORT PORTD - #define PD1_DDR DDRD - #define PD1_PWM NULL - #undef PD2 - #define PD2_PIN PIND2 - #define PD2_RPORT PIND - #define PD2_WPORT PORTD - #define PD2_DDR DDRD - #define PD2_PWM NULL - #undef PD3 - #define PD3_PIN PIND3 - #define PD3_RPORT PIND - #define PD3_WPORT PORTD - #define PD3_DDR DDRD - #define PD3_PWM NULL - #undef PD4 - #define PD4_PIN PIND4 - #define PD4_RPORT PIND - #define PD4_WPORT PORTD - #define PD4_DDR DDRD - #define PD4_PWM NULL - #undef PD5 - #define PD5_PIN PIND5 - #define PD5_RPORT PIND - #define PD5_WPORT PORTD - #define PD5_DDR DDRD - #define PD5_PWM NULL - #undef PD6 - #define PD6_PIN PIND6 - #define PD6_RPORT PIND - #define PD6_WPORT PORTD - #define PD6_DDR DDRD - #define PD6_PWM NULL - #undef PD7 - #define PD7_PIN PIND7 - #define PD7_RPORT PIND - #define PD7_WPORT PORTD - #define PD7_DDR DDRD - #define PD7_PWM NULL - - #undef PE0 - #define PE0_PIN PINE0 - #define PE0_RPORT PINE - #define PE0_WPORT PORTE - #define PE0_DDR DDRE - #define PE0_PWM NULL - #undef PE1 - #define PE1_PIN PINE1 - #define PE1_RPORT PINE - #define PE1_WPORT PORTE - #define PE1_DDR DDRE - #define PE1_PWM NULL - #undef PE2 - #define PE2_PIN PINE2 - #define PE2_RPORT PINE - #define PE2_WPORT PORTE - #define PE2_DDR DDRE - #define PE2_PWM NULL - #undef PE3 - #define PE3_PIN PINE3 - #define PE3_RPORT PINE - #define PE3_WPORT PORTE - #define PE3_DDR DDRE - #define PE3_PWM &OCR3AL - #undef PE4 - #define PE4_PIN PINE4 - #define PE4_RPORT PINE - #define PE4_WPORT PORTE - #define PE4_DDR DDRE - #define PE4_PWM &OCR3BL - #undef PE5 - #define PE5_PIN PINE5 - #define PE5_RPORT PINE - #define PE5_WPORT PORTE - #define PE5_DDR DDRE - #define PE5_PWM &OCR3CL - #undef PE6 - #define PE6_PIN PINE6 - #define PE6_RPORT PINE - #define PE6_WPORT PORTE - #define PE6_DDR DDRE - #define PE6_PWM NULL - #undef PE7 - #define PE7_PIN PINE7 - #define PE7_RPORT PINE - #define PE7_WPORT PORTE - #define PE7_DDR DDRE - #define PE7_PWM NULL - - #undef PF0 - #define PF0_PIN PINF0 - #define PF0_RPORT PINF - #define PF0_WPORT PORTF - #define PF0_DDR DDRF - #define PF0_PWM NULL - #undef PF1 - #define PF1_PIN PINF1 - #define PF1_RPORT PINF - #define PF1_WPORT PORTF - #define PF1_DDR DDRF - #define PF1_PWM NULL - #undef PF2 - #define PF2_PIN PINF2 - #define PF2_RPORT PINF - #define PF2_WPORT PORTF - #define PF2_DDR DDRF - #define PF2_PWM NULL - #undef PF3 - #define PF3_PIN PINF3 - #define PF3_RPORT PINF - #define PF3_WPORT PORTF - #define PF3_DDR DDRF - #define PF3_PWM NULL - #undef PF4 - #define PF4_PIN PINF4 - #define PF4_RPORT PINF - #define PF4_WPORT PORTF - #define PF4_DDR DDRF - #define PF4_PWM NULL - #undef PF5 - #define PF5_PIN PINF5 - #define PF5_RPORT PINF - #define PF5_WPORT PORTF - #define PF5_DDR DDRF - #define PF5_PWM NULL - #undef PF6 - #define PF6_PIN PINF6 - #define PF6_RPORT PINF - #define PF6_WPORT PORTF - #define PF6_DDR DDRF - #define PF6_PWM NULL - #undef PF7 - #define PF7_PIN PINF7 - #define PF7_RPORT PINF - #define PF7_WPORT PORTF - #define PF7_DDR DDRF - #define PF7_PWM NULL - - #undef PG0 - #define PG0_PIN PING0 - #define PG0_RPORT PING - #define PG0_WPORT PORTG - #define PG0_DDR DDRG - #define PG0_PWM NULL - #undef PG1 - #define PG1_PIN PING1 - #define PG1_RPORT PING - #define PG1_WPORT PORTG - #define PG1_DDR DDRG - #define PG1_PWM NULL - #undef PG2 - #define PG2_PIN PING2 - #define PG2_RPORT PING - #define PG2_WPORT PORTG - #define PG2_DDR DDRG - #define PG2_PWM NULL - #undef PG3 - #define PG3_PIN PING3 - #define PG3_RPORT PING - #define PG3_WPORT PORTG - #define PG3_DDR DDRG - #define PG3_PWM NULL - #undef PG4 - #define PG4_PIN PING4 - #define PG4_RPORT PING - #define PG4_WPORT PORTG - #define PG4_DDR DDRG - #define PG4_PWM NULL - #undef PG5 - #define PG5_PIN PING5 - #define PG5_RPORT PING - #define PG5_WPORT PORTG - #define PG5_DDR DDRG - #define PG5_PWM &OCR0B -#endif // __AVR_ATmega(1281|2561)__ - -#ifndef DIO0_PIN - #error "pins for this chip not defined in arduino.h! If you write an appropriate pin definition and have this firmware work on your chip, please submit a pull request" -#endif - #endif // _FASTIO_ARDUINO_H diff --git a/Marlin/fastio_1280.h b/Marlin/fastio_1280.h new file mode 100644 index 000000000..f9f56c8a9 --- /dev/null +++ b/Marlin/fastio_1280.h @@ -0,0 +1,1115 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (C) 2016 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 . + * + */ + +/** + * Pin mapping for the 1280 and 2560 + * + * 1280 22 23 24 25 26 27 28 29 53 52 51 50 10 11 12 13 37 36 35 34 33 32 31 30 21 20 19 18 81 82 83 38 00 01 78 05 02 03 79 80 54 55 56 57 58 59 60 61 41 40 39 71 70 04 17 16 84 06 07 08 09 85 15 14 72 73 75 76 77 74 62 63 64 65 66 67 68 69 49 48 47 46 45 44 43 42 + * Port A0 A1 A2 A3 A4 A5 A6 A7 B0 B1 B2 B3 B4 B5 B6 B7 C0 C1 C2 C3 C4 C5 C6 C7 D0 D1 D2 D3 D4 D5 D6 D7 E0 E1 E2 E3 E4 E5 E6 E7 F0 F1 F2 F3 F4 F5 F6 F7 G0 G1 G2 G3 G4 G5 H0 H1 H2 H3 H4 H5 H6 H7 J0 J1 J2 J3 J4 J5 J6 J7 K0 K1 K2 K3 K4 K5 K6 K7 L0 L1 L2 L3 L4 L5 L6 L7 + * Marlin 00 01 02 03 04 05 06 07 08 09 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 + */ + +#ifndef _FASTIO_1280 +#define _FASTIO_1280 + +#include "fastio.h" + +// change for your board +#define DEBUG_LED DIO21 + +// UART +#define RXD DIO0 +#define TXD DIO1 + +// SPI +#define SCK DIO52 +#define MISO DIO50 +#define MOSI DIO51 +#define SS DIO53 + +// TWI (I2C) +#define SCL DIO21 +#define SDA DIO20 + +// Timers and PWM +#define OC0A DIO13 +#define OC0B DIO4 +#define OC1A DIO11 +#define OC1B DIO12 +#define OC2A DIO10 +#define OC2B DIO9 +#define OC3A DIO5 +#define OC3B DIO2 +#define OC3C DIO3 +#define OC4A DIO6 +#define OC4B DIO7 +#define OC4C DIO8 +#define OC5A DIO46 +#define OC5B DIO45 +#define OC5C DIO44 + +// Digital I/O + +#define DIO0_PIN PINE0 +#define DIO0_RPORT PINE +#define DIO0_WPORT PORTE +#define DIO0_DDR DDRE +#define DIO0_PWM NULL + +#define DIO1_PIN PINE1 +#define DIO1_RPORT PINE +#define DIO1_WPORT PORTE +#define DIO1_DDR DDRE +#define DIO1_PWM NULL + +#define DIO2_PIN PINE4 +#define DIO2_RPORT PINE +#define DIO2_WPORT PORTE +#define DIO2_DDR DDRE +#define DIO2_PWM &OCR3BL + +#define DIO3_PIN PINE5 +#define DIO3_RPORT PINE +#define DIO3_WPORT PORTE +#define DIO3_DDR DDRE +#define DIO3_PWM &OCR3CL + +#define DIO4_PIN PING5 +#define DIO4_RPORT PING +#define DIO4_WPORT PORTG +#define DIO4_DDR DDRG +#define DIO4_PWM &OCR0B + +#define DIO5_PIN PINE3 +#define DIO5_RPORT PINE +#define DIO5_WPORT PORTE +#define DIO5_DDR DDRE +#define DIO5_PWM &OCR3AL + +#define DIO6_PIN PINH3 +#define DIO6_RPORT PINH +#define DIO6_WPORT PORTH +#define DIO6_DDR DDRH +#define DIO6_PWM &OCR4AL + +#define DIO7_PIN PINH4 +#define DIO7_RPORT PINH +#define DIO7_WPORT PORTH +#define DIO7_DDR DDRH +#define DIO7_PWM &OCR4BL + +#define DIO8_PIN PINH5 +#define DIO8_RPORT PINH +#define DIO8_WPORT PORTH +#define DIO8_DDR DDRH +#define DIO8_PWM &OCR4CL + +#define DIO9_PIN PINH6 +#define DIO9_RPORT PINH +#define DIO9_WPORT PORTH +#define DIO9_DDR DDRH +#define DIO9_PWM &OCR2B + +#define DIO10_PIN PINB4 +#define DIO10_RPORT PINB +#define DIO10_WPORT PORTB +#define DIO10_DDR DDRB +#define DIO10_PWM &OCR2A + +#define DIO11_PIN PINB5 +#define DIO11_RPORT PINB +#define DIO11_WPORT PORTB +#define DIO11_DDR DDRB +#define DIO11_PWM NULL + +#define DIO12_PIN PINB6 +#define DIO12_RPORT PINB +#define DIO12_WPORT PORTB +#define DIO12_DDR DDRB +#define DIO12_PWM NULL + +#define DIO13_PIN PINB7 +#define DIO13_RPORT PINB +#define DIO13_WPORT PORTB +#define DIO13_DDR DDRB +#define DIO13_PWM &OCR0A + +#define DIO14_PIN PINJ1 +#define DIO14_RPORT PINJ +#define DIO14_WPORT PORTJ +#define DIO14_DDR DDRJ +#define DIO14_PWM NULL + +#define DIO15_PIN PINJ0 +#define DIO15_RPORT PINJ +#define DIO15_WPORT PORTJ +#define DIO15_DDR DDRJ +#define DIO15_PWM NULL + +#define DIO16_PIN PINH1 +#define DIO16_RPORT PINH +#define DIO16_WPORT PORTH +#define DIO16_DDR DDRH +#define DIO16_PWM NULL + +#define DIO17_PIN PINH0 +#define DIO17_RPORT PINH +#define DIO17_WPORT PORTH +#define DIO17_DDR DDRH +#define DIO17_PWM NULL + +#define DIO18_PIN PIND3 +#define DIO18_RPORT PIND +#define DIO18_WPORT PORTD +#define DIO18_DDR DDRD +#define DIO18_PWM NULL + +#define DIO19_PIN PIND2 +#define DIO19_RPORT PIND +#define DIO19_WPORT PORTD +#define DIO19_DDR DDRD +#define DIO19_PWM NULL + +#define DIO20_PIN PIND1 +#define DIO20_RPORT PIND +#define DIO20_WPORT PORTD +#define DIO20_DDR DDRD +#define DIO20_PWM NULL + +#define DIO21_PIN PIND0 +#define DIO21_RPORT PIND +#define DIO21_WPORT PORTD +#define DIO21_DDR DDRD +#define DIO21_PWM NULL + +#define DIO22_PIN PINA0 +#define DIO22_RPORT PINA +#define DIO22_WPORT PORTA +#define DIO22_DDR DDRA +#define DIO22_PWM NULL + +#define DIO23_PIN PINA1 +#define DIO23_RPORT PINA +#define DIO23_WPORT PORTA +#define DIO23_DDR DDRA +#define DIO23_PWM NULL + +#define DIO24_PIN PINA2 +#define DIO24_RPORT PINA +#define DIO24_WPORT PORTA +#define DIO24_DDR DDRA +#define DIO24_PWM NULL + +#define DIO25_PIN PINA3 +#define DIO25_RPORT PINA +#define DIO25_WPORT PORTA +#define DIO25_DDR DDRA +#define DIO25_PWM NULL + +#define DIO26_PIN PINA4 +#define DIO26_RPORT PINA +#define DIO26_WPORT PORTA +#define DIO26_DDR DDRA +#define DIO26_PWM NULL + +#define DIO27_PIN PINA5 +#define DIO27_RPORT PINA +#define DIO27_WPORT PORTA +#define DIO27_DDR DDRA +#define DIO27_PWM NULL + +#define DIO28_PIN PINA6 +#define DIO28_RPORT PINA +#define DIO28_WPORT PORTA +#define DIO28_DDR DDRA +#define DIO28_PWM NULL + +#define DIO29_PIN PINA7 +#define DIO29_RPORT PINA +#define DIO29_WPORT PORTA +#define DIO29_DDR DDRA +#define DIO29_PWM NULL + +#define DIO30_PIN PINC7 +#define DIO30_RPORT PINC +#define DIO30_WPORT PORTC +#define DIO30_DDR DDRC +#define DIO30_PWM NULL + +#define DIO31_PIN PINC6 +#define DIO31_RPORT PINC +#define DIO31_WPORT PORTC +#define DIO31_DDR DDRC +#define DIO31_PWM NULL + +#define DIO32_PIN PINC5 +#define DIO32_RPORT PINC +#define DIO32_WPORT PORTC +#define DIO32_DDR DDRC +#define DIO32_PWM NULL + +#define DIO33_PIN PINC4 +#define DIO33_RPORT PINC +#define DIO33_WPORT PORTC +#define DIO33_DDR DDRC +#define DIO33_PWM NULL + +#define DIO34_PIN PINC3 +#define DIO34_RPORT PINC +#define DIO34_WPORT PORTC +#define DIO34_DDR DDRC +#define DIO34_PWM NULL + +#define DIO35_PIN PINC2 +#define DIO35_RPORT PINC +#define DIO35_WPORT PORTC +#define DIO35_DDR DDRC +#define DIO35_PWM NULL + +#define DIO36_PIN PINC1 +#define DIO36_RPORT PINC +#define DIO36_WPORT PORTC +#define DIO36_DDR DDRC +#define DIO36_PWM NULL + +#define DIO37_PIN PINC0 +#define DIO37_RPORT PINC +#define DIO37_WPORT PORTC +#define DIO37_DDR DDRC +#define DIO37_PWM NULL + +#define DIO38_PIN PIND7 +#define DIO38_RPORT PIND +#define DIO38_WPORT PORTD +#define DIO38_DDR DDRD +#define DIO38_PWM NULL + +#define DIO39_PIN PING2 +#define DIO39_RPORT PING +#define DIO39_WPORT PORTG +#define DIO39_DDR DDRG +#define DIO39_PWM NULL + +#define DIO40_PIN PING1 +#define DIO40_RPORT PING +#define DIO40_WPORT PORTG +#define DIO40_DDR DDRG +#define DIO40_PWM NULL + +#define DIO41_PIN PING0 +#define DIO41_RPORT PING +#define DIO41_WPORT PORTG +#define DIO41_DDR DDRG +#define DIO41_PWM NULL + +#define DIO42_PIN PINL7 +#define DIO42_RPORT PINL +#define DIO42_WPORT PORTL +#define DIO42_DDR DDRL +#define DIO42_PWM NULL + +#define DIO43_PIN PINL6 +#define DIO43_RPORT PINL +#define DIO43_WPORT PORTL +#define DIO43_DDR DDRL +#define DIO43_PWM NULL + +#define DIO44_PIN PINL5 +#define DIO44_RPORT PINL +#define DIO44_WPORT PORTL +#define DIO44_DDR DDRL +#define DIO44_PWM &OCR5CL + +#define DIO45_PIN PINL4 +#define DIO45_RPORT PINL +#define DIO45_WPORT PORTL +#define DIO45_DDR DDRL +#define DIO45_PWM &OCR5BL + +#define DIO46_PIN PINL3 +#define DIO46_RPORT PINL +#define DIO46_WPORT PORTL +#define DIO46_DDR DDRL +#define DIO46_PWM &OCR5AL + +#define DIO47_PIN PINL2 +#define DIO47_RPORT PINL +#define DIO47_WPORT PORTL +#define DIO47_DDR DDRL +#define DIO47_PWM NULL + +#define DIO48_PIN PINL1 +#define DIO48_RPORT PINL +#define DIO48_WPORT PORTL +#define DIO48_DDR DDRL +#define DIO48_PWM NULL + +#define DIO49_PIN PINL0 +#define DIO49_RPORT PINL +#define DIO49_WPORT PORTL +#define DIO49_DDR DDRL +#define DIO49_PWM NULL + +#define DIO50_PIN PINB3 +#define DIO50_RPORT PINB +#define DIO50_WPORT PORTB +#define DIO50_DDR DDRB +#define DIO50_PWM NULL + +#define DIO51_PIN PINB2 +#define DIO51_RPORT PINB +#define DIO51_WPORT PORTB +#define DIO51_DDR DDRB +#define DIO51_PWM NULL + +#define DIO52_PIN PINB1 +#define DIO52_RPORT PINB +#define DIO52_WPORT PORTB +#define DIO52_DDR DDRB +#define DIO52_PWM NULL + +#define DIO53_PIN PINB0 +#define DIO53_RPORT PINB +#define DIO53_WPORT PORTB +#define DIO53_DDR DDRB +#define DIO53_PWM NULL + +#define DIO54_PIN PINF0 +#define DIO54_RPORT PINF +#define DIO54_WPORT PORTF +#define DIO54_DDR DDRF +#define DIO54_PWM NULL + +#define DIO55_PIN PINF1 +#define DIO55_RPORT PINF +#define DIO55_WPORT PORTF +#define DIO55_DDR DDRF +#define DIO55_PWM NULL + +#define DIO56_PIN PINF2 +#define DIO56_RPORT PINF +#define DIO56_WPORT PORTF +#define DIO56_DDR DDRF +#define DIO56_PWM NULL + +#define DIO57_PIN PINF3 +#define DIO57_RPORT PINF +#define DIO57_WPORT PORTF +#define DIO57_DDR DDRF +#define DIO57_PWM NULL + +#define DIO58_PIN PINF4 +#define DIO58_RPORT PINF +#define DIO58_WPORT PORTF +#define DIO58_DDR DDRF +#define DIO58_PWM NULL + +#define DIO59_PIN PINF5 +#define DIO59_RPORT PINF +#define DIO59_WPORT PORTF +#define DIO59_DDR DDRF +#define DIO59_PWM NULL + +#define DIO60_PIN PINF6 +#define DIO60_RPORT PINF +#define DIO60_WPORT PORTF +#define DIO60_DDR DDRF +#define DIO60_PWM NULL + +#define DIO61_PIN PINF7 +#define DIO61_RPORT PINF +#define DIO61_WPORT PORTF +#define DIO61_DDR DDRF +#define DIO61_PWM NULL + +#define DIO62_PIN PINK0 +#define DIO62_RPORT PINK +#define DIO62_WPORT PORTK +#define DIO62_DDR DDRK +#define DIO62_PWM NULL + +#define DIO63_PIN PINK1 +#define DIO63_RPORT PINK +#define DIO63_WPORT PORTK +#define DIO63_DDR DDRK +#define DIO63_PWM NULL + +#define DIO64_PIN PINK2 +#define DIO64_RPORT PINK +#define DIO64_WPORT PORTK +#define DIO64_DDR DDRK +#define DIO64_PWM NULL + +#define DIO65_PIN PINK3 +#define DIO65_RPORT PINK +#define DIO65_WPORT PORTK +#define DIO65_DDR DDRK +#define DIO65_PWM NULL + +#define DIO66_PIN PINK4 +#define DIO66_RPORT PINK +#define DIO66_WPORT PORTK +#define DIO66_DDR DDRK +#define DIO66_PWM NULL + +#define DIO67_PIN PINK5 +#define DIO67_RPORT PINK +#define DIO67_WPORT PORTK +#define DIO67_DDR DDRK +#define DIO67_PWM NULL + +#define DIO68_PIN PINK6 +#define DIO68_RPORT PINK +#define DIO68_WPORT PORTK +#define DIO68_DDR DDRK +#define DIO68_PWM NULL + +#define DIO69_PIN PINK7 +#define DIO69_RPORT PINK +#define DIO69_WPORT PORTK +#define DIO69_DDR DDRK +#define DIO69_PWM NULL + +#define DIO70_PIN PING4 +#define DIO70_RPORT PING +#define DIO70_WPORT PORTG +#define DIO70_DDR DDRG +#define DIO70_PWM NULL + +#define DIO71_PIN PING3 +#define DIO71_RPORT PING +#define DIO71_WPORT PORTG +#define DIO71_DDR DDRG +#define DIO71_PWM NULL + +#define DIO72_PIN PINJ2 +#define DIO72_RPORT PINJ +#define DIO72_WPORT PORTJ +#define DIO72_DDR DDRJ +#define DIO72_PWM NULL + +#define DIO73_PIN PINJ3 +#define DIO73_RPORT PINJ +#define DIO73_WPORT PORTJ +#define DIO73_DDR DDRJ +#define DIO73_PWM NULL + +#define DIO74_PIN PINJ7 +#define DIO74_RPORT PINJ +#define DIO74_WPORT PORTJ +#define DIO74_DDR DDRJ +#define DIO74_PWM NULL + +#define DIO75_PIN PINJ4 +#define DIO75_RPORT PINJ +#define DIO75_WPORT PORTJ +#define DIO75_DDR DDRJ +#define DIO75_PWM NULL + +#define DIO76_PIN PINJ5 +#define DIO76_RPORT PINJ +#define DIO76_WPORT PORTJ +#define DIO76_DDR DDRJ +#define DIO76_PWM NULL + +#define DIO77_PIN PINJ6 +#define DIO77_RPORT PINJ +#define DIO77_WPORT PORTJ +#define DIO77_DDR DDRJ +#define DIO77_PWM NULL + +#define DIO78_PIN PINE2 +#define DIO78_RPORT PINE +#define DIO78_WPORT PORTE +#define DIO78_DDR DDRE +#define DIO78_PWM NULL + +#define DIO79_PIN PINE6 +#define DIO79_RPORT PINE +#define DIO79_WPORT PORTE +#define DIO79_DDR DDRE +#define DIO79_PWM NULL + +#define DIO80_PIN PINE7 +#define DIO80_RPORT PINE +#define DIO80_WPORT PORTE +#define DIO80_DDR DDRE +#define DIO80_PWM NULL + +#define DIO81_PIN PIND4 +#define DIO81_RPORT PIND +#define DIO81_WPORT PORTD +#define DIO81_DDR DDRD +#define DIO81_PWM NULL + +#define DIO82_PIN PIND5 +#define DIO82_RPORT PIND +#define DIO82_WPORT PORTD +#define DIO82_DDR DDRD +#define DIO82_PWM NULL + +#define DIO83_PIN PIND6 +#define DIO83_RPORT PIND +#define DIO83_WPORT PORTD +#define DIO83_DDR DDRD +#define DIO83_PWM NULL + +#define DIO84_PIN PINH2 +#define DIO84_RPORT PINH +#define DIO84_WPORT PORTH +#define DIO84_DDR DDRH +#define DIO84_PWM NULL + +#define DIO85_PIN PINH7 +#define DIO85_RPORT PINH +#define DIO85_WPORT PORTH +#define DIO85_DDR DDRH +#define DIO85_PWM NULL + +#undef PA0 +#define PA0_PIN PINA0 +#define PA0_RPORT PINA +#define PA0_WPORT PORTA +#define PA0_DDR DDRA +#define PA0_PWM NULL +#undef PA1 +#define PA1_PIN PINA1 +#define PA1_RPORT PINA +#define PA1_WPORT PORTA +#define PA1_DDR DDRA +#define PA1_PWM NULL +#undef PA2 +#define PA2_PIN PINA2 +#define PA2_RPORT PINA +#define PA2_WPORT PORTA +#define PA2_DDR DDRA +#define PA2_PWM NULL +#undef PA3 +#define PA3_PIN PINA3 +#define PA3_RPORT PINA +#define PA3_WPORT PORTA +#define PA3_DDR DDRA +#define PA3_PWM NULL +#undef PA4 +#define PA4_PIN PINA4 +#define PA4_RPORT PINA +#define PA4_WPORT PORTA +#define PA4_DDR DDRA +#define PA4_PWM NULL +#undef PA5 +#define PA5_PIN PINA5 +#define PA5_RPORT PINA +#define PA5_WPORT PORTA +#define PA5_DDR DDRA +#define PA5_PWM NULL +#undef PA6 +#define PA6_PIN PINA6 +#define PA6_RPORT PINA +#define PA6_WPORT PORTA +#define PA6_DDR DDRA +#define PA6_PWM NULL +#undef PA7 +#define PA7_PIN PINA7 +#define PA7_RPORT PINA +#define PA7_WPORT PORTA +#define PA7_DDR DDRA +#define PA7_PWM NULL + +#undef PB0 +#define PB0_PIN PINB0 +#define PB0_RPORT PINB +#define PB0_WPORT PORTB +#define PB0_DDR DDRB +#define PB0_PWM NULL +#undef PB1 +#define PB1_PIN PINB1 +#define PB1_RPORT PINB +#define PB1_WPORT PORTB +#define PB1_DDR DDRB +#define PB1_PWM NULL +#undef PB2 +#define PB2_PIN PINB2 +#define PB2_RPORT PINB +#define PB2_WPORT PORTB +#define PB2_DDR DDRB +#define PB2_PWM NULL +#undef PB3 +#define PB3_PIN PINB3 +#define PB3_RPORT PINB +#define PB3_WPORT PORTB +#define PB3_DDR DDRB +#define PB3_PWM NULL +#undef PB4 +#define PB4_PIN PINB4 +#define PB4_RPORT PINB +#define PB4_WPORT PORTB +#define PB4_DDR DDRB +#define PB4_PWM &OCR2A +#undef PB5 +#define PB5_PIN PINB5 +#define PB5_RPORT PINB +#define PB5_WPORT PORTB +#define PB5_DDR DDRB +#define PB5_PWM NULL +#undef PB6 +#define PB6_PIN PINB6 +#define PB6_RPORT PINB +#define PB6_WPORT PORTB +#define PB6_DDR DDRB +#define PB6_PWM NULL +#undef PB7 +#define PB7_PIN PINB7 +#define PB7_RPORT PINB +#define PB7_WPORT PORTB +#define PB7_DDR DDRB +#define PB7_PWM &OCR0A + +#undef PC0 +#define PC0_PIN PINC0 +#define PC0_RPORT PINC +#define PC0_WPORT PORTC +#define PC0_DDR DDRC +#define PC0_PWM NULL +#undef PC1 +#define PC1_PIN PINC1 +#define PC1_RPORT PINC +#define PC1_WPORT PORTC +#define PC1_DDR DDRC +#define PC1_PWM NULL +#undef PC2 +#define PC2_PIN PINC2 +#define PC2_RPORT PINC +#define PC2_WPORT PORTC +#define PC2_DDR DDRC +#define PC2_PWM NULL +#undef PC3 +#define PC3_PIN PINC3 +#define PC3_RPORT PINC +#define PC3_WPORT PORTC +#define PC3_DDR DDRC +#define PC3_PWM NULL +#undef PC4 +#define PC4_PIN PINC4 +#define PC4_RPORT PINC +#define PC4_WPORT PORTC +#define PC4_DDR DDRC +#define PC4_PWM NULL +#undef PC5 +#define PC5_PIN PINC5 +#define PC5_RPORT PINC +#define PC5_WPORT PORTC +#define PC5_DDR DDRC +#define PC5_PWM NULL +#undef PC6 +#define PC6_PIN PINC6 +#define PC6_RPORT PINC +#define PC6_WPORT PORTC +#define PC6_DDR DDRC +#define PC6_PWM NULL +#undef PC7 +#define PC7_PIN PINC7 +#define PC7_RPORT PINC +#define PC7_WPORT PORTC +#define PC7_DDR DDRC +#define PC7_PWM NULL + +#undef PD0 +#define PD0_PIN PIND0 +#define PD0_RPORT PIND +#define PD0_WPORT PORTD +#define PD0_DDR DDRD +#define PD0_PWM NULL +#undef PD1 +#define PD1_PIN PIND1 +#define PD1_RPORT PIND +#define PD1_WPORT PORTD +#define PD1_DDR DDRD +#define PD1_PWM NULL +#undef PD2 +#define PD2_PIN PIND2 +#define PD2_RPORT PIND +#define PD2_WPORT PORTD +#define PD2_DDR DDRD +#define PD2_PWM NULL +#undef PD3 +#define PD3_PIN PIND3 +#define PD3_RPORT PIND +#define PD3_WPORT PORTD +#define PD3_DDR DDRD +#define PD3_PWM NULL +#undef PD4 +#define PD4_PIN PIND4 +#define PD4_RPORT PIND +#define PD4_WPORT PORTD +#define PD4_DDR DDRD +#define PD4_PWM NULL +#undef PD5 +#define PD5_PIN PIND5 +#define PD5_RPORT PIND +#define PD5_WPORT PORTD +#define PD5_DDR DDRD +#define PD5_PWM NULL +#undef PD6 +#define PD6_PIN PIND6 +#define PD6_RPORT PIND +#define PD6_WPORT PORTD +#define PD6_DDR DDRD +#define PD6_PWM NULL +#undef PD7 +#define PD7_PIN PIND7 +#define PD7_RPORT PIND +#define PD7_WPORT PORTD +#define PD7_DDR DDRD +#define PD7_PWM NULL + +#undef PE0 +#define PE0_PIN PINE0 +#define PE0_RPORT PINE +#define PE0_WPORT PORTE +#define PE0_DDR DDRE +#define PE0_PWM NULL +#undef PE1 +#define PE1_PIN PINE1 +#define PE1_RPORT PINE +#define PE1_WPORT PORTE +#define PE1_DDR DDRE +#define PE1_PWM NULL +#undef PE2 +#define PE2_PIN PINE2 +#define PE2_RPORT PINE +#define PE2_WPORT PORTE +#define PE2_DDR DDRE +#define PE2_PWM NULL +#undef PE3 +#define PE3_PIN PINE3 +#define PE3_RPORT PINE +#define PE3_WPORT PORTE +#define PE3_DDR DDRE +#define PE3_PWM &OCR3AL +#undef PE4 +#define PE4_PIN PINE4 +#define PE4_RPORT PINE +#define PE4_WPORT PORTE +#define PE4_DDR DDRE +#define PE4_PWM &OCR3BL +#undef PE5 +#define PE5_PIN PINE5 +#define PE5_RPORT PINE +#define PE5_WPORT PORTE +#define PE5_DDR DDRE +#define PE5_PWM &OCR3CL +#undef PE6 +#define PE6_PIN PINE6 +#define PE6_RPORT PINE +#define PE6_WPORT PORTE +#define PE6_DDR DDRE +#define PE6_PWM NULL +#undef PE7 +#define PE7_PIN PINE7 +#define PE7_RPORT PINE +#define PE7_WPORT PORTE +#define PE7_DDR DDRE +#define PE7_PWM NULL + +#undef PF0 +#define PF0_PIN PINF0 +#define PF0_RPORT PINF +#define PF0_WPORT PORTF +#define PF0_DDR DDRF +#define PF0_PWM NULL +#undef PF1 +#define PF1_PIN PINF1 +#define PF1_RPORT PINF +#define PF1_WPORT PORTF +#define PF1_DDR DDRF +#define PF1_PWM NULL +#undef PF2 +#define PF2_PIN PINF2 +#define PF2_RPORT PINF +#define PF2_WPORT PORTF +#define PF2_DDR DDRF +#define PF2_PWM NULL +#undef PF3 +#define PF3_PIN PINF3 +#define PF3_RPORT PINF +#define PF3_WPORT PORTF +#define PF3_DDR DDRF +#define PF3_PWM NULL +#undef PF4 +#define PF4_PIN PINF4 +#define PF4_RPORT PINF +#define PF4_WPORT PORTF +#define PF4_DDR DDRF +#define PF4_PWM NULL +#undef PF5 +#define PF5_PIN PINF5 +#define PF5_RPORT PINF +#define PF5_WPORT PORTF +#define PF5_DDR DDRF +#define PF5_PWM NULL +#undef PF6 +#define PF6_PIN PINF6 +#define PF6_RPORT PINF +#define PF6_WPORT PORTF +#define PF6_DDR DDRF +#define PF6_PWM NULL +#undef PF7 +#define PF7_PIN PINF7 +#define PF7_RPORT PINF +#define PF7_WPORT PORTF +#define PF7_DDR DDRF +#define PF7_PWM NULL + +#undef PG0 +#define PG0_PIN PING0 +#define PG0_RPORT PING +#define PG0_WPORT PORTG +#define PG0_DDR DDRG +#define PG0_PWM NULL +#undef PG1 +#define PG1_PIN PING1 +#define PG1_RPORT PING +#define PG1_WPORT PORTG +#define PG1_DDR DDRG +#define PG1_PWM NULL +#undef PG2 +#define PG2_PIN PING2 +#define PG2_RPORT PING +#define PG2_WPORT PORTG +#define PG2_DDR DDRG +#define PG2_PWM NULL +#undef PG3 +#define PG3_PIN PING3 +#define PG3_RPORT PING +#define PG3_WPORT PORTG +#define PG3_DDR DDRG +#define PG3_PWM NULL +#undef PG4 +#define PG4_PIN PING4 +#define PG4_RPORT PING +#define PG4_WPORT PORTG +#define PG4_DDR DDRG +#define PG4_PWM NULL +#undef PG5 +#define PG5_PIN PING5 +#define PG5_RPORT PING +#define PG5_WPORT PORTG +#define PG5_DDR DDRG +#define PG5_PWM &OCR0B + +#undef PH0 +#define PH0_PIN PINH0 +#define PH0_RPORT PINH +#define PH0_WPORT PORTH +#define PH0_DDR DDRH +#define PH0_PWM NULL +#undef PH1 +#define PH1_PIN PINH1 +#define PH1_RPORT PINH +#define PH1_WPORT PORTH +#define PH1_DDR DDRH +#define PH1_PWM NULL +#undef PH2 +#define PH2_PIN PINH2 +#define PH2_RPORT PINH +#define PH2_WPORT PORTH +#define PH2_DDR DDRH +#define PH2_PWM NULL +#undef PH3 +#define PH3_PIN PINH3 +#define PH3_RPORT PINH +#define PH3_WPORT PORTH +#define PH3_DDR DDRH +#define PH3_PWM &OCR4AL +#undef PH4 +#define PH4_PIN PINH4 +#define PH4_RPORT PINH +#define PH4_WPORT PORTH +#define PH4_DDR DDRH +#define PH4_PWM &OCR4BL +#undef PH5 +#define PH5_PIN PINH5 +#define PH5_RPORT PINH +#define PH5_WPORT PORTH +#define PH5_DDR DDRH +#define PH5_PWM &OCR4CL +#undef PH6 +#define PH6_PIN PINH6 +#define PH6_RPORT PINH +#define PH6_WPORT PORTH +#define PH6_DDR DDRH +#define PH6_PWM &OCR2B +#undef PH7 +#define PH7_PIN PINH7 +#define PH7_RPORT PINH +#define PH7_WPORT PORTH +#define PH7_DDR DDRH +#define PH7_PWM NULL + +#undef PJ0 +#define PJ0_PIN PINJ0 +#define PJ0_RPORT PINJ +#define PJ0_WPORT PORTJ +#define PJ0_DDR DDRJ +#define PJ0_PWM NULL +#undef PJ1 +#define PJ1_PIN PINJ1 +#define PJ1_RPORT PINJ +#define PJ1_WPORT PORTJ +#define PJ1_DDR DDRJ +#define PJ1_PWM NULL +#undef PJ2 +#define PJ2_PIN PINJ2 +#define PJ2_RPORT PINJ +#define PJ2_WPORT PORTJ +#define PJ2_DDR DDRJ +#define PJ2_PWM NULL +#undef PJ3 +#define PJ3_PIN PINJ3 +#define PJ3_RPORT PINJ +#define PJ3_WPORT PORTJ +#define PJ3_DDR DDRJ +#define PJ3_PWM NULL +#undef PJ4 +#define PJ4_PIN PINJ4 +#define PJ4_RPORT PINJ +#define PJ4_WPORT PORTJ +#define PJ4_DDR DDRJ +#define PJ4_PWM NULL +#undef PJ5 +#define PJ5_PIN PINJ5 +#define PJ5_RPORT PINJ +#define PJ5_WPORT PORTJ +#define PJ5_DDR DDRJ +#define PJ5_PWM NULL +#undef PJ6 +#define PJ6_PIN PINJ6 +#define PJ6_RPORT PINJ +#define PJ6_WPORT PORTJ +#define PJ6_DDR DDRJ +#define PJ6_PWM NULL +#undef PJ7 +#define PJ7_PIN PINJ7 +#define PJ7_RPORT PINJ +#define PJ7_WPORT PORTJ +#define PJ7_DDR DDRJ +#define PJ7_PWM NULL + +#undef PK0 +#define PK0_PIN PINK0 +#define PK0_RPORT PINK +#define PK0_WPORT PORTK +#define PK0_DDR DDRK +#define PK0_PWM NULL +#undef PK1 +#define PK1_PIN PINK1 +#define PK1_RPORT PINK +#define PK1_WPORT PORTK +#define PK1_DDR DDRK +#define PK1_PWM NULL +#undef PK2 +#define PK2_PIN PINK2 +#define PK2_RPORT PINK +#define PK2_WPORT PORTK +#define PK2_DDR DDRK +#define PK2_PWM NULL +#undef PK3 +#define PK3_PIN PINK3 +#define PK3_RPORT PINK +#define PK3_WPORT PORTK +#define PK3_DDR DDRK +#define PK3_PWM NULL +#undef PK4 +#define PK4_PIN PINK4 +#define PK4_RPORT PINK +#define PK4_WPORT PORTK +#define PK4_DDR DDRK +#define PK4_PWM NULL +#undef PK5 +#define PK5_PIN PINK5 +#define PK5_RPORT PINK +#define PK5_WPORT PORTK +#define PK5_DDR DDRK +#define PK5_PWM NULL +#undef PK6 +#define PK6_PIN PINK6 +#define PK6_RPORT PINK +#define PK6_WPORT PORTK +#define PK6_DDR DDRK +#define PK6_PWM NULL +#undef PK7 +#define PK7_PIN PINK7 +#define PK7_RPORT PINK +#define PK7_WPORT PORTK +#define PK7_DDR DDRK +#define PK7_PWM NULL + +#undef PL0 +#define PL0_PIN PINL0 +#define PL0_RPORT PINL +#define PL0_WPORT PORTL +#define PL0_DDR DDRL +#define PL0_PWM NULL +#undef PL1 +#define PL1_PIN PINL1 +#define PL1_RPORT PINL +#define PL1_WPORT PORTL +#define PL1_DDR DDRL +#define PL1_PWM NULL +#undef PL2 +#define PL2_PIN PINL2 +#define PL2_RPORT PINL +#define PL2_WPORT PORTL +#define PL2_DDR DDRL +#define PL2_PWM NULL +#undef PL3 +#define PL3_PIN PINL3 +#define PL3_RPORT PINL +#define PL3_WPORT PORTL +#define PL3_DDR DDRL +#define PL3_PWM &OCR5AL +#undef PL4 +#define PL4_PIN PINL4 +#define PL4_RPORT PINL +#define PL4_WPORT PORTL +#define PL4_DDR DDRL +#define PL4_PWM &OCR5BL +#undef PL5 +#define PL5_PIN PINL5 +#define PL5_RPORT PINL +#define PL5_WPORT PORTL +#define PL5_DDR DDRL +#define PL5_PWM &OCR5CL +#undef PL6 +#define PL6_PIN PINL6 +#define PL6_RPORT PINL +#define PL6_WPORT PORTL +#define PL6_DDR DDRL +#define PL6_PWM NULL +#undef PL7 +#define PL7_PIN PINL7 +#define PL7_RPORT PINL +#define PL7_WPORT PORTL +#define PL7_DDR DDRL +#define PL7_PWM NULL + +#endif // _FASTIO_1280 diff --git a/Marlin/fastio_1281.h b/Marlin/fastio_1281.h new file mode 100644 index 000000000..85d2c4ef7 --- /dev/null +++ b/Marlin/fastio_1281.h @@ -0,0 +1,720 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (C) 2016 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 . + * + */ + +/** + * Pin mapping for the 1281 and 2561 + * + * 1281 38 39 40 41 42 43 44 45 16 10 11 12 06 07 08 09 30 31 32 33 34 35 36 37 17 18 19 20 21 22 23 24 00 01 13 05 02 03 14 15 46 47 48 49 50 51 52 53 25 26 27 28 29 04 + * Port A0 A1 A2 A3 A4 A5 A6 A7 B0 B1 B2 B3 B4 B5 B6 B7 C0 C1 C2 C3 C4 C5 C6 C7 D0 D1 D2 D3 D4 D5 D6 D7 E0 E1 E2 E3 E4 E5 E6 E7 F0 F1 F2 F3 F4 F5 F6 F7 G0 G1 G2 G3 G4 G5 + * Marlin 00 01 02 03 04 05 06 07 08 09 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 + */ + +#ifndef _FASTIO_1281 +#define _FASTIO_1281 + +#include "fastio.h" + +// change for your board +#define DEBUG_LED DIO46 + +// UART +#define RXD DIO0 +#define TXD DIO1 + +// SPI +#define SCK DIO10 +#define MISO DIO12 +#define MOSI DIO11 +#define SS DIO16 + +// TWI (I2C) +#define SCL DIO17 +#define SDA DIO18 + +// Timers and PWM +#define OC0A DIO9 +#define OC0B DIO4 +#define OC1A DIO7 +#define OC1B DIO8 +#define OC2A DIO6 +#define OC3A DIO5 +#define OC3B DIO2 +#define OC3C DIO3 + +// Digital I/O + +#define DIO0_PIN PINE0 +#define DIO0_RPORT PINE +#define DIO0_WPORT PORTE +#define DIO0_DDR DDRE +#define DIO0_PWM NULL + +#define DIO1_PIN PINE1 +#define DIO1_RPORT PINE +#define DIO1_WPORT PORTE +#define DIO1_DDR DDRE +#define DIO1_PWM NULL + +#define DIO2_PIN PINE4 +#define DIO2_RPORT PINE +#define DIO2_WPORT PORTE +#define DIO2_DDR DDRE +#define DIO2_PWM &OCR3BL + +#define DIO3_PIN PINE5 +#define DIO3_RPORT PINE +#define DIO3_WPORT PORTE +#define DIO3_DDR DDRE +#define DIO3_PWM &OCR3CL + +#define DIO4_PIN PING5 +#define DIO4_RPORT PING +#define DIO4_WPORT PORTG +#define DIO4_DDR DDRG +#define DIO4_PWM &OCR0B + +#define DIO5_PIN PINE3 +#define DIO5_RPORT PINE +#define DIO5_WPORT PORTE +#define DIO5_DDR DDRE +#define DIO5_PWM &OCR3AL + +#define DIO6_PIN PINB4 +#define DIO6_RPORT PINB +#define DIO6_WPORT PORTB +#define DIO6_DDR DDRB +#define DIO6_PWM &OCR2AL + +#define DIO7_PIN PINB5 +#define DIO7_RPORT PINB +#define DIO7_WPORT PORTB +#define DIO7_DDR DDRB +#define DIO7_PWM &OCR1AL + +#define DIO8_PIN PINB6 +#define DIO8_RPORT PINB +#define DIO8_WPORT PORTB +#define DIO8_DDR DDRB +#define DIO8_PWM &OCR1BL + +#define DIO9_PIN PINB7 +#define DIO9_RPORT PINB +#define DIO9_WPORT PORTB +#define DIO9_DDR DDRB +#define DIO9_PWM &OCR0AL + +#define DIO10_PIN PINB1 +#define DIO10_RPORT PINB +#define DIO10_WPORT PORTB +#define DIO10_DDR DDRB +#define DIO10_PWM NULL + +#define DIO11_PIN PINB2 +#define DIO11_RPORT PINB +#define DIO11_WPORT PORTB +#define DIO11_DDR DDRB +#define DIO11_PWM NULL + +#define DIO12_PIN PINB3 +#define DIO12_RPORT PINB +#define DIO12_WPORT PORTB +#define DIO12_DDR DDRB +#define DIO12_PWM NULL + +#define DIO13_PIN PINE2 +#define DIO13_RPORT PINE +#define DIO13_WPORT PORTE +#define DIO13_DDR DDRE +#define DIO13_PWM NULL + +#define DIO14_PIN PINE6 +#define DIO14_RPORT PINE +#define DIO14_WPORT PORTE +#define DIO14_DDR DDRE +#define DIO14_PWM NULL + +#define DIO15_PIN PINE7 +#define DIO15_RPORT PINE +#define DIO15_WPORT PORTE +#define DIO15_DDR DDRE +#define DIO15_PWM NULL + +#define DIO16_PIN PINB0 +#define DIO16_RPORT PINB +#define DIO16_WPORT PORTB +#define DIO16_DDR DDRB +#define DIO16_PWM NULL + +#define DIO17_PIN PIND0 +#define DIO17_RPORT PIND +#define DIO17_WPORT PORTD +#define DIO17_DDR DDRD +#define DIO17_PWM NULL + +#define DIO18_PIN PIND1 +#define DIO18_RPORT PIND +#define DIO18_WPORT PORTD +#define DIO18_DDR DDRD +#define DIO18_PWM NULL + +#define DIO19_PIN PIND2 +#define DIO19_RPORT PIND +#define DIO19_WPORT PORTD +#define DIO19_DDR DDRD +#define DIO19_PWM NULL + +#define DIO20_PIN PIND3 +#define DIO20_RPORT PIND +#define DIO20_WPORT PORTD +#define DIO20_DDR DDRD +#define DIO20_PWM NULL + +#define DIO21_PIN PIND4 +#define DIO21_RPORT PIND +#define DIO21_WPORT PORTD +#define DIO21_DDR DDRD +#define DIO21_PWM NULL + +#define DIO22_PIN PIND5 +#define DIO22_RPORT PIND +#define DIO22_WPORT PORTD +#define DIO22_DDR DDRD +#define DIO22_PWM NULL + +#define DIO23_PIN PIND6 +#define DIO23_RPORT PIND +#define DIO23_WPORT PORTD +#define DIO23_DDR DDRD +#define DIO23_PWM NULL + +#define DIO24_PIN PIND7 +#define DIO24_RPORT PIND +#define DIO24_WPORT PORTD +#define DIO24_DDR DDRD +#define DIO24_PWM NULL + +#define DIO25_PIN PING0 +#define DIO25_RPORT PING +#define DIO25_WPORT PORTG +#define DIO25_DDR DDRG +#define DIO25_PWM NULL + +#define DIO26_PIN PING1 +#define DIO26_RPORT PING +#define DIO26_WPORT PORTG +#define DIO26_DDR DDRG +#define DIO26_PWM NULL + +#define DIO27_PIN PING2 +#define DIO27_RPORT PING +#define DIO27_WPORT PORTG +#define DIO27_DDR DDRG +#define DIO27_PWM NULL + +#define DIO28_PIN PING3 +#define DIO28_RPORT PING +#define DIO28_WPORT PORTG +#define DIO28_DDR DDRG +#define DIO28_PWM NULL + +#define DIO29_PIN PING4 +#define DIO29_RPORT PING +#define DIO29_WPORT PORTG +#define DIO29_DDR DDRG +#define DIO29_PWM NULL + +#define DIO30_PIN PINC0 +#define DIO30_RPORT PINC +#define DIO30_WPORT PORTC +#define DIO30_DDR DDRC +#define DIO30_PWM NULL + +#define DIO31_PIN PINC1 +#define DIO31_RPORT PINC +#define DIO31_WPORT PORTC +#define DIO31_DDR DDRC +#define DIO31_PWM NULL + +#define DIO32_PIN PINC2 +#define DIO32_RPORT PINC +#define DIO32_WPORT PORTC +#define DIO32_DDR DDRC +#define DIO32_PWM NULL + +#define DIO33_PIN PINC3 +#define DIO33_RPORT PINC +#define DIO33_WPORT PORTC +#define DIO33_DDR DDRC +#define DIO33_PWM NULL + +#define DIO34_PIN PINC4 +#define DIO34_RPORT PINC +#define DIO34_WPORT PORTC +#define DIO34_DDR DDRC +#define DIO34_PWM NULL + +#define DIO35_PIN PINC5 +#define DIO35_RPORT PINC +#define DIO35_WPORT PORTC +#define DIO35_DDR DDRC +#define DIO35_PWM NULL + +#define DIO36_PIN PINC6 +#define DIO36_RPORT PINC +#define DIO36_WPORT PORTC +#define DIO36_DDR DDRC +#define DIO36_PWM NULL + +#define DIO37_PIN PINC7 +#define DIO37_RPORT PINC +#define DIO37_WPORT PORTC +#define DIO37_DDR DDRC +#define DIO37_PWM NULL + +#define DIO38_PIN PINA0 +#define DIO38_RPORT PINA +#define DIO38_WPORT PORTA +#define DIO38_DDR DDRA +#define DIO38_PWM NULL + +#define DIO39_PIN PINA1 +#define DIO39_RPORT PINA +#define DIO39_WPORT PORTA +#define DIO39_DDR DDRA +#define DIO39_PWM NULL + +#define DIO40_PIN PINA2 +#define DIO40_RPORT PINA +#define DIO40_WPORT PORTA +#define DIO40_DDR DDRA +#define DIO40_PWM NULL + +#define DIO41_PIN PINA3 +#define DIO41_RPORT PINA +#define DIO41_WPORT PORTA +#define DIO41_DDR DDRA +#define DIO41_PWM NULL + +#define DIO42_PIN PINA4 +#define DIO42_RPORT PINA +#define DIO42_WPORT PORTA +#define DIO42_DDR DDRA +#define DIO42_PWM NULL + +#define DIO43_PIN PINA5 +#define DIO43_RPORT PINA +#define DIO43_WPORT PORTA +#define DIO43_DDR DDRA +#define DIO43_PWM NULL + +#define DIO44_PIN PINA6 +#define DIO44_RPORT PINA +#define DIO44_WPORT PORTA +#define DIO44_DDR DDRA +#define DIO44_PWM NULL + +#define DIO45_PIN PINA7 +#define DIO45_RPORT PINA +#define DIO45_WPORT PORTA +#define DIO45_DDR DDRA +#define DIO45_PWM NULL + +#define DIO46_PIN PINF0 +#define DIO46_RPORT PINF +#define DIO46_WPORT PORTF +#define DIO46_DDR DDRF +#define DIO46_PWM NULL + +#define DIO47_PIN PINF1 +#define DIO47_RPORT PINF +#define DIO47_WPORT PORTF +#define DIO47_DDR DDRF +#define DIO47_PWM NULL + +#define DIO48_PIN PINF2 +#define DIO48_RPORT PINF +#define DIO48_WPORT PORTF +#define DIO48_DDR DDRF +#define DIO48_PWM NULL + +#define DIO49_PIN PINF3 +#define DIO49_RPORT PINF +#define DIO49_WPORT PORTF +#define DIO49_DDR DDRF +#define DIO49_PWM NULL + +#define DIO50_PIN PINF4 +#define DIO50_RPORT PINF +#define DIO50_WPORT PORTF +#define DIO50_DDR DDRF +#define DIO50_PWM NULL + +#define DIO51_PIN PINF5 +#define DIO51_RPORT PINF +#define DIO51_WPORT PORTF +#define DIO51_DDR DDRF +#define DIO51_PWM NULL + +#define DIO52_PIN PINF6 +#define DIO52_RPORT PINF +#define DIO52_WPORT PORTF +#define DIO52_DDR DDRF +#define DIO52_PWM NULL + +#define DIO53_PIN PINF7 +#define DIO53_RPORT PINF +#define DIO53_WPORT PORTF +#define DIO53_DDR DDRF +#define DIO53_PWM NULL + +#undef PA0 +#define PA0_PIN PINA0 +#define PA0_RPORT PINA +#define PA0_WPORT PORTA +#define PA0_DDR DDRA +#define PA0_PWM NULL +#undef PA1 +#define PA1_PIN PINA1 +#define PA1_RPORT PINA +#define PA1_WPORT PORTA +#define PA1_DDR DDRA +#define PA1_PWM NULL +#undef PA2 +#define PA2_PIN PINA2 +#define PA2_RPORT PINA +#define PA2_WPORT PORTA +#define PA2_DDR DDRA +#define PA2_PWM NULL +#undef PA3 +#define PA3_PIN PINA3 +#define PA3_RPORT PINA +#define PA3_WPORT PORTA +#define PA3_DDR DDRA +#define PA3_PWM NULL +#undef PA4 +#define PA4_PIN PINA4 +#define PA4_RPORT PINA +#define PA4_WPORT PORTA +#define PA4_DDR DDRA +#define PA4_PWM NULL +#undef PA5 +#define PA5_PIN PINA5 +#define PA5_RPORT PINA +#define PA5_WPORT PORTA +#define PA5_DDR DDRA +#define PA5_PWM NULL +#undef PA6 +#define PA6_PIN PINA6 +#define PA6_RPORT PINA +#define PA6_WPORT PORTA +#define PA6_DDR DDRA +#define PA6_PWM NULL +#undef PA7 +#define PA7_PIN PINA7 +#define PA7_RPORT PINA +#define PA7_WPORT PORTA +#define PA7_DDR DDRA +#define PA7_PWM NULL + +#undef PB0 +#define PB0_PIN PINB0 +#define PB0_RPORT PINB +#define PB0_WPORT PORTB +#define PB0_DDR DDRB +#define PB0_PWM NULL +#undef PB1 +#define PB1_PIN PINB1 +#define PB1_RPORT PINB +#define PB1_WPORT PORTB +#define PB1_DDR DDRB +#define PB1_PWM NULL +#undef PB2 +#define PB2_PIN PINB2 +#define PB2_RPORT PINB +#define PB2_WPORT PORTB +#define PB2_DDR DDRB +#define PB2_PWM NULL +#undef PB3 +#define PB3_PIN PINB3 +#define PB3_RPORT PINB +#define PB3_WPORT PORTB +#define PB3_DDR DDRB +#define PB3_PWM NULL +#undef PB4 +#define PB4_PIN PINB4 +#define PB4_RPORT PINB +#define PB4_WPORT PORTB +#define PB4_DDR DDRB +#define PB4_PWM &OCR2A +#undef PB5 +#define PB5_PIN PINB5 +#define PB5_RPORT PINB +#define PB5_WPORT PORTB +#define PB5_DDR DDRB +#define PB5_PWM NULL +#undef PB6 +#define PB6_PIN PINB6 +#define PB6_RPORT PINB +#define PB6_WPORT PORTB +#define PB6_DDR DDRB +#define PB6_PWM NULL +#undef PB7 +#define PB7_PIN PINB7 +#define PB7_RPORT PINB +#define PB7_WPORT PORTB +#define PB7_DDR DDRB +#define PB7_PWM &OCR0A + +#undef PC0 +#define PC0_PIN PINC0 +#define PC0_RPORT PINC +#define PC0_WPORT PORTC +#define PC0_DDR DDRC +#define PC0_PWM NULL +#undef PC1 +#define PC1_PIN PINC1 +#define PC1_RPORT PINC +#define PC1_WPORT PORTC +#define PC1_DDR DDRC +#define PC1_PWM NULL +#undef PC2 +#define PC2_PIN PINC2 +#define PC2_RPORT PINC +#define PC2_WPORT PORTC +#define PC2_DDR DDRC +#define PC2_PWM NULL +#undef PC3 +#define PC3_PIN PINC3 +#define PC3_RPORT PINC +#define PC3_WPORT PORTC +#define PC3_DDR DDRC +#define PC3_PWM NULL +#undef PC4 +#define PC4_PIN PINC4 +#define PC4_RPORT PINC +#define PC4_WPORT PORTC +#define PC4_DDR DDRC +#define PC4_PWM NULL +#undef PC5 +#define PC5_PIN PINC5 +#define PC5_RPORT PINC +#define PC5_WPORT PORTC +#define PC5_DDR DDRC +#define PC5_PWM NULL +#undef PC6 +#define PC6_PIN PINC6 +#define PC6_RPORT PINC +#define PC6_WPORT PORTC +#define PC6_DDR DDRC +#define PC6_PWM NULL +#undef PC7 +#define PC7_PIN PINC7 +#define PC7_RPORT PINC +#define PC7_WPORT PORTC +#define PC7_DDR DDRC +#define PC7_PWM NULL + +#undef PD0 +#define PD0_PIN PIND0 +#define PD0_RPORT PIND +#define PD0_WPORT PORTD +#define PD0_DDR DDRD +#define PD0_PWM NULL +#undef PD1 +#define PD1_PIN PIND1 +#define PD1_RPORT PIND +#define PD1_WPORT PORTD +#define PD1_DDR DDRD +#define PD1_PWM NULL +#undef PD2 +#define PD2_PIN PIND2 +#define PD2_RPORT PIND +#define PD2_WPORT PORTD +#define PD2_DDR DDRD +#define PD2_PWM NULL +#undef PD3 +#define PD3_PIN PIND3 +#define PD3_RPORT PIND +#define PD3_WPORT PORTD +#define PD3_DDR DDRD +#define PD3_PWM NULL +#undef PD4 +#define PD4_PIN PIND4 +#define PD4_RPORT PIND +#define PD4_WPORT PORTD +#define PD4_DDR DDRD +#define PD4_PWM NULL +#undef PD5 +#define PD5_PIN PIND5 +#define PD5_RPORT PIND +#define PD5_WPORT PORTD +#define PD5_DDR DDRD +#define PD5_PWM NULL +#undef PD6 +#define PD6_PIN PIND6 +#define PD6_RPORT PIND +#define PD6_WPORT PORTD +#define PD6_DDR DDRD +#define PD6_PWM NULL +#undef PD7 +#define PD7_PIN PIND7 +#define PD7_RPORT PIND +#define PD7_WPORT PORTD +#define PD7_DDR DDRD +#define PD7_PWM NULL + +#undef PE0 +#define PE0_PIN PINE0 +#define PE0_RPORT PINE +#define PE0_WPORT PORTE +#define PE0_DDR DDRE +#define PE0_PWM NULL +#undef PE1 +#define PE1_PIN PINE1 +#define PE1_RPORT PINE +#define PE1_WPORT PORTE +#define PE1_DDR DDRE +#define PE1_PWM NULL +#undef PE2 +#define PE2_PIN PINE2 +#define PE2_RPORT PINE +#define PE2_WPORT PORTE +#define PE2_DDR DDRE +#define PE2_PWM NULL +#undef PE3 +#define PE3_PIN PINE3 +#define PE3_RPORT PINE +#define PE3_WPORT PORTE +#define PE3_DDR DDRE +#define PE3_PWM &OCR3AL +#undef PE4 +#define PE4_PIN PINE4 +#define PE4_RPORT PINE +#define PE4_WPORT PORTE +#define PE4_DDR DDRE +#define PE4_PWM &OCR3BL +#undef PE5 +#define PE5_PIN PINE5 +#define PE5_RPORT PINE +#define PE5_WPORT PORTE +#define PE5_DDR DDRE +#define PE5_PWM &OCR3CL +#undef PE6 +#define PE6_PIN PINE6 +#define PE6_RPORT PINE +#define PE6_WPORT PORTE +#define PE6_DDR DDRE +#define PE6_PWM NULL +#undef PE7 +#define PE7_PIN PINE7 +#define PE7_RPORT PINE +#define PE7_WPORT PORTE +#define PE7_DDR DDRE +#define PE7_PWM NULL + +#undef PF0 +#define PF0_PIN PINF0 +#define PF0_RPORT PINF +#define PF0_WPORT PORTF +#define PF0_DDR DDRF +#define PF0_PWM NULL +#undef PF1 +#define PF1_PIN PINF1 +#define PF1_RPORT PINF +#define PF1_WPORT PORTF +#define PF1_DDR DDRF +#define PF1_PWM NULL +#undef PF2 +#define PF2_PIN PINF2 +#define PF2_RPORT PINF +#define PF2_WPORT PORTF +#define PF2_DDR DDRF +#define PF2_PWM NULL +#undef PF3 +#define PF3_PIN PINF3 +#define PF3_RPORT PINF +#define PF3_WPORT PORTF +#define PF3_DDR DDRF +#define PF3_PWM NULL +#undef PF4 +#define PF4_PIN PINF4 +#define PF4_RPORT PINF +#define PF4_WPORT PORTF +#define PF4_DDR DDRF +#define PF4_PWM NULL +#undef PF5 +#define PF5_PIN PINF5 +#define PF5_RPORT PINF +#define PF5_WPORT PORTF +#define PF5_DDR DDRF +#define PF5_PWM NULL +#undef PF6 +#define PF6_PIN PINF6 +#define PF6_RPORT PINF +#define PF6_WPORT PORTF +#define PF6_DDR DDRF +#define PF6_PWM NULL +#undef PF7 +#define PF7_PIN PINF7 +#define PF7_RPORT PINF +#define PF7_WPORT PORTF +#define PF7_DDR DDRF +#define PF7_PWM NULL + +#undef PG0 +#define PG0_PIN PING0 +#define PG0_RPORT PING +#define PG0_WPORT PORTG +#define PG0_DDR DDRG +#define PG0_PWM NULL +#undef PG1 +#define PG1_PIN PING1 +#define PG1_RPORT PING +#define PG1_WPORT PORTG +#define PG1_DDR DDRG +#define PG1_PWM NULL +#undef PG2 +#define PG2_PIN PING2 +#define PG2_RPORT PING +#define PG2_WPORT PORTG +#define PG2_DDR DDRG +#define PG2_PWM NULL +#undef PG3 +#define PG3_PIN PING3 +#define PG3_RPORT PING +#define PG3_WPORT PORTG +#define PG3_DDR DDRG +#define PG3_PWM NULL +#undef PG4 +#define PG4_PIN PING4 +#define PG4_RPORT PING +#define PG4_WPORT PORTG +#define PG4_DDR DDRG +#define PG4_PWM NULL +#undef PG5 +#define PG5_PIN PING5 +#define PG5_RPORT PING +#define PG5_WPORT PORTG +#define PG5_DDR DDRG +#define PG5_PWM &OCR0B + +#endif // _FASTIO_1281 diff --git a/Marlin/fastio_168.h b/Marlin/fastio_168.h new file mode 100644 index 000000000..4ee67a32b --- /dev/null +++ b/Marlin/fastio_168.h @@ -0,0 +1,362 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (C) 2016 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 . + * + */ + +/** + * Pin mapping for the 168, 328, and 328P + * + * 168 08 09 10 11 12 13 14 15 16 17 18 19 20 21 00 01 02 03 04 05 06 07 + * Port B0 B1 B2 B3 B4 B5 C0 C1 C2 C3 C4 C5 C6 C7 D0 D1 D2 D3 D4 D5 D6 D7 + * Marlin 08 09 10 11 12 13 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 + */ + +#ifndef _FASTIO_168 +#define _FASTIO_168 + +#include "fastio.h" + +#define DEBUG_LED AIO5 + +// UART +#define RXD DIO0 +#define TXD DIO1 + +// SPI +#define SCK DIO13 +#define MISO DIO12 +#define MOSI DIO11 +#define SS DIO10 + +// TWI (I2C) +#define SCL AIO5 +#define SDA AIO4 + +// Timers and PWM +#define OC0A DIO6 +#define OC0B DIO5 +#define OC1A DIO9 +#define OC1B DIO10 +#define OC2A DIO11 +#define OC2B DIO3 + +// Digital I/O + +#define DIO0_PIN PIND0 +#define DIO0_RPORT PIND +#define DIO0_WPORT PORTD +#define DIO0_DDR DDRD +#define DIO0_PWM NULL + +#define DIO1_PIN PIND1 +#define DIO1_RPORT PIND +#define DIO1_WPORT PORTD +#define DIO1_DDR DDRD +#define DIO1_PWM NULL + +#define DIO2_PIN PIND2 +#define DIO2_RPORT PIND +#define DIO2_WPORT PORTD +#define DIO2_DDR DDRD +#define DIO2_PWM NULL + +#define DIO3_PIN PIND3 +#define DIO3_RPORT PIND +#define DIO3_WPORT PORTD +#define DIO3_DDR DDRD +#define DIO3_PWM &OCR2B + +#define DIO4_PIN PIND4 +#define DIO4_RPORT PIND +#define DIO4_WPORT PORTD +#define DIO4_DDR DDRD +#define DIO4_PWM NULL + +#define DIO5_PIN PIND5 +#define DIO5_RPORT PIND +#define DIO5_WPORT PORTD +#define DIO5_DDR DDRD +#define DIO5_PWM &OCR0B + +#define DIO6_PIN PIND6 +#define DIO6_RPORT PIND +#define DIO6_WPORT PORTD +#define DIO6_DDR DDRD +#define DIO6_PWM &OCR0A + +#define DIO7_PIN PIND7 +#define DIO7_RPORT PIND +#define DIO7_WPORT PORTD +#define DIO7_DDR DDRD +#define DIO7_PWM NULL + +#define DIO8_PIN PINB0 +#define DIO8_RPORT PINB +#define DIO8_WPORT PORTB +#define DIO8_DDR DDRB +#define DIO8_PWM NULL + +#define DIO9_PIN PINB1 +#define DIO9_RPORT PINB +#define DIO9_WPORT PORTB +#define DIO9_DDR DDRB +#define DIO9_PWM NULL + +#define DIO10_PIN PINB2 +#define DIO10_RPORT PINB +#define DIO10_WPORT PORTB +#define DIO10_DDR DDRB +#define DIO10_PWM NULL + +#define DIO11_PIN PINB3 +#define DIO11_RPORT PINB +#define DIO11_WPORT PORTB +#define DIO11_DDR DDRB +#define DIO11_PWM &OCR2A + +#define DIO12_PIN PINB4 +#define DIO12_RPORT PINB +#define DIO12_WPORT PORTB +#define DIO12_DDR DDRB +#define DIO12_PWM NULL + +#define DIO13_PIN PINB5 +#define DIO13_RPORT PINB +#define DIO13_WPORT PORTB +#define DIO13_DDR DDRB +#define DIO13_PWM NULL + +#define DIO14_PIN PINC0 +#define DIO14_RPORT PINC +#define DIO14_WPORT PORTC +#define DIO14_DDR DDRC +#define DIO14_PWM NULL + +#define DIO15_PIN PINC1 +#define DIO15_RPORT PINC +#define DIO15_WPORT PORTC +#define DIO15_DDR DDRC +#define DIO15_PWM NULL + +#define DIO16_PIN PINC2 +#define DIO16_RPORT PINC +#define DIO16_WPORT PORTC +#define DIO16_DDR DDRC +#define DIO16_PWM NULL + +#define DIO17_PIN PINC3 +#define DIO17_RPORT PINC +#define DIO17_WPORT PORTC +#define DIO17_DDR DDRC +#define DIO17_PWM NULL + +#define DIO18_PIN PINC4 +#define DIO18_RPORT PINC +#define DIO18_WPORT PORTC +#define DIO18_DDR DDRC +#define DIO18_PWM NULL + +#define DIO19_PIN PINC5 +#define DIO19_RPORT PINC +#define DIO19_WPORT PORTC +#define DIO19_DDR DDRC +#define DIO19_PWM NULL + +#define DIO20_PIN PINC6 +#define DIO20_RPORT PINC +#define DIO20_WPORT PORTC +#define DIO20_DDR DDRC +#define DIO20_PWM NULL + +#define DIO21_PIN PINC7 +#define DIO21_RPORT PINC +#define DIO21_WPORT PORTC +#define DIO21_DDR DDRC +#define DIO21_PWM NULL + +#undef PB0 +#define PB0_PIN PINB0 +#define PB0_RPORT PINB +#define PB0_WPORT PORTB +#define PB0_DDR DDRB +#define PB0_PWM NULL + +#undef PB1 +#define PB1_PIN PINB1 +#define PB1_RPORT PINB +#define PB1_WPORT PORTB +#define PB1_DDR DDRB +#define PB1_PWM NULL + +#undef PB2 +#define PB2_PIN PINB2 +#define PB2_RPORT PINB +#define PB2_WPORT PORTB +#define PB2_DDR DDRB +#define PB2_PWM NULL + +#undef PB3 +#define PB3_PIN PINB3 +#define PB3_RPORT PINB +#define PB3_WPORT PORTB +#define PB3_DDR DDRB +#define PB3_PWM &OCR2A + +#undef PB4 +#define PB4_PIN PINB4 +#define PB4_RPORT PINB +#define PB4_WPORT PORTB +#define PB4_DDR DDRB +#define PB4_PWM NULL + +#undef PB5 +#define PB5_PIN PINB5 +#define PB5_RPORT PINB +#define PB5_WPORT PORTB +#define PB5_DDR DDRB +#define PB5_PWM NULL + +#undef PB6 +#define PB6_PIN PINB6 +#define PB6_RPORT PINB +#define PB6_WPORT PORTB +#define PB6_DDR DDRB +#define PB6_PWM NULL + +#undef PB7 +#define PB7_PIN PINB7 +#define PB7_RPORT PINB +#define PB7_WPORT PORTB +#define PB7_DDR DDRB +#define PB7_PWM NULL + +#undef PC0 +#define PC0_PIN PINC0 +#define PC0_RPORT PINC +#define PC0_WPORT PORTC +#define PC0_DDR DDRC +#define PC0_PWM NULL + +#undef PC1 +#define PC1_PIN PINC1 +#define PC1_RPORT PINC +#define PC1_WPORT PORTC +#define PC1_DDR DDRC +#define PC1_PWM NULL + +#undef PC2 +#define PC2_PIN PINC2 +#define PC2_RPORT PINC +#define PC2_WPORT PORTC +#define PC2_DDR DDRC +#define PC2_PWM NULL + +#undef PC3 +#define PC3_PIN PINC3 +#define PC3_RPORT PINC +#define PC3_WPORT PORTC +#define PC3_DDR DDRC +#define PC3_PWM NULL + +#undef PC4 +#define PC4_PIN PINC4 +#define PC4_RPORT PINC +#define PC4_WPORT PORTC +#define PC4_DDR DDRC +#define PC4_PWM NULL + +#undef PC5 +#define PC5_PIN PINC5 +#define PC5_RPORT PINC +#define PC5_WPORT PORTC +#define PC5_DDR DDRC +#define PC5_PWM NULL + +#undef PC6 +#define PC6_PIN PINC6 +#define PC6_RPORT PINC +#define PC6_WPORT PORTC +#define PC6_DDR DDRC +#define PC6_PWM NULL + +#undef PC7 +#define PC7_PIN PINC7 +#define PC7_RPORT PINC +#define PC7_WPORT PORTC +#define PC7_DDR DDRC +#define PC7_PWM NULL + +#undef PD0 +#define PD0_PIN PIND0 +#define PD0_RPORT PIND +#define PD0_WPORT PORTD +#define PD0_DDR DDRD +#define PD0_PWM NULL + +#undef PD1 +#define PD1_PIN PIND1 +#define PD1_RPORT PIND +#define PD1_WPORT PORTD +#define PD1_DDR DDRD +#define PD1_PWM NULL + +#undef PD2 +#define PD2_PIN PIND2 +#define PD2_RPORT PIND +#define PD2_WPORT PORTD +#define PD2_DDR DDRD +#define PD2_PWM NULL + +#undef PD3 +#define PD3_PIN PIND3 +#define PD3_RPORT PIND +#define PD3_WPORT PORTD +#define PD3_DDR DDRD +#define PD3_PWM &OCR2B + +#undef PD4 +#define PD4_PIN PIND4 +#define PD4_RPORT PIND +#define PD4_WPORT PORTD +#define PD4_DDR DDRD +#define PD4_PWM NULL + +#undef PD5 +#define PD5_PIN PIND5 +#define PD5_RPORT PIND +#define PD5_WPORT PORTD +#define PD5_DDR DDRD +#define PD5_PWM &OCR0B + +#undef PD6 +#define PD6_PIN PIND6 +#define PD6_RPORT PIND +#define PD6_WPORT PORTD +#define PD6_DDR DDRD +#define PD6_PWM &OCR0A + +#undef PD7 +#define PD7_PIN PIND7 +#define PD7_RPORT PIND +#define PD7_WPORT PORTD +#define PD7_DDR DDRD +#define PD7_PWM NULL + +#endif // _FASTIO_168 diff --git a/Marlin/fastio_644.h b/Marlin/fastio_644.h new file mode 100644 index 000000000..6465738d0 --- /dev/null +++ b/Marlin/fastio_644.h @@ -0,0 +1,531 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (C) 2016 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 . + * + */ + +/** + * Pin mapping for the 644, 644p, 644pa, and 1284p + * + * 644p 31 30 29 28 27 26 25 24 00 01 02 03 04 05 06 07 16 17 18 19 20 21 22 23 08 09 10 11 12 13 14 15 + * Port A0 A1 A2 A3 A4 A5 A6 A7 B0 B1 B2 B3 B4 B5 B6 B7 C0 C1 C2 C3 C4 C5 C6 C7 D0 D1 D2 D3 D4 D5 D6 D7 + * Marlin 00 01 02 03 04 05 06 07 08 09 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 + */ + +#ifndef _FASTIO_644 +#define _FASTIO_644 + +#include "fastio.h" + +#define DEBUG_LED DIO0 + +// UART +#define RXD DIO8 +#define TXD DIO9 +#define RXD0 DIO8 +#define TXD0 DIO9 + +#define RXD1 DIO10 +#define TXD1 DIO11 + +// SPI +#define SCK DIO7 +#define MISO DIO6 +#define MOSI DIO5 +#define SS DIO4 + +// TWI (I2C) +#define SCL DIO16 +#define SDA DIO17 + +// Timers and PWM +#define OC0A DIO3 +#define OC0B DIO4 +#define OC1A DIO13 +#define OC1B DIO12 +#define OC2A DIO15 +#define OC2B DIO14 + +// Digital I/O + +#define DIO0_PIN PINB0 +#define DIO0_RPORT PINB +#define DIO0_WPORT PORTB +#define DIO0_DDR DDRB +#define DIO0_PWM NULL + +#define DIO1_PIN PINB1 +#define DIO1_RPORT PINB +#define DIO1_WPORT PORTB +#define DIO1_DDR DDRB +#define DIO1_PWM NULL + +#define DIO2_PIN PINB2 +#define DIO2_RPORT PINB +#define DIO2_WPORT PORTB +#define DIO2_DDR DDRB +#define DIO2_PWM NULL + +#define DIO3_PIN PINB3 +#define DIO3_RPORT PINB +#define DIO3_WPORT PORTB +#define DIO3_DDR DDRB +#define DIO3_PWM OCR0A + +#define DIO4_PIN PINB4 +#define DIO4_RPORT PINB +#define DIO4_WPORT PORTB +#define DIO4_DDR DDRB +#define DIO4_PWM OCR0B + +#define DIO5_PIN PINB5 +#define DIO5_RPORT PINB +#define DIO5_WPORT PORTB +#define DIO5_DDR DDRB +#define DIO5_PWM NULL + +#define DIO6_PIN PINB6 +#define DIO6_RPORT PINB +#define DIO6_WPORT PORTB +#define DIO6_DDR DDRB +#define DIO6_PWM NULL + +#define DIO7_PIN PINB7 +#define DIO7_RPORT PINB +#define DIO7_WPORT PORTB +#define DIO7_DDR DDRB +#define DIO7_PWM NULL + +#define DIO8_PIN PIND0 +#define DIO8_RPORT PIND +#define DIO8_WPORT PORTD +#define DIO8_DDR DDRD +#define DIO8_PWM NULL + +#define DIO9_PIN PIND1 +#define DIO9_RPORT PIND +#define DIO9_WPORT PORTD +#define DIO9_DDR DDRD +#define DIO9_PWM NULL + +#define DIO10_PIN PIND2 +#define DIO10_RPORT PIND +#define DIO10_WPORT PORTD +#define DIO10_DDR DDRD +#define DIO10_PWM NULL + +#define DIO11_PIN PIND3 +#define DIO11_RPORT PIND +#define DIO11_WPORT PORTD +#define DIO11_DDR DDRD +#define DIO11_PWM NULL + +#define DIO12_PIN PIND4 +#define DIO12_RPORT PIND +#define DIO12_WPORT PORTD +#define DIO12_DDR DDRD +#define DIO12_PWM OCR1B + +#define DIO13_PIN PIND5 +#define DIO13_RPORT PIND +#define DIO13_WPORT PORTD +#define DIO13_DDR DDRD +#define DIO13_PWM OCR1A + +#define DIO14_PIN PIND6 +#define DIO14_RPORT PIND +#define DIO14_WPORT PORTD +#define DIO14_DDR DDRD +#define DIO14_PWM OCR2B + +#define DIO15_PIN PIND7 +#define DIO15_RPORT PIND +#define DIO15_WPORT PORTD +#define DIO15_DDR DDRD +#define DIO15_PWM OCR2A + +#define DIO16_PIN PINC0 +#define DIO16_RPORT PINC +#define DIO16_WPORT PORTC +#define DIO16_DDR DDRC +#define DIO16_PWM NULL + +#define DIO17_PIN PINC1 +#define DIO17_RPORT PINC +#define DIO17_WPORT PORTC +#define DIO17_DDR DDRC +#define DIO17_PWM NULL + +#define DIO18_PIN PINC2 +#define DIO18_RPORT PINC +#define DIO18_WPORT PORTC +#define DIO18_DDR DDRC +#define DIO18_PWM NULL + +#define DIO19_PIN PINC3 +#define DIO19_RPORT PINC +#define DIO19_WPORT PORTC +#define DIO19_DDR DDRC +#define DIO19_PWM NULL + +#define DIO20_PIN PINC4 +#define DIO20_RPORT PINC +#define DIO20_WPORT PORTC +#define DIO20_DDR DDRC +#define DIO20_PWM NULL + +#define DIO21_PIN PINC5 +#define DIO21_RPORT PINC +#define DIO21_WPORT PORTC +#define DIO21_DDR DDRC +#define DIO21_PWM NULL + +#define DIO22_PIN PINC6 +#define DIO22_RPORT PINC +#define DIO22_WPORT PORTC +#define DIO22_DDR DDRC +#define DIO22_PWM NULL + +#define DIO23_PIN PINC7 +#define DIO23_RPORT PINC +#define DIO23_WPORT PORTC +#define DIO23_DDR DDRC +#define DIO23_PWM NULL + +#define DIO24_PIN PINA7 +#define DIO24_RPORT PINA +#define DIO24_WPORT PORTA +#define DIO24_DDR DDRA +#define DIO24_PWM NULL + +#define DIO25_PIN PINA6 +#define DIO25_RPORT PINA +#define DIO25_WPORT PORTA +#define DIO25_DDR DDRA +#define DIO25_PWM NULL + +#define DIO26_PIN PINA5 +#define DIO26_RPORT PINA +#define DIO26_WPORT PORTA +#define DIO26_DDR DDRA +#define DIO26_PWM NULL + +#define DIO27_PIN PINA4 +#define DIO27_RPORT PINA +#define DIO27_WPORT PORTA +#define DIO27_DDR DDRA +#define DIO27_PWM NULL + +#define DIO28_PIN PINA3 +#define DIO28_RPORT PINA +#define DIO28_WPORT PORTA +#define DIO28_DDR DDRA +#define DIO28_PWM NULL + +#define DIO29_PIN PINA2 +#define DIO29_RPORT PINA +#define DIO29_WPORT PORTA +#define DIO29_DDR DDRA +#define DIO29_PWM NULL + +#define DIO30_PIN PINA1 +#define DIO30_RPORT PINA +#define DIO30_WPORT PORTA +#define DIO30_DDR DDRA +#define DIO30_PWM NULL + +#define DIO31_PIN PINA0 +#define DIO31_RPORT PINA +#define DIO31_WPORT PORTA +#define DIO31_DDR DDRA +#define DIO31_PWM NULL + +#define AIO0_PIN PINA0 +#define AIO0_RPORT PINA +#define AIO0_WPORT PORTA +#define AIO0_DDR DDRA +#define AIO0_PWM NULL + +#define AIO1_PIN PINA1 +#define AIO1_RPORT PINA +#define AIO1_WPORT PORTA +#define AIO1_DDR DDRA +#define AIO1_PWM NULL + +#define AIO2_PIN PINA2 +#define AIO2_RPORT PINA +#define AIO2_WPORT PORTA +#define AIO2_DDR DDRA +#define AIO2_PWM NULL + +#define AIO3_PIN PINA3 +#define AIO3_RPORT PINA +#define AIO3_WPORT PORTA +#define AIO3_DDR DDRA +#define AIO3_PWM NULL + +#define AIO4_PIN PINA4 +#define AIO4_RPORT PINA +#define AIO4_WPORT PORTA +#define AIO4_DDR DDRA +#define AIO4_PWM NULL + +#define AIO5_PIN PINA5 +#define AIO5_RPORT PINA +#define AIO5_WPORT PORTA +#define AIO5_DDR DDRA +#define AIO5_PWM NULL + +#define AIO6_PIN PINA6 +#define AIO6_RPORT PINA +#define AIO6_WPORT PORTA +#define AIO6_DDR DDRA +#define AIO6_PWM NULL + +#define AIO7_PIN PINA7 +#define AIO7_RPORT PINA +#define AIO7_WPORT PORTA +#define AIO7_DDR DDRA +#define AIO7_PWM NULL + +#undef PA0 +#define PA0_PIN PINA0 +#define PA0_RPORT PINA +#define PA0_WPORT PORTA +#define PA0_DDR DDRA +#define PA0_PWM NULL + +#undef PA1 +#define PA1_PIN PINA1 +#define PA1_RPORT PINA +#define PA1_WPORT PORTA +#define PA1_DDR DDRA +#define PA1_PWM NULL + +#undef PA2 +#define PA2_PIN PINA2 +#define PA2_RPORT PINA +#define PA2_WPORT PORTA +#define PA2_DDR DDRA +#define PA2_PWM NULL + +#undef PA3 +#define PA3_PIN PINA3 +#define PA3_RPORT PINA +#define PA3_WPORT PORTA +#define PA3_DDR DDRA +#define PA3_PWM NULL + +#undef PA4 +#define PA4_PIN PINA4 +#define PA4_RPORT PINA +#define PA4_WPORT PORTA +#define PA4_DDR DDRA +#define PA4_PWM NULL + +#undef PA5 +#define PA5_PIN PINA5 +#define PA5_RPORT PINA +#define PA5_WPORT PORTA +#define PA5_DDR DDRA +#define PA5_PWM NULL + +#undef PA6 +#define PA6_PIN PINA6 +#define PA6_RPORT PINA +#define PA6_WPORT PORTA +#define PA6_DDR DDRA +#define PA6_PWM NULL + +#undef PA7 +#define PA7_PIN PINA7 +#define PA7_RPORT PINA +#define PA7_WPORT PORTA +#define PA7_DDR DDRA +#define PA7_PWM NULL + +#undef PB0 +#define PB0_PIN PINB0 +#define PB0_RPORT PINB +#define PB0_WPORT PORTB +#define PB0_DDR DDRB +#define PB0_PWM NULL + +#undef PB1 +#define PB1_PIN PINB1 +#define PB1_RPORT PINB +#define PB1_WPORT PORTB +#define PB1_DDR DDRB +#define PB1_PWM NULL + +#undef PB2 +#define PB2_PIN PINB2 +#define PB2_RPORT PINB +#define PB2_WPORT PORTB +#define PB2_DDR DDRB +#define PB2_PWM NULL + +#undef PB3 +#define PB3_PIN PINB3 +#define PB3_RPORT PINB +#define PB3_WPORT PORTB +#define PB3_DDR DDRB +#define PB3_PWM OCR0A + +#undef PB4 +#define PB4_PIN PINB4 +#define PB4_RPORT PINB +#define PB4_WPORT PORTB +#define PB4_DDR DDRB +#define PB4_PWM OCR0B + +#undef PB5 +#define PB5_PIN PINB5 +#define PB5_RPORT PINB +#define PB5_WPORT PORTB +#define PB5_DDR DDRB +#define PB5_PWM NULL + +#undef PB6 +#define PB6_PIN PINB6 +#define PB6_RPORT PINB +#define PB6_WPORT PORTB +#define PB6_DDR DDRB +#define PB6_PWM NULL + +#undef PB7 +#define PB7_PIN PINB7 +#define PB7_RPORT PINB +#define PB7_WPORT PORTB +#define PB7_DDR DDRB +#define PB7_PWM NULL + +#undef PC0 +#define PC0_PIN PINC0 +#define PC0_RPORT PINC +#define PC0_WPORT PORTC +#define PC0_DDR DDRC +#define PC0_PWM NULL + +#undef PC1 +#define PC1_PIN PINC1 +#define PC1_RPORT PINC +#define PC1_WPORT PORTC +#define PC1_DDR DDRC +#define PC1_PWM NULL + +#undef PC2 +#define PC2_PIN PINC2 +#define PC2_RPORT PINC +#define PC2_WPORT PORTC +#define PC2_DDR DDRC +#define PC2_PWM NULL + +#undef PC3 +#define PC3_PIN PINC3 +#define PC3_RPORT PINC +#define PC3_WPORT PORTC +#define PC3_DDR DDRC +#define PC3_PWM NULL + +#undef PC4 +#define PC4_PIN PINC4 +#define PC4_RPORT PINC +#define PC4_WPORT PORTC +#define PC4_DDR DDRC +#define PC4_PWM NULL + +#undef PC5 +#define PC5_PIN PINC5 +#define PC5_RPORT PINC +#define PC5_WPORT PORTC +#define PC5_DDR DDRC +#define PC5_PWM NULL + +#undef PC6 +#define PC6_PIN PINC6 +#define PC6_RPORT PINC +#define PC6_WPORT PORTC +#define PC6_DDR DDRC +#define PC6_PWM NULL + +#undef PC7 +#define PC7_PIN PINC7 +#define PC7_RPORT PINC +#define PC7_WPORT PORTC +#define PC7_DDR DDRC +#define PC7_PWM NULL + +#undef PD0 +#define PD0_PIN PIND0 +#define PD0_RPORT PIND +#define PD0_WPORT PORTD +#define PD0_DDR DDRD +#define PD0_PWM NULL + +#undef PD1 +#define PD1_PIN PIND1 +#define PD1_RPORT PIND +#define PD1_WPORT PORTD +#define PD1_DDR DDRD +#define PD1_PWM NULL + +#undef PD2 +#define PD2_PIN PIND2 +#define PD2_RPORT PIND +#define PD2_WPORT PORTD +#define PD2_DDR DDRD +#define PD2_PWM NULL + +#undef PD3 +#define PD3_PIN PIND3 +#define PD3_RPORT PIND +#define PD3_WPORT PORTD +#define PD3_DDR DDRD +#define PD3_PWM NULL + +#undef PD4 +#define PD4_PIN PIND4 +#define PD4_RPORT PIND +#define PD4_WPORT PORTD +#define PD4_DDR DDRD +#define PD4_PWM NULL + +#undef PD5 +#define PD5_PIN PIND5 +#define PD5_RPORT PIND +#define PD5_WPORT PORTD +#define PD5_DDR DDRD +#define PD5_PWM NULL + +#undef PD6 +#define PD6_PIN PIND6 +#define PD6_RPORT PIND +#define PD6_WPORT PORTD +#define PD6_DDR DDRD +#define PD6_PWM OCR2B + +#undef PD7 +#define PD7_PIN PIND7 +#define PD7_RPORT PIND +#define PD7_WPORT PORTD +#define PD7_DDR DDRD +#define PD7_PWM OCR2A + +#endif // _FASTIO_644 diff --git a/Marlin/fastio_AT90USB-Marlin.h b/Marlin/fastio_AT90USB-Marlin.h new file mode 100644 index 000000000..955da40c4 --- /dev/null +++ b/Marlin/fastio_AT90USB-Marlin.h @@ -0,0 +1,681 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (C) 2016 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 . + * + */ + +/** + * Pin mapping (Marlin) for AT90USB646, 647, 1286, and 1287 + * + * AT90USB 51 50 49 48 47 46 45 44 10 11 12 13 14 15 16 17 35 36 37 38 39 40 41 42 25 26 27 28 29 30 31 32 33 34 43 09 18 19 01 02 61 60 59 58 57 56 55 54 + * Teensy 28 29 30 31 32 33 34 35 20 21 22 23 24 25 26 27 10 11 12 13 14 15 16 17 00 01 02 03 04 05 06 07 08 09(46*47)36 37 18 19 38 39 40 41 42 43 44 45 + * Port A0 A1 A2 A3 A4 A5 A6 A7 B0 B1 B2 B3 B4 B5 B6 B7 C0 C1 C2 C3 C4 C5 C6 C7 D0 D1 D2 D3 D4 D5 D6 D7 E0 E1 E2 E3 E4 E5 E6 E7 F0 F1 F2 F3 F4 F5 F6 F7 + * > Marlin 00 01 02 03 04 05 06 07 08 09 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 + * The pins 46 and 47 are not supported by Teensyduino, but are supported below. + */ + +#ifndef _FASTIO_AT90USB +#define _FASTIO_AT90USB + +#include "fastio.h" + +// change for your board +#define DEBUG_LED DIO31 /* led D5 red */ + +// SPI +#define SCK DIO9 // 21 +#define MISO DIO11 // 23 +#define MOSI DIO10 // 22 +#define SS DIO8 // 20 + +// Digital I/O + +#define DIO0_PIN PINA0 +#define DIO0_RPORT PINA +#define DIO0_WPORT PORTA +#define DIO0_PWM NULL +#define DIO0_DDR DDRA + +#define DIO1_PIN PINA1 +#define DIO1_RPORT PINA +#define DIO1_WPORT PORTA +#define DIO1_PWM NULL +#define DIO1_DDR DDRA + +#define DIO2_PIN PINA2 +#define DIO2_RPORT PINA +#define DIO2_WPORT PORTA +#define DIO2_PWM NULL +#define DIO2_DDR DDRA + +#define DIO3_PIN PINA3 +#define DIO3_RPORT PINA +#define DIO3_WPORT PORTA +#define DIO3_PWM NULL +#define DIO3_DDR DDRA + +#define DIO4_PIN PINA4 +#define DIO4_RPORT PINA +#define DIO4_WPORT PORTA +#define DIO4_PWM NULL +#define DIO4_DDR DDRA + +#define DIO5_PIN PINA5 +#define DIO5_RPORT PINA +#define DIO5_WPORT PORTA +#define DIO5_PWM NULL +#define DIO5_DDR DDRA + +#define DIO6_PIN PINA6 +#define DIO6_RPORT PINA +#define DIO6_WPORT PORTA +#define DIO6_PWM NULL +#define DIO6_DDR DDRA + +#define DIO7_PIN PINA7 +#define DIO7_RPORT PINA +#define DIO7_WPORT PORTA +#define DIO7_PWM NULL +#define DIO7_DDR DDRA + +#define DIO8_PIN PINB0 +#define DIO8_RPORT PINB +#define DIO8_WPORT PORTB +#define DIO8_PWM NULL +#define DIO8_DDR DDRB + +#define DIO9_PIN PINB1 +#define DIO9_RPORT PINB +#define DIO9_WPORT PORTB +#define DIO9_PWM NULL +#define DIO9_DDR DDRB + +#define DIO10_PIN PINB2 +#define DIO10_RPORT PINB +#define DIO10_WPORT PORTB +#define DIO10_PWM NULL +#define DIO10_DDR DDRB + +#define DIO11_PIN PINB3 +#define DIO11_RPORT PINB +#define DIO11_WPORT PORTB +#define DIO11_PWM NULL +#define DIO11_DDR DDRB + +#define DIO12_PIN PINB4 +#define DIO12_RPORT PINB +#define DIO12_WPORT PORTB +#define DIO12_PWM NULL +#define DIO12_DDR DDRB + +#define DIO13_PIN PINB5 +#define DIO13_RPORT PINB +#define DIO13_WPORT PORTB +#define DIO13_PWM NULL +#define DIO13_DDR DDRB + +#define DIO14_PIN PINB6 +#define DIO14_RPORT PINB +#define DIO14_WPORT PORTB +#define DIO14_PWM NULL +#define DIO14_DDR DDRB + +#define DIO15_PIN PINB7 +#define DIO15_RPORT PINB +#define DIO15_WPORT PORTB +#define DIO15_PWM NULL +#define DIO15_DDR DDRB + +#define DIO16_PIN PINC0 +#define DIO16_RPORT PINC +#define DIO16_WPORT PORTC +#define DIO16_PWM NULL +#define DIO16_DDR DDRC + +#define DIO17_PIN PINC1 +#define DIO17_RPORT PINC +#define DIO17_WPORT PORTC +#define DIO17_PWM NULL +#define DIO17_DDR DDRC + +#define DIO18_PIN PINC2 +#define DIO18_RPORT PINC +#define DIO18_WPORT PORTC +#define DIO18_PWM NULL +#define DIO18_DDR DDRC + +#define DIO19_PIN PINC3 +#define DIO19_RPORT PINC +#define DIO19_WPORT PORTC +#define DIO19_PWM NULL +#define DIO19_DDR DDRC + +#define DIO20_PIN PINC4 +#define DIO20_RPORT PINC +#define DIO20_WPORT PORTC +#define DIO20_PWM NULL +#define DIO20_DDR DDRC + +#define DIO21_PIN PINC5 +#define DIO21_RPORT PINC +#define DIO21_WPORT PORTC +#define DIO21_PWM NULL +#define DIO21_DDR DDRC + +#define DIO22_PIN PINC6 +#define DIO22_RPORT PINC +#define DIO22_WPORT PORTC +#define DIO22_PWM NULL +#define DIO22_DDR DDRC + +#define DIO23_PIN PINC7 +#define DIO23_RPORT PINC +#define DIO23_WPORT PORTC +#define DIO23_PWM NULL +#define DIO23_DDR DDRC + +#define DIO24_PIN PIND0 +#define DIO24_RPORT PIND +#define DIO24_WPORT PORTD +#define DIO24_PWM NULL +#define DIO24_DDR DDRD + +#define DIO25_PIN PIND1 +#define DIO25_RPORT PIND +#define DIO25_WPORT PORTD +#define DIO25_PWM NULL +#define DIO25_DDR DDRD + +#define DIO26_PIN PIND2 +#define DIO26_RPORT PIND +#define DIO26_WPORT PORTD +#define DIO26_PWM NULL +#define DIO26_DDR DDRD + +#define DIO27_PIN PIND3 +#define DIO27_RPORT PIND +#define DIO27_WPORT PORTD +#define DIO27_PWM NULL +#define DIO27_DDR DDRD + +#define DIO28_PIN PIND4 +#define DIO28_RPORT PIND +#define DIO28_WPORT PORTD +#define DIO28_PWM NULL +#define DIO28_DDR DDRD + +#define DIO29_PIN PIND5 +#define DIO29_RPORT PIND +#define DIO29_WPORT PORTD +#define DIO29_PWM NULL +#define DIO29_DDR DDRD + +#define DIO30_PIN PIND6 +#define DIO30_RPORT PIND +#define DIO30_WPORT PORTD +#define DIO30_PWM NULL +#define DIO30_DDR DDRD + +#define DIO31_PIN PIND7 +#define DIO31_RPORT PIND +#define DIO31_WPORT PORTD +#define DIO31_PWM NULL +#define DIO31_DDR DDRD + +#define DIO32_PIN PINE0 +#define DIO32_RPORT PINE +#define DIO32_WPORT PORTE +#define DIO32_PWM NULL +#define DIO32_DDR DDRE + +#define DIO33_PIN PINE1 +#define DIO33_RPORT PINE +#define DIO33_WPORT PORTE +#define DIO33_PWM NULL +#define DIO33_DDR DDRE + +#define DIO34_PIN PINE2 +#define DIO34_RPORT PINE +#define DIO34_WPORT PORTE +#define DIO34_PWM NULL +#define DIO34_DDR DDRE + +#define DIO35_PIN PINE3 +#define DIO35_RPORT PINE +#define DIO35_WPORT PORTE +#define DIO35_PWM NULL +#define DIO35_DDR DDRE + +#define DIO36_PIN PINE4 +#define DIO36_RPORT PINE +#define DIO36_WPORT PORTE +#define DIO36_PWM NULL +#define DIO36_DDR DDRE + +#define DIO37_PIN PINE5 +#define DIO37_RPORT PINE +#define DIO37_WPORT PORTE +#define DIO37_PWM NULL +#define DIO37_DDR DDRE + +#define DIO38_PIN PINE6 +#define DIO38_RPORT PINE +#define DIO38_WPORT PORTE +#define DIO38_PWM NULL +#define DIO38_DDR DDRE + +#define DIO39_PIN PINE7 +#define DIO39_RPORT PINE +#define DIO39_WPORT PORTE +#define DIO39_PWM NULL +#define DIO39_DDR DDRE + +#define AIO0_PIN PINF0 +#define AIO0_RPORT PINF +#define AIO0_WPORT PORTF +#define AIO0_PWM NULL +#define AIO0_DDR DDRF + +#define AIO1_PIN PINF1 +#define AIO1_RPORT PINF +#define AIO1_WPORT PORTF +#define AIO1_PWM NULL +#define AIO1_DDR DDRF + +#define AIO2_PIN PINF2 +#define AIO2_RPORT PINF +#define AIO2_WPORT PORTF +#define AIO2_PWM NULL +#define AIO2_DDR DDRF + +#define AIO3_PIN PINF3 +#define AIO3_RPORT PINF +#define AIO3_WPORT PORTF +#define AIO3_PWM NULL +#define AIO3_DDR DDRF + +#define AIO4_PIN PINF4 +#define AIO4_RPORT PINF +#define AIO4_WPORT PORTF +#define AIO4_PWM NULL +#define AIO4_DDR DDRF + +#define AIO5_PIN PINF5 +#define AIO5_RPORT PINF +#define AIO5_WPORT PORTF +#define AIO5_PWM NULL +#define AIO5_DDR DDRF + +#define AIO6_PIN PINF6 +#define AIO6_RPORT PINF +#define AIO6_WPORT PORTF +#define AIO6_PWM NULL +#define AIO6_DDR DDRF + +#define AIO7_PIN PINF7 +#define AIO7_RPORT PINF +#define AIO7_WPORT PORTF +#define AIO7_PWM NULL +#define AIO7_DDR DDRF + +#define DIO40_PIN PINF0 +#define DIO40_RPORT PINF +#define DIO40_WPORT PORTF +#define DIO40_PWM NULL +#define DIO40_DDR DDRF + +#define DIO41_PIN PINF1 +#define DIO41_RPORT PINF +#define DIO41_WPORT PORTF +#define DIO41_PWM NULL +#define DIO41_DDR DDRF + +#define DIO42_PIN PINF2 +#define DIO42_RPORT PINF +#define DIO42_WPORT PORTF +#define DIO42_PWM NULL +#define DIO42_DDR DDRF + +#define DIO43_PIN PINF3 +#define DIO43_RPORT PINF +#define DIO43_WPORT PORTF +#define DIO43_PWM NULL +#define DIO43_DDR DDRF + +#define DIO44_PIN PINF4 +#define DIO44_RPORT PINF +#define DIO44_WPORT PORTF +#define DIO44_PWM NULL +#define DIO44_DDR DDRF + +#define DIO45_PIN PINF5 +#define DIO45_RPORT PINF +#define DIO45_WPORT PORTF +#define DIO45_PWM NULL +#define DIO45_DDR DDRF + +#define DIO46_PIN PINF6 +#define DIO46_RPORT PINF +#define DIO46_WPORT PORTF +#define DIO46_PWM NULL +#define DIO46_DDR DDRF + +#define DIO47_PIN PINF7 +#define DIO47_RPORT PINF +#define DIO47_WPORT PORTF +#define DIO47_PWM NULL +#define DIO47_DDR DDRF + +// Analog Outputs + +#undef PA0 +#define PA0_PIN PINA0 +#define PA0_RPORT PINA +#define PA0_WPORT PORTA +#define PA0_PWM NULL +#define PA0_DDR DDRA +#undef PA1 +#define PA1_PIN PINA1 +#define PA1_RPORT PINA +#define PA1_WPORT PORTA +#define PA1_PWM NULL +#define PA1_DDR DDRA +#undef PA2 +#define PA2_PIN PINA2 +#define PA2_RPORT PINA +#define PA2_WPORT PORTA +#define PA2_PWM NULL +#define PA2_DDR DDRA +#undef PA3 +#define PA3_PIN PINA3 +#define PA3_RPORT PINA +#define PA3_WPORT PORTA +#define PA3_PWM NULL +#define PA3_DDR DDRA +#undef PA4 +#define PA4_PIN PINA4 +#define PA4_RPORT PINA +#define PA4_WPORT PORTA +#define PA4_PWM NULL +#define PA4_DDR DDRA +#undef PA5 +#define PA5_PIN PINA5 +#define PA5_RPORT PINA +#define PA5_WPORT PORTA +#define PA5_PWM NULL +#define PA5_DDR DDRA +#undef PA6 +#define PA6_PIN PINA6 +#define PA6_RPORT PINA +#define PA6_WPORT PORTA +#define PA6_PWM NULL +#define PA6_DDR DDRA +#undef PA7 +#define PA7_PIN PINA7 +#define PA7_RPORT PINA +#define PA7_WPORT PORTA +#define PA7_PWM NULL +#define PA7_DDR DDRA + +#undef PB0 +#define PB0_PIN PINB0 +#define PB0_RPORT PINB +#define PB0_WPORT PORTB +#define PB0_PWM NULL +#define PB0_DDR DDRB +#undef PB1 +#define PB1_PIN PINB1 +#define PB1_RPORT PINB +#define PB1_WPORT PORTB +#define PB1_PWM NULL +#define PB1_DDR DDRB +#undef PB2 +#define PB2_PIN PINB2 +#define PB2_RPORT PINB +#define PB2_WPORT PORTB +#define PB2_PWM NULL +#define PB2_DDR DDRB +#undef PB3 +#define PB3_PIN PINB3 +#define PB3_RPORT PINB +#define PB3_WPORT PORTB +#define PB3_PWM NULL +#define PB3_DDR DDRB +#undef PB4 +#define PB4_PIN PINB4 +#define PB4_RPORT PINB +#define PB4_WPORT PORTB +#define PB4_PWM NULL +#define PB4_DDR DDRB +#undef PB5 +#define PB5_PIN PINB5 +#define PB5_RPORT PINB +#define PB5_WPORT PORTB +#define PB5_PWM NULL +#define PB5_DDR DDRB +#undef PB6 +#define PB6_PIN PINB6 +#define PB6_RPORT PINB +#define PB6_WPORT PORTB +#define PB6_PWM NULL +#define PB6_DDR DDRB +#undef PB7 +#define PB7_PIN PINB7 +#define PB7_RPORT PINB +#define PB7_WPORT PORTB +#define PB7_PWM NULL +#define PB7_DDR DDRB + +#undef PC0 +#define PC0_PIN PINC0 +#define PC0_RPORT PINC +#define PC0_WPORT PORTC +#define PC0_PWM NULL +#define PC0_DDR DDRC +#undef PC1 +#define PC1_PIN PINC1 +#define PC1_RPORT PINC +#define PC1_WPORT PORTC +#define PC1_PWM NULL +#define PC1_DDR DDRC +#undef PC2 +#define PC2_PIN PINC2 +#define PC2_RPORT PINC +#define PC2_WPORT PORTC +#define PC2_PWM NULL +#define PC2_DDR DDRC +#undef PC3 +#define PC3_PIN PINC3 +#define PC3_RPORT PINC +#define PC3_WPORT PORTC +#define PC3_PWM NULL +#define PC3_DDR DDRC +#undef PC4 +#define PC4_PIN PINC4 +#define PC4_RPORT PINC +#define PC4_WPORT PORTC +#define PC4_PWM NULL +#define PC4_DDR DDRC +#undef PC5 +#define PC5_PIN PINC5 +#define PC5_RPORT PINC +#define PC5_WPORT PORTC +#define PC5_PWM NULL +#define PC5_DDR DDRC +#undef PC6 +#define PC6_PIN PINC6 +#define PC6_RPORT PINC +#define PC6_WPORT PORTC +#define PC6_PWM NULL +#define PC6_DDR DDRC +#undef PC7 +#define PC7_PIN PINC7 +#define PC7_RPORT PINC +#define PC7_WPORT PORTC +#define PC7_PWM NULL +#define PC7_DDR DDRC + +#undef PD0 +#define PD0_PIN PIND0 +#define PD0_RPORT PIND +#define PD0_WPORT PORTD +#define PD0_PWM NULL +#define PD0_DDR DDRD +#undef PD1 +#define PD1_PIN PIND1 +#define PD1_RPORT PIND +#define PD1_WPORT PORTD +#define PD1_PWM NULL +#define PD1_DDR DDRD +#undef PD2 +#define PD2_PIN PIND2 +#define PD2_RPORT PIND +#define PD2_WPORT PORTD +#define PD2_PWM NULL +#define PD2_DDR DDRD +#undef PD3 +#define PD3_PIN PIND3 +#define PD3_RPORT PIND +#define PD3_WPORT PORTD +#define PD3_PWM NULL +#define PD3_DDR DDRD +#undef PD4 +#define PD4_PIN PIND4 +#define PD4_RPORT PIND +#define PD4_WPORT PORTD +#define PD4_PWM NULL +#define PD4_DDR DDRD +#undef PD5 +#define PD5_PIN PIND5 +#define PD5_RPORT PIND +#define PD5_WPORT PORTD +#define PD5_PWM NULL +#define PD5_DDR DDRD +#undef PD6 +#define PD6_PIN PIND6 +#define PD6_RPORT PIND +#define PD6_WPORT PORTD +#define PD6_PWM NULL +#define PD6_DDR DDRD +#undef PD7 +#define PD7_PIN PIND7 +#define PD7_RPORT PIND +#define PD7_WPORT PORTD +#define PD7_PWM NULL +#define PD7_DDR DDRD + +#undef PE0 +#define PE0_PIN PINE0 +#define PE0_RPORT PINE +#define PE0_WPORT PORTE +#define PE0_PWM NULL +#define PE0_DDR DDRE +#undef PE1 +#define PE1_PIN PINE1 +#define PE1_RPORT PINE +#define PE1_WPORT PORTE +#define PE1_PWM NULL +#define PE1_DDR DDRE +#undef PE2 +#define PE2_PIN PINE2 +#define PE2_RPORT PINE +#define PE2_WPORT PORTE +#define PE2_PWM NULL +#define PE2_DDR DDRE +#undef PE3 +#define PE3_PIN PINE3 +#define PE3_RPORT PINE +#define PE3_WPORT PORTE +#define PE3_PWM NULL +#define PE3_DDR DDRE +#undef PE4 +#define PE4_PIN PINE4 +#define PE4_RPORT PINE +#define PE4_WPORT PORTE +#define PE4_PWM NULL +#define PE4_DDR DDRE +#undef PE5 +#define PE5_PIN PINE5 +#define PE5_RPORT PINE +#define PE5_WPORT PORTE +#define PE5_PWM NULL +#define PE5_DDR DDRE +#undef PE6 +#define PE6_PIN PINE6 +#define PE6_RPORT PINE +#define PE6_WPORT PORTE +#define PE6_PWM NULL +#define PE6_DDR DDRE +#undef PE7 +#define PE7_PIN PINE7 +#define PE7_RPORT PINE +#define PE7_WPORT PORTE +#define PE7_PWM NULL +#define PE7_DDR DDRE + +#undef PF0 +#define PF0_PIN PINF0 +#define PF0_RPORT PINF +#define PF0_WPORT PORTF +#define PF0_PWM NULL +#define PF0_DDR DDRF +#undef PF1 +#define PF1_PIN PINF1 +#define PF1_RPORT PINF +#define PF1_WPORT PORTF +#define PF1_PWM NULL +#define PF1_DDR DDRF +#undef PF2 +#define PF2_PIN PINF2 +#define PF2_RPORT PINF +#define PF2_WPORT PORTF +#define PF2_PWM NULL +#define PF2_DDR DDRF +#undef PF3 +#define PF3_PIN PINF3 +#define PF3_RPORT PINF +#define PF3_WPORT PORTF +#define PF3_PWM NULL +#define PF3_DDR DDRF +#undef PF4 +#define PF4_PIN PINF4 +#define PF4_RPORT PINF +#define PF4_WPORT PORTF +#define PF4_PWM NULL +#define PF4_DDR DDRF +#undef PF5 +#define PF5_PIN PINF5 +#define PF5_RPORT PINF +#define PF5_WPORT PORTF +#define PF5_PWM NULL +#define PF5_DDR DDRF +#undef PF6 +#define PF6_PIN PINF6 +#define PF6_RPORT PINF +#define PF6_WPORT PORTF +#define PF6_PWM NULL +#define PF6_DDR DDRF +#undef PF7 +#define PF7_PIN PINF7 +#define PF7_RPORT PINF +#define PF7_WPORT PORTF +#define PF7_PWM NULL +#define PF7_DDR DDRF + +#endif // _FASTIO_AT90USB diff --git a/Marlin/fastio_AT90USB-Teensy.h b/Marlin/fastio_AT90USB-Teensy.h new file mode 100644 index 000000000..7cafa6901 --- /dev/null +++ b/Marlin/fastio_AT90USB-Teensy.h @@ -0,0 +1,683 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (C) 2016 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 . + * + */ + +/** + * Pin mapping (Teensy) for AT90USB646, 647, 1286, and 1287 + * + * AT90USB 51 50 49 48 47 46 45 44 10 11 12 13 14 15 16 17 35 36 37 38 39 40 41 42 25 26 27 28 29 30 31 32 33 34 43 09 18 19 01 02 61 60 59 58 57 56 55 54 + * > Teensy 28 29 30 31 32 33 34 35 20 21 22 23 24 25 26 27 10 11 12 13 14 15 16 17 00 01 02 03 04 05 06 07 08 09(46*47)36 37 18 19 38 39 40 41 42 43 44 45 + * Port A0 A1 A2 A3 A4 A5 A6 A7 B0 B1 B2 B3 B4 B5 B6 B7 C0 C1 C2 C3 C4 C5 C6 C7 D0 D1 D2 D3 D4 D5 D6 D7 E0 E1 E2 E3 E4 E5 E6 E7 F0 F1 F2 F3 F4 F5 F6 F7 + * Marlin 00 01 02 03 04 05 06 07 08 09 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 + * The pins 46 and 47 are not supported by Teensyduino, but are supported below. + */ + +#ifndef _FASTIO_AT90USB +#define _FASTIO_AT90USB + +#include "fastio.h" + +// change for your board +#define DEBUG_LED DIO31 /* led D5 red */ + +// SPI +#define SCK DIO21 // 9 +#define MISO DIO23 // 11 +#define MOSI DIO22 // 10 +#define SS DIO20 // 8 + +// Digital I/O + +#define DIO0_PIN PIND0 +#define DIO0_RPORT PIND +#define DIO0_WPORT PORTD +#define DIO0_PWM NULL +#define DIO0_DDR DDRD + +#define DIO1_PIN PIND1 +#define DIO1_RPORT PIND +#define DIO1_WPORT PORTD +#define DIO1_PWM NULL +#define DIO1_DDR DDRD + +#define DIO2_PIN PIND2 +#define DIO2_RPORT PIND +#define DIO2_WPORT PORTD +#define DIO2_PWM NULL +#define DIO2_DDR DDRD + +#define DIO3_PIN PIND3 +#define DIO3_RPORT PIND +#define DIO3_WPORT PORTD +#define DIO3_PWM NULL +#define DIO3_DDR DDRD + +#define DIO4_PIN PIND4 +#define DIO4_RPORT PIND +#define DIO4_WPORT PORTD +#define DIO4_PWM NULL +#define DIO4_DDR DDRD + +#define DIO5_PIN PIND5 +#define DIO5_RPORT PIND +#define DIO5_WPORT PORTD +#define DIO5_PWM NULL +#define DIO5_DDR DDRD + +#define DIO6_PIN PIND6 +#define DIO6_RPORT PIND +#define DIO6_WPORT PORTD +#define DIO6_PWM NULL +#define DIO6_DDR DDRD + +#define DIO7_PIN PIND7 +#define DIO7_RPORT PIND +#define DIO7_WPORT PORTD +#define DIO7_PWM NULL +#define DIO7_DDR DDRD + +#define DIO8_PIN PINE0 +#define DIO8_RPORT PINE +#define DIO8_WPORT PORTE +#define DIO8_PWM NULL +#define DIO8_DDR DDRE + +#define DIO9_PIN PINE1 +#define DIO9_RPORT PINE +#define DIO9_WPORT PORTE +#define DIO9_PWM NULL +#define DIO9_DDR DDRE + +#define DIO10_PIN PINC0 +#define DIO10_RPORT PINC +#define DIO10_WPORT PORTC +#define DIO10_PWM NULL +#define DIO10_DDR DDRC + +#define DIO11_PIN PINC1 +#define DIO11_RPORT PINC +#define DIO11_WPORT PORTC +#define DIO11_PWM NULL +#define DIO11_DDR DDRC + +#define DIO12_PIN PINC2 +#define DIO12_RPORT PINC +#define DIO12_WPORT PORTC +#define DIO12_PWM NULL +#define DIO12_DDR DDRC + +#define DIO13_PIN PINC3 +#define DIO13_RPORT PINC +#define DIO13_WPORT PORTC +#define DIO13_PWM NULL +#define DIO13_DDR DDRC + +#define DIO14_PIN PINC4 +#define DIO14_RPORT PINC +#define DIO14_WPORT PORTC +#define DIO14_PWM NULL +#define DIO14_DDR DDRC + +#define DIO15_PIN PINC5 +#define DIO15_RPORT PINC +#define DIO15_WPORT PORTC +#define DIO15_PWM NULL +#define DIO15_DDR DDRC + +#define DIO16_PIN PINC6 +#define DIO16_RPORT PINC +#define DIO16_WPORT PORTC +#define DIO16_PWM NULL +#define DIO16_DDR DDRC + +#define DIO17_PIN PINC7 +#define DIO17_RPORT PINC +#define DIO17_WPORT PORTC +#define DIO17_PWM NULL +#define DIO17_DDR DDRC + +#define DIO18_PIN PINE6 +#define DIO18_RPORT PINE +#define DIO18_WPORT PORTE +#define DIO18_PWM NULL +#define DIO18_DDR DDRE + +#define DIO19_PIN PINE7 +#define DIO19_RPORT PINE +#define DIO19_WPORT PORTE +#define DIO19_PWM NULL +#define DIO19_DDR DDRE + +#define DIO20_PIN PINB0 +#define DIO20_RPORT PINB +#define DIO20_WPORT PORTB +#define DIO20_PWM NULL +#define DIO20_DDR DDRB + +#define DIO21_PIN PINB1 +#define DIO21_RPORT PINB +#define DIO21_WPORT PORTB +#define DIO21_PWM NULL +#define DIO21_DDR DDRB + +#define DIO22_PIN PINB2 +#define DIO22_RPORT PINB +#define DIO22_WPORT PORTB +#define DIO22_PWM NULL +#define DIO22_DDR DDRB + +#define DIO23_PIN PINB3 +#define DIO23_RPORT PINB +#define DIO23_WPORT PORTB +#define DIO23_PWM NULL +#define DIO23_DDR DDRB + +#define DIO24_PIN PINB4 +#define DIO24_RPORT PINB +#define DIO24_WPORT PORTB +#define DIO24_PWM NULL +#define DIO24_DDR DDRB + +#define DIO25_PIN PINB5 +#define DIO25_RPORT PINB +#define DIO25_WPORT PORTB +#define DIO25_PWM NULL +#define DIO25_DDR DDRB + +#define DIO26_PIN PINB6 +#define DIO26_RPORT PINB +#define DIO26_WPORT PORTB +#define DIO26_PWM NULL +#define DIO26_DDR DDRB + +#define DIO27_PIN PINB7 +#define DIO27_RPORT PINB +#define DIO27_WPORT PORTB +#define DIO27_PWM NULL +#define DIO27_DDR DDRB + +#define DIO28_PIN PINA0 +#define DIO28_RPORT PINA +#define DIO28_WPORT PORTA +#define DIO28_PWM NULL +#define DIO28_DDR DDRA + +#define DIO29_PIN PINA1 +#define DIO29_RPORT PINA +#define DIO29_WPORT PORTA +#define DIO29_PWM NULL +#define DIO29_DDR DDRA + +#define DIO30_PIN PINA2 +#define DIO30_RPORT PINA +#define DIO30_WPORT PORTA +#define DIO30_PWM NULL +#define DIO30_DDR DDRA + +#define DIO31_PIN PINA3 +#define DIO31_RPORT PINA +#define DIO31_WPORT PORTA +#define DIO31_PWM NULL +#define DIO31_DDR DDRA + +#define DIO32_PIN PINA4 +#define DIO32_RPORT PINA +#define DIO32_WPORT PORTA +#define DIO32_PWM NULL +#define DIO32_DDR DDRA + +#define DIO33_PIN PINA5 +#define DIO33_RPORT PINA +#define DIO33_WPORT PORTA +#define DIO33_PWM NULL +#define DIO33_DDR DDRA + +#define DIO34_PIN PINA6 +#define DIO34_RPORT PINA +#define DIO34_WPORT PORTA +#define DIO34_PWM NULL +#define DIO34_DDR DDRA + +#define DIO35_PIN PINA7 +#define DIO35_RPORT PINA +#define DIO35_WPORT PORTA +#define DIO35_PWM NULL +#define DIO35_DDR DDRA + +#define DIO36_PIN PINE4 +#define DIO36_RPORT PINE +#define DIO36_WPORT PORTE +#define DIO36_PWM NULL +#define DIO36_DDR DDRE + +#define DIO37_PIN PINE5 +#define DIO37_RPORT PINE +#define DIO37_WPORT PORTE +#define DIO37_PWM NULL +#define DIO37_DDR DDRE + +#define DIO38_PIN PINF0 +#define DIO38_RPORT PINF +#define DIO38_WPORT PORTF +#define DIO38_PWM NULL +#define DIO38_DDR DDRF + +#define DIO39_PIN PINF1 +#define DIO39_RPORT PINF +#define DIO39_WPORT PORTF +#define DIO39_PWM NULL +#define DIO39_DDR DDRF + +#define DIO40_PIN PINF2 +#define DIO40_RPORT PINF +#define DIO40_WPORT PORTF +#define DIO40_PWM NULL +#define DIO40_DDR DDRF + +#define DIO41_PIN PINF3 +#define DIO41_RPORT PINF +#define DIO41_WPORT PORTF +#define DIO41_PWM NULL +#define DIO41_DDR DDRF + +#define DIO42_PIN PINF4 +#define DIO42_RPORT PINF +#define DIO42_WPORT PORTF +#define DIO42_PWM NULL +#define DIO42_DDR DDRF + +#define DIO43_PIN PINF5 +#define DIO43_RPORT PINF +#define DIO43_WPORT PORTF +#define DIO43_PWM NULL +#define DIO43_DDR DDRF + +#define DIO44_PIN PINF6 +#define DIO44_RPORT PINF +#define DIO44_WPORT PORTF +#define DIO44_PWM NULL +#define DIO44_DDR DDRF + +#define DIO45_PIN PINF7 +#define DIO45_RPORT PINF +#define DIO45_WPORT PORTF +#define DIO45_PWM NULL +#define DIO45_DDR DDRF + +#define AIO0_PIN PINF0 +#define AIO0_RPORT PINF +#define AIO0_WPORT PORTF +#define AIO0_PWM NULL +#define AIO0_DDR DDRF + +#define AIO1_PIN PINF1 +#define AIO1_RPORT PINF +#define AIO1_WPORT PORTF +#define AIO1_PWM NULL +#define AIO1_DDR DDRF + +#define AIO2_PIN PINF2 +#define AIO2_RPORT PINF +#define AIO2_WPORT PORTF +#define AIO2_PWM NULL +#define AIO2_DDR DDRF + +#define AIO3_PIN PINF3 +#define AIO3_RPORT PINF +#define AIO3_WPORT PORTF +#define AIO3_PWM NULL +#define AIO3_DDR DDRF + +#define AIO4_PIN PINF4 +#define AIO4_RPORT PINF +#define AIO4_WPORT PORTF +#define AIO4_PWM NULL +#define AIO4_DDR DDRF + +#define AIO5_PIN PINF5 +#define AIO5_RPORT PINF +#define AIO5_WPORT PORTF +#define AIO5_PWM NULL +#define AIO5_DDR DDRF + +#define AIO6_PIN PINF6 +#define AIO6_RPORT PINF +#define AIO6_WPORT PORTF +#define AIO6_PWM NULL +#define AIO6_DDR DDRF + +#define AIO7_PIN PINF7 +#define AIO7_RPORT PINF +#define AIO7_WPORT PORTF +#define AIO7_PWM NULL +#define AIO7_DDR DDRF + +//-- Begin not supported by Teensyduino +//-- don't use Arduino functions on these pins pinMode/digitalWrite/etc +#define DIO46_PIN PINE2 +#define DIO46_RPORT PINE +#define DIO46_WPORT PORTE +#define DIO46_PWM NULL +#define DIO46_DDR DDRE + +#define DIO47_PIN PINE3 +#define DIO47_RPORT PINE +#define DIO47_WPORT PORTE +#define DIO47_PWM NULL +#define DIO47_DDR DDRE +//-- end not supported by Teensyduino + +#undef PA0 +#define PA0_PIN PINA0 +#define PA0_RPORT PINA +#define PA0_WPORT PORTA +#define PA0_PWM NULL +#define PA0_DDR DDRA +#undef PA1 +#define PA1_PIN PINA1 +#define PA1_RPORT PINA +#define PA1_WPORT PORTA +#define PA1_PWM NULL +#define PA1_DDR DDRA +#undef PA2 +#define PA2_PIN PINA2 +#define PA2_RPORT PINA +#define PA2_WPORT PORTA +#define PA2_PWM NULL +#define PA2_DDR DDRA +#undef PA3 +#define PA3_PIN PINA3 +#define PA3_RPORT PINA +#define PA3_WPORT PORTA +#define PA3_PWM NULL +#define PA3_DDR DDRA +#undef PA4 +#define PA4_PIN PINA4 +#define PA4_RPORT PINA +#define PA4_WPORT PORTA +#define PA4_PWM NULL +#define PA4_DDR DDRA +#undef PA5 +#define PA5_PIN PINA5 +#define PA5_RPORT PINA +#define PA5_WPORT PORTA +#define PA5_PWM NULL +#define PA5_DDR DDRA +#undef PA6 +#define PA6_PIN PINA6 +#define PA6_RPORT PINA +#define PA6_WPORT PORTA +#define PA6_PWM NULL +#define PA6_DDR DDRA +#undef PA7 +#define PA7_PIN PINA7 +#define PA7_RPORT PINA +#define PA7_WPORT PORTA +#define PA7_PWM NULL +#define PA7_DDR DDRA + +#undef PB0 +#define PB0_PIN PINB0 +#define PB0_RPORT PINB +#define PB0_WPORT PORTB +#define PB0_PWM NULL +#define PB0_DDR DDRB +#undef PB1 +#define PB1_PIN PINB1 +#define PB1_RPORT PINB +#define PB1_WPORT PORTB +#define PB1_PWM NULL +#define PB1_DDR DDRB +#undef PB2 +#define PB2_PIN PINB2 +#define PB2_RPORT PINB +#define PB2_WPORT PORTB +#define PB2_PWM NULL +#define PB2_DDR DDRB +#undef PB3 +#define PB3_PIN PINB3 +#define PB3_RPORT PINB +#define PB3_WPORT PORTB +#define PB3_PWM NULL +#define PB3_DDR DDRB +#undef PB4 +#define PB4_PIN PINB4 +#define PB4_RPORT PINB +#define PB4_WPORT PORTB +#define PB4_PWM NULL +#define PB4_DDR DDRB +#undef PB5 +#define PB5_PIN PINB5 +#define PB5_RPORT PINB +#define PB5_WPORT PORTB +#define PB5_PWM NULL +#define PB5_DDR DDRB +#undef PB6 +#define PB6_PIN PINB6 +#define PB6_RPORT PINB +#define PB6_WPORT PORTB +#define PB6_PWM NULL +#define PB6_DDR DDRB +#undef PB7 +#define PB7_PIN PINB7 +#define PB7_RPORT PINB +#define PB7_WPORT PORTB +#define PB7_PWM NULL +#define PB7_DDR DDRB + +#undef PC0 +#define PC0_PIN PINC0 +#define PC0_RPORT PINC +#define PC0_WPORT PORTC +#define PC0_PWM NULL +#define PC0_DDR DDRC +#undef PC1 +#define PC1_PIN PINC1 +#define PC1_RPORT PINC +#define PC1_WPORT PORTC +#define PC1_PWM NULL +#define PC1_DDR DDRC +#undef PC2 +#define PC2_PIN PINC2 +#define PC2_RPORT PINC +#define PC2_WPORT PORTC +#define PC2_PWM NULL +#define PC2_DDR DDRC +#undef PC3 +#define PC3_PIN PINC3 +#define PC3_RPORT PINC +#define PC3_WPORT PORTC +#define PC3_PWM NULL +#define PC3_DDR DDRC +#undef PC4 +#define PC4_PIN PINC4 +#define PC4_RPORT PINC +#define PC4_WPORT PORTC +#define PC4_PWM NULL +#define PC4_DDR DDRC +#undef PC5 +#define PC5_PIN PINC5 +#define PC5_RPORT PINC +#define PC5_WPORT PORTC +#define PC5_PWM NULL +#define PC5_DDR DDRC +#undef PC6 +#define PC6_PIN PINC6 +#define PC6_RPORT PINC +#define PC6_WPORT PORTC +#define PC6_PWM NULL +#define PC6_DDR DDRC +#undef PC7 +#define PC7_PIN PINC7 +#define PC7_RPORT PINC +#define PC7_WPORT PORTC +#define PC7_PWM NULL +#define PC7_DDR DDRC + +#undef PD0 +#define PD0_PIN PIND0 +#define PD0_RPORT PIND +#define PD0_WPORT PORTD +#define PD0_PWM NULL +#define PD0_DDR DDRD +#undef PD1 +#define PD1_PIN PIND1 +#define PD1_RPORT PIND +#define PD1_WPORT PORTD +#define PD1_PWM NULL +#define PD1_DDR DDRD +#undef PD2 +#define PD2_PIN PIND2 +#define PD2_RPORT PIND +#define PD2_WPORT PORTD +#define PD2_PWM NULL +#define PD2_DDR DDRD +#undef PD3 +#define PD3_PIN PIND3 +#define PD3_RPORT PIND +#define PD3_WPORT PORTD +#define PD3_PWM NULL +#define PD3_DDR DDRD +#undef PD4 +#define PD4_PIN PIND4 +#define PD4_RPORT PIND +#define PD4_WPORT PORTD +#define PD4_PWM NULL +#define PD4_DDR DDRD +#undef PD5 +#define PD5_PIN PIND5 +#define PD5_RPORT PIND +#define PD5_WPORT PORTD +#define PD5_PWM NULL +#define PD5_DDR DDRD +#undef PD6 +#define PD6_PIN PIND6 +#define PD6_RPORT PIND +#define PD6_WPORT PORTD +#define PD6_PWM NULL +#define PD6_DDR DDRD +#undef PD7 +#define PD7_PIN PIND7 +#define PD7_RPORT PIND +#define PD7_WPORT PORTD +#define PD7_PWM NULL +#define PD7_DDR DDRD + +#undef PE0 +#define PE0_PIN PINE0 +#define PE0_RPORT PINE +#define PE0_WPORT PORTE +#define PE0_PWM NULL +#define PE0_DDR DDRE +#undef PE1 +#define PE1_PIN PINE1 +#define PE1_RPORT PINE +#define PE1_WPORT PORTE +#define PE1_PWM NULL +#define PE1_DDR DDRE +#undef PE2 +#define PE2_PIN PINE2 +#define PE2_RPORT PINE +#define PE2_WPORT PORTE +#define PE2_PWM NULL +#define PE2_DDR DDRE +#undef PE3 +#define PE3_PIN PINE3 +#define PE3_RPORT PINE +#define PE3_WPORT PORTE +#define PE3_PWM NULL +#define PE3_DDR DDRE +#undef PE4 +#define PE4_PIN PINE4 +#define PE4_RPORT PINE +#define PE4_WPORT PORTE +#define PE4_PWM NULL +#define PE4_DDR DDRE +#undef PE5 +#define PE5_PIN PINE5 +#define PE5_RPORT PINE +#define PE5_WPORT PORTE +#define PE5_PWM NULL +#define PE5_DDR DDRE +#undef PE6 +#define PE6_PIN PINE6 +#define PE6_RPORT PINE +#define PE6_WPORT PORTE +#define PE6_PWM NULL +#define PE6_DDR DDRE +#undef PE7 +#define PE7_PIN PINE7 +#define PE7_RPORT PINE +#define PE7_WPORT PORTE +#define PE7_PWM NULL +#define PE7_DDR DDRE + +#undef PF0 +#define PF0_PIN PINF0 +#define PF0_RPORT PINF +#define PF0_WPORT PORTF +#define PF0_PWM NULL +#define PF0_DDR DDRF +#undef PF1 +#define PF1_PIN PINF1 +#define PF1_RPORT PINF +#define PF1_WPORT PORTF +#define PF1_PWM NULL +#define PF1_DDR DDRF +#undef PF2 +#define PF2_PIN PINF2 +#define PF2_RPORT PINF +#define PF2_WPORT PORTF +#define PF2_PWM NULL +#define PF2_DDR DDRF +#undef PF3 +#define PF3_PIN PINF3 +#define PF3_RPORT PINF +#define PF3_WPORT PORTF +#define PF3_PWM NULL +#define PF3_DDR DDRF +#undef PF4 +#define PF4_PIN PINF4 +#define PF4_RPORT PINF +#define PF4_WPORT PORTF +#define PF4_PWM NULL +#define PF4_DDR DDRF +#undef PF5 +#define PF5_PIN PINF5 +#define PF5_RPORT PINF +#define PF5_WPORT PORTF +#define PF5_PWM NULL +#define PF5_DDR DDRF +#undef PF6 +#define PF6_PIN PINF6 +#define PF6_RPORT PINF +#define PF6_WPORT PORTF +#define PF6_PWM NULL +#define PF6_DDR DDRF +#undef PF7 +#define PF7_PIN PINF7 +#define PF7_RPORT PINF +#define PF7_WPORT PORTF +#define PF7_PWM NULL +#define PF7_DDR DDRF + +#endif // AT90USBxx_TEENSYPP_ASSIGNMENTS Teensyduino assignments +#endif // _FASTIO_AT90USB From d7fda2fe49ea47b825849a7e19da63e2baad840f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 21 May 2017 10:40:05 -0500 Subject: [PATCH 121/189] Formatting, const in G33 --- Marlin/Marlin_main.cpp | 13 +++++-------- 1 file changed, 5 insertions(+), 8 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 7e408edbe..20ef82c77 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -5137,7 +5137,6 @@ void home_all_axes() { gcode_G28(true); } } const bool towers_set = !code_seen('T'), - _1p_calibration = probe_points == 1, _4p_calibration = probe_points == 2, _4p_towers_points = _4p_calibration && towers_set, @@ -5151,14 +5150,12 @@ void home_all_axes() { gcode_G28(true); } _7p_intermed_points = _7p_calibration && !_7p_half_circle; if (!_1p_calibration) { // test if the outer radius is reachable + const float circles = (_7p_quadruple_circle ? 1.5 : + _7p_triple_circle ? 1.0 : + _7p_double_circle ? 0.5 : 0), + radius = (1 + circles * 0.1) * delta_calibration_radius; for (uint8_t axis = 1; axis < 13; ++axis) { - float circles = (_7p_quadruple_circle ? 1.5 : - _7p_triple_circle ? 1.0 : - _7p_double_circle ? 0.5 : 0); - if (!position_is_reachable_by_probe_xy(cos(RADIANS(180 + 30 * axis)) * - delta_calibration_radius * (1 + circles * 0.1), - sin(RADIANS(180 + 30 * axis)) * - delta_calibration_radius * (1 + circles * 0.1))) { + if (!position_is_reachable_by_probe_xy(cos(RADIANS(180 + 30 * axis)) * radius, sin(RADIANS(180 + 30 * axis)) * radius)) { SERIAL_PROTOCOLLNPGM("?(M665 B)ed radius is implausible."); return; } From 364f8fb6136f977e7c1b80d4c71eb39e5823f615 Mon Sep 17 00:00:00 2001 From: Roxy-3D Date: Sun, 21 May 2017 11:10:22 -0500 Subject: [PATCH 122/189] Update Configuration.h files to better names (#6814) Changed UBL_G26_MESH_EDITING to UBL_G26_MESH_VALIDATION Added UBL_MESH_EDIT_MOVES_Z to prepare for that change (coming next) --- Marlin/Configuration.h | 3 ++- Marlin/G26_Mesh_Validation_Tool.cpp | 4 ++-- Marlin/Marlin_main.cpp | 12 ++++++------ Marlin/SanityCheck.h | 4 +++- .../example_configurations/Cartesio/Configuration.h | 3 ++- Marlin/example_configurations/Felix/Configuration.h | 3 ++- .../Felix/DUAL/Configuration.h | 3 ++- .../FolgerTech-i3-2020/Configuration.h | 3 ++- .../example_configurations/Hephestos/Configuration.h | 3 ++- .../Hephestos_2/Configuration.h | 3 ++- Marlin/example_configurations/K8200/Configuration.h | 3 ++- Marlin/example_configurations/K8400/Configuration.h | 3 ++- .../K8400/Dual-head/Configuration.h | 3 ++- .../RepRapWorld/Megatronics/Configuration.h | 3 ++- .../example_configurations/RigidBot/Configuration.h | 3 ++- Marlin/example_configurations/SCARA/Configuration.h | 5 +++-- Marlin/example_configurations/TAZ4/Configuration.h | 5 +++-- .../example_configurations/TinyBoy2/Configuration.h | 5 +++-- Marlin/example_configurations/WITBOX/Configuration.h | 5 +++-- .../adafruit/ST7565/Configuration.h | 3 ++- .../delta/FLSUN/auto_calibrate/Configuration.h | 3 ++- .../delta/FLSUN/kossel_mini/Configuration.h | 3 ++- .../delta/generic/Configuration.h | 3 ++- .../delta/kossel_mini/Configuration.h | 3 ++- .../delta/kossel_pro/Configuration.h | 3 ++- .../delta/kossel_xl/Configuration.h | 3 ++- .../gCreate_gMax1.5+/Configuration.h | 3 ++- .../example_configurations/makibox/Configuration.h | 3 ++- .../tvrrug/Round2/Configuration.h | 5 +++-- Marlin/example_configurations/wt150/Configuration.h | 3 ++- 30 files changed, 70 insertions(+), 41 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 529b510aa..9e7e98614 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -886,7 +886,8 @@ #define UBL_PROBE_PT_2_Y 20 #define UBL_PROBE_PT_3_X 180 #define UBL_PROBE_PT_3_Y 20 - //#define UBL_G26_MESH_EDITING // Enable G26 mesh editing + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation + #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle #elif ENABLED(MESH_BED_LEVELING) diff --git a/Marlin/G26_Mesh_Validation_Tool.cpp b/Marlin/G26_Mesh_Validation_Tool.cpp index 5e65a200b..d605cc70e 100644 --- a/Marlin/G26_Mesh_Validation_Tool.cpp +++ b/Marlin/G26_Mesh_Validation_Tool.cpp @@ -26,7 +26,7 @@ #include "MarlinConfig.h" -#if ENABLED(AUTO_BED_LEVELING_UBL) && ENABLED(UBL_G26_MESH_EDITING) +#if ENABLED(AUTO_BED_LEVELING_UBL) && ENABLED(UBL_G26_MESH_VALIDATION) #include "ubl.h" #include "Marlin.h" @@ -873,4 +873,4 @@ return UBL_OK; } -#endif // AUTO_BED_LEVELING_UBL && UBL_G26_MESH_EDITING +#endif // AUTO_BED_LEVELING_UBL && UBL_G26_MESH_VALIDATION diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 3caccf8d9..4690ec8b1 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -57,7 +57,7 @@ * G12 - Clean tool * G20 - Set input units to inches * G21 - Set input units to millimeters - * G26 - Mesh Validation Pattern (Requires UBL_G26_MESH_EDITING) + * G26 - Mesh Validation Pattern (Requires UBL_G26_MESH_VALIDATION) * G27 - Park Nozzle (Requires NOZZLE_PARK_FEATURE) * G28 - Home one or more axes * G29 - Detailed Z probe, probes the bed at 3 or more points. Will fail if you haven't homed yet. @@ -6613,7 +6613,7 @@ inline void gcode_M42() { #endif // Z_MIN_PROBE_REPEATABILITY_TEST -#if ENABLED(AUTO_BED_LEVELING_UBL) && ENABLED(UBL_G26_MESH_EDITING) +#if ENABLED(AUTO_BED_LEVELING_UBL) && ENABLED(UBL_G26_MESH_VALIDATION) inline void gcode_M49() { ubl.g26_debug_flag ^= true; @@ -6621,7 +6621,7 @@ inline void gcode_M42() { serialprintPGM(ubl.g26_debug_flag ? PSTR("on.") : PSTR("off.")); } -#endif // AUTO_BED_LEVELING_UBL && UBL_G26_MESH_EDITING +#endif // AUTO_BED_LEVELING_UBL && UBL_G26_MESH_VALIDATION /** * M75: Start print timer @@ -10096,7 +10096,7 @@ void process_next_command() { break; #endif // INCH_MODE_SUPPORT - #if ENABLED(AUTO_BED_LEVELING_UBL) && ENABLED(UBL_G26_MESH_EDITING) + #if ENABLED(AUTO_BED_LEVELING_UBL) && ENABLED(UBL_G26_MESH_VALIDATION) case 26: // G26: Mesh Validation Pattern generation gcode_G26(); break; @@ -10248,11 +10248,11 @@ void process_next_command() { break; #endif // Z_MIN_PROBE_REPEATABILITY_TEST - #if ENABLED(AUTO_BED_LEVELING_UBL) && ENABLED(UBL_G26_MESH_EDITING) + #if ENABLED(AUTO_BED_LEVELING_UBL) && ENABLED(UBL_G26_MESH_VALIDATION) case 49: // M49: Turn on or off G26 debug flag for verbose output gcode_M49(); break; - #endif // AUTO_BED_LEVELING_UBL && UBL_G26_MESH_EDITING + #endif // AUTO_BED_LEVELING_UBL && UBL_G26_MESH_VALIDATION case 75: // M75: Start print timer gcode_M75(); break; diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index a63bbfdad..cc466b233 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -157,7 +157,9 @@ #elif defined(UBL_MESH_NUM_X_POINTS) || defined(UBL_MESH_NUM_Y_POINTS) #error "UBL_MESH_NUM_[XY]_POINTS is now GRID_MAX_POINTS_[XY]. Please update your configuration." #elif defined(UBL_MESH_EDIT_ENABLED) - #error "UBL_MESH_EDIT_ENABLED is now UBL_G26_MESH_EDITING. Please update your configuration." + #error "UBL_MESH_EDIT_ENABLED is now UBL_G26_MESH_VALIDATION. Please update your configuration." +#elif defined(UBL_MESH_EDITING) + #error "UBL_MESH_EDITING is now UBL_G26_MESH_VALIDATION. Please update your configuration." #elif defined(BEEPER) #error "BEEPER is now BEEPER_PIN. Please update your pins definitions." #elif defined(SDCARDDETECT) diff --git a/Marlin/example_configurations/Cartesio/Configuration.h b/Marlin/example_configurations/Cartesio/Configuration.h index dc247b68f..61cfd8379 100644 --- a/Marlin/example_configurations/Cartesio/Configuration.h +++ b/Marlin/example_configurations/Cartesio/Configuration.h @@ -884,7 +884,8 @@ #define UBL_PROBE_PT_2_Y 20 #define UBL_PROBE_PT_3_X 180 #define UBL_PROBE_PT_3_Y 20 - //#define UBL_G26_MESH_EDITING // Enable G26 mesh editing + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation + #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle #elif ENABLED(MESH_BED_LEVELING) diff --git a/Marlin/example_configurations/Felix/Configuration.h b/Marlin/example_configurations/Felix/Configuration.h index 55cee75a7..a6818fffb 100644 --- a/Marlin/example_configurations/Felix/Configuration.h +++ b/Marlin/example_configurations/Felix/Configuration.h @@ -868,7 +868,8 @@ #define UBL_PROBE_PT_2_Y 20 #define UBL_PROBE_PT_3_X 180 #define UBL_PROBE_PT_3_Y 20 - //#define UBL_G26_MESH_EDITING // Enable G26 mesh editing + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation + #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle #elif ENABLED(MESH_BED_LEVELING) diff --git a/Marlin/example_configurations/Felix/DUAL/Configuration.h b/Marlin/example_configurations/Felix/DUAL/Configuration.h index 6c967aeff..3ae6ef145 100644 --- a/Marlin/example_configurations/Felix/DUAL/Configuration.h +++ b/Marlin/example_configurations/Felix/DUAL/Configuration.h @@ -868,7 +868,8 @@ #define UBL_PROBE_PT_2_Y 20 #define UBL_PROBE_PT_3_X 180 #define UBL_PROBE_PT_3_Y 20 - //#define UBL_G26_MESH_EDITING // Enable G26 mesh editing + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation + #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle #elif ENABLED(MESH_BED_LEVELING) diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h index c6e7d8774..85bf48ea5 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h @@ -890,7 +890,8 @@ #define UBL_PROBE_PT_2_Y 25 #define UBL_PROBE_PT_3_X 180 #define UBL_PROBE_PT_3_Y 25 - #define UBL_G26_MESH_EDITING // Enable G26 mesh editing + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation + #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle #elif ENABLED(MESH_BED_LEVELING) diff --git a/Marlin/example_configurations/Hephestos/Configuration.h b/Marlin/example_configurations/Hephestos/Configuration.h index 21395ffe0..1627a7380 100644 --- a/Marlin/example_configurations/Hephestos/Configuration.h +++ b/Marlin/example_configurations/Hephestos/Configuration.h @@ -876,7 +876,8 @@ #define UBL_PROBE_PT_2_Y 20 #define UBL_PROBE_PT_3_X 180 #define UBL_PROBE_PT_3_Y 20 - //#define UBL_G26_MESH_EDITING // Enable G26 mesh editing + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation + #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle #elif ENABLED(MESH_BED_LEVELING) diff --git a/Marlin/example_configurations/Hephestos_2/Configuration.h b/Marlin/example_configurations/Hephestos_2/Configuration.h index 48623dcd3..832a06e9b 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration.h @@ -879,7 +879,8 @@ #define UBL_PROBE_PT_2_Y 20 #define UBL_PROBE_PT_3_X 180 #define UBL_PROBE_PT_3_Y 20 - //#define UBL_G26_MESH_EDITING // Enable G26 mesh editing + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation + #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle #elif ENABLED(MESH_BED_LEVELING) diff --git a/Marlin/example_configurations/K8200/Configuration.h b/Marlin/example_configurations/K8200/Configuration.h index 799a405ca..953582821 100644 --- a/Marlin/example_configurations/K8200/Configuration.h +++ b/Marlin/example_configurations/K8200/Configuration.h @@ -914,7 +914,8 @@ #define UBL_PROBE_PT_2_Y 20 #define UBL_PROBE_PT_3_X 180 #define UBL_PROBE_PT_3_Y 20 - //#define UBL_G26_MESH_EDITING // Enable G26 mesh editing + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation + #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle #elif ENABLED(MESH_BED_LEVELING) diff --git a/Marlin/example_configurations/K8400/Configuration.h b/Marlin/example_configurations/K8400/Configuration.h index f356ebd86..1835a8a83 100644 --- a/Marlin/example_configurations/K8400/Configuration.h +++ b/Marlin/example_configurations/K8400/Configuration.h @@ -885,7 +885,8 @@ #define UBL_PROBE_PT_2_Y 20 #define UBL_PROBE_PT_3_X 180 #define UBL_PROBE_PT_3_Y 20 - //#define UBL_G26_MESH_EDITING // Enable G26 mesh editing + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation + #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle #elif ENABLED(MESH_BED_LEVELING) diff --git a/Marlin/example_configurations/K8400/Dual-head/Configuration.h b/Marlin/example_configurations/K8400/Dual-head/Configuration.h index ddf10b4ef..b359a5e1c 100644 --- a/Marlin/example_configurations/K8400/Dual-head/Configuration.h +++ b/Marlin/example_configurations/K8400/Dual-head/Configuration.h @@ -885,7 +885,8 @@ #define UBL_PROBE_PT_2_Y 20 #define UBL_PROBE_PT_3_X 180 #define UBL_PROBE_PT_3_Y 20 - //#define UBL_G26_MESH_EDITING // Enable G26 mesh editing + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation + #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle #elif ENABLED(MESH_BED_LEVELING) diff --git a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h index 7b4b0e4b8..cf42a25d5 100644 --- a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h +++ b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h @@ -885,7 +885,8 @@ #define UBL_PROBE_PT_2_Y 20 #define UBL_PROBE_PT_3_X 180 #define UBL_PROBE_PT_3_Y 20 - //#define UBL_G26_MESH_EDITING // Enable G26 mesh editing + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation + #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle #elif ENABLED(MESH_BED_LEVELING) diff --git a/Marlin/example_configurations/RigidBot/Configuration.h b/Marlin/example_configurations/RigidBot/Configuration.h index 476f5caa8..22c8ac621 100644 --- a/Marlin/example_configurations/RigidBot/Configuration.h +++ b/Marlin/example_configurations/RigidBot/Configuration.h @@ -884,7 +884,8 @@ #define UBL_PROBE_PT_2_Y 20 #define UBL_PROBE_PT_3_X 180 #define UBL_PROBE_PT_3_Y 20 - //#define UBL_G26_MESH_EDITING // Enable G26 mesh editing + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation + #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle #elif ENABLED(MESH_BED_LEVELING) diff --git a/Marlin/example_configurations/SCARA/Configuration.h b/Marlin/example_configurations/SCARA/Configuration.h index a1f59cbcb..0d86d1338 100644 --- a/Marlin/example_configurations/SCARA/Configuration.h +++ b/Marlin/example_configurations/SCARA/Configuration.h @@ -901,8 +901,9 @@ #define UBL_PROBE_PT_2_Y 20 #define UBL_PROBE_PT_3_X 180 #define UBL_PROBE_PT_3_Y 20 - //#define UBL_G26_MESH_EDITING // Enable G26 mesh editing - + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation + #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle + #elif ENABLED(MESH_BED_LEVELING) //=========================================================================== diff --git a/Marlin/example_configurations/TAZ4/Configuration.h b/Marlin/example_configurations/TAZ4/Configuration.h index c5af5592a..2492fc9ac 100644 --- a/Marlin/example_configurations/TAZ4/Configuration.h +++ b/Marlin/example_configurations/TAZ4/Configuration.h @@ -905,8 +905,9 @@ #define UBL_PROBE_PT_2_Y 20 #define UBL_PROBE_PT_3_X 180 #define UBL_PROBE_PT_3_Y 20 - //#define UBL_G26_MESH_EDITING // Enable G26 mesh editing - + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation + #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle + #elif ENABLED(MESH_BED_LEVELING) //=========================================================================== diff --git a/Marlin/example_configurations/TinyBoy2/Configuration.h b/Marlin/example_configurations/TinyBoy2/Configuration.h index b93b90d0d..1bdc0f94e 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration.h @@ -941,8 +941,9 @@ #define UBL_PROBE_PT_2_Y 20 #define UBL_PROBE_PT_3_X 180 #define UBL_PROBE_PT_3_Y 20 - //#define UBL_G26_MESH_EDITING // Enable G26 mesh editing - + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation + #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle + #elif ENABLED(MESH_BED_LEVELING) //=========================================================================== diff --git a/Marlin/example_configurations/WITBOX/Configuration.h b/Marlin/example_configurations/WITBOX/Configuration.h index 3dcf34e70..cb06b543c 100644 --- a/Marlin/example_configurations/WITBOX/Configuration.h +++ b/Marlin/example_configurations/WITBOX/Configuration.h @@ -876,8 +876,9 @@ #define UBL_PROBE_PT_2_Y 20 #define UBL_PROBE_PT_3_X 180 #define UBL_PROBE_PT_3_Y 20 - //#define UBL_G26_MESH_EDITING // Enable G26 mesh editing - + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation + #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle + #elif ENABLED(MESH_BED_LEVELING) //=========================================================================== diff --git a/Marlin/example_configurations/adafruit/ST7565/Configuration.h b/Marlin/example_configurations/adafruit/ST7565/Configuration.h index 3b9f667d8..e67befb2e 100644 --- a/Marlin/example_configurations/adafruit/ST7565/Configuration.h +++ b/Marlin/example_configurations/adafruit/ST7565/Configuration.h @@ -885,7 +885,8 @@ #define UBL_PROBE_PT_2_Y 20 #define UBL_PROBE_PT_3_X 180 #define UBL_PROBE_PT_3_Y 20 - //#define UBL_G26_MESH_EDITING // Enable G26 mesh editing + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation + #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle #elif ENABLED(MESH_BED_LEVELING) diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h index b23bb75f6..ddfb6bab8 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h @@ -1004,7 +1004,8 @@ #define UBL_PROBE_PT_2_Y 20 #define UBL_PROBE_PT_3_X 180 #define UBL_PROBE_PT_3_Y 20 - //#define UBL_G26_MESH_EDITING // Enable G26 mesh editing + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation + #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle #elif ENABLED(MESH_BED_LEVELING) diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h index 9838387b4..564d4913b 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h @@ -1006,7 +1006,8 @@ #define UBL_PROBE_PT_2_Y 20 #define UBL_PROBE_PT_3_X 180 #define UBL_PROBE_PT_3_Y 20 - //#define UBL_G26_MESH_EDITING // Enable G26 mesh editing + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation + #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle #elif ENABLED(MESH_BED_LEVELING) diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index dee93545c..48290d5e3 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -995,7 +995,8 @@ #define UBL_PROBE_PT_2_Y 20 #define UBL_PROBE_PT_3_X 180 #define UBL_PROBE_PT_3_Y 20 - //#define UBL_G26_MESH_EDITING // Enable G26 mesh editing + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation + #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle #elif ENABLED(MESH_BED_LEVELING) diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index 5af56f449..d27e47c85 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -998,7 +998,8 @@ #define UBL_PROBE_PT_2_Y 20 #define UBL_PROBE_PT_3_X 180 #define UBL_PROBE_PT_3_Y 20 - //#define UBL_G26_MESH_EDITING // Enable G26 mesh editing + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation + #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle #elif ENABLED(MESH_BED_LEVELING) diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration.h b/Marlin/example_configurations/delta/kossel_pro/Configuration.h index 1a623d6b0..4e2bea190 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration.h @@ -1004,7 +1004,8 @@ #define UBL_PROBE_PT_2_Y 20 #define UBL_PROBE_PT_3_X 180 #define UBL_PROBE_PT_3_Y 20 - //#define UBL_G26_MESH_EDITING // Enable G26 mesh editing + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation + #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle #elif ENABLED(MESH_BED_LEVELING) diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration.h b/Marlin/example_configurations/delta/kossel_xl/Configuration.h index fa9c00692..b76beed37 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration.h @@ -1062,7 +1062,8 @@ #define UBL_PROBE_PT_2_Y 20 #define UBL_PROBE_PT_3_X 180 #define UBL_PROBE_PT_3_Y 20 - //#define UBL_G26_MESH_EDITING // Enable G26 mesh editing + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation + #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle #elif ENABLED(MESH_BED_LEVELING) diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h index 776b9e9dd..94cb081e7 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h @@ -902,7 +902,8 @@ #define UBL_PROBE_PT_2_Y 63 #define UBL_PROBE_PT_3_X 348 #define UBL_PROBE_PT_3_Y 211 - #define UBL_G26_MESH_EDITING // Enable G26 mesh editing + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation + #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle #elif ENABLED(MESH_BED_LEVELING) diff --git a/Marlin/example_configurations/makibox/Configuration.h b/Marlin/example_configurations/makibox/Configuration.h index 56cec59aa..ca2052c8d 100644 --- a/Marlin/example_configurations/makibox/Configuration.h +++ b/Marlin/example_configurations/makibox/Configuration.h @@ -888,7 +888,8 @@ #define UBL_PROBE_PT_2_Y 20 #define UBL_PROBE_PT_3_X 180 #define UBL_PROBE_PT_3_Y 20 - //#define UBL_G26_MESH_EDITING // Enable G26 mesh editing + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation + #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle #elif ENABLED(MESH_BED_LEVELING) diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration.h b/Marlin/example_configurations/tvrrug/Round2/Configuration.h index 53d75f1f6..550916356 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration.h @@ -881,8 +881,9 @@ #define UBL_PROBE_PT_2_Y 20 #define UBL_PROBE_PT_3_X 180 #define UBL_PROBE_PT_3_Y 20 - //#define UBL_G26_MESH_EDITING // Enable G26 mesh editing - + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation + #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle + #elif ENABLED(MESH_BED_LEVELING) //=========================================================================== diff --git a/Marlin/example_configurations/wt150/Configuration.h b/Marlin/example_configurations/wt150/Configuration.h index 2c1e4cfb6..3b8e8b8e7 100644 --- a/Marlin/example_configurations/wt150/Configuration.h +++ b/Marlin/example_configurations/wt150/Configuration.h @@ -890,7 +890,8 @@ #define UBL_PROBE_PT_2_Y 20 #define UBL_PROBE_PT_3_X 180 #define UBL_PROBE_PT_3_Y 20 - //#define UBL_G26_MESH_EDITING // Enable G26 mesh editing + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation + #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle #elif ENABLED(MESH_BED_LEVELING) From 2c309a8f7c511fd16a60cf9a6eab99a0f7078f6c Mon Sep 17 00:00:00 2001 From: MagoKimbra Date: Sun, 21 May 2017 19:01:44 +0200 Subject: [PATCH 123/189] Fix set_lcd_contrast --- Marlin/ultralcd.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 868846952..7edbdc519 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -4052,7 +4052,7 @@ void lcd_reset_alert_level() { lcd_status_message_level = 0; } #if HAS_LCD_CONTRAST - void set_lcd_contrast(const int value) { + void set_lcd_contrast(const uint16_t value) { lcd_contrast = constrain(value, LCD_CONTRAST_MIN, LCD_CONTRAST_MAX); u8g.setContrast(lcd_contrast); } From ba5910ab6cc2ff16b0ec487934d1a4307148dda5 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 21 May 2017 12:35:06 -0500 Subject: [PATCH 124/189] Constrain LCD status message rendering --- Marlin/ultralcd_impl_DOGM.h | 6 ++++-- Marlin/ultralcd_impl_HD44780.h | 3 ++- 2 files changed, 6 insertions(+), 3 deletions(-) diff --git a/Marlin/ultralcd_impl_DOGM.h b/Marlin/ultralcd_impl_DOGM.h index 8664c64b8..f37c7b18b 100644 --- a/Marlin/ultralcd_impl_DOGM.h +++ b/Marlin/ultralcd_impl_DOGM.h @@ -634,7 +634,8 @@ static void lcd_implementation_status_screen() { #if ENABLED(FILAMENT_LCD_DISPLAY) && ENABLED(SDSUPPORT) if (PENDING(millis(), previous_lcd_status_ms + 5000UL)) { //Display both Status message line and Filament display on the last line - lcd_print(lcd_status_message); + const char *str = lcd_status_message; + for (uint8_t i = 0; char c = str[i] && i < LCD_WIDTH; ++i) lcd_print(c); } else { lcd_printPGM(PSTR(LCD_STR_FILAM_DIA)); @@ -646,7 +647,8 @@ static void lcd_implementation_status_screen() { u8g.print('%'); } #else - lcd_print(lcd_status_message); + const char *str = lcd_status_message; + for (uint8_t i = 0; char c = str[i] && i < LCD_WIDTH; ++i) lcd_print(c); #endif } } diff --git a/Marlin/ultralcd_impl_HD44780.h b/Marlin/ultralcd_impl_HD44780.h index 0f8e03493..eef964e8d 100644 --- a/Marlin/ultralcd_impl_HD44780.h +++ b/Marlin/ultralcd_impl_HD44780.h @@ -795,7 +795,8 @@ static void lcd_implementation_status_screen() { #endif // FILAMENT_LCD_DISPLAY && SDSUPPORT - lcd_print(lcd_status_message); + const char *str = lcd_status_message; + for (uint8_t i = 0; char c = str[i] && i < LCD_WIDTH; ++i) lcd_print(c); } #if ENABLED(ULTIPANEL) From 76af9ac7c568187da21ae204bc987bc80d5f9452 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 21 May 2017 12:51:58 -0500 Subject: [PATCH 125/189] tweaks --- Marlin/ultralcd_impl_DOGM.h | 8 ++++++-- Marlin/ultralcd_impl_HD44780.h | 8 +++++--- 2 files changed, 11 insertions(+), 5 deletions(-) diff --git a/Marlin/ultralcd_impl_DOGM.h b/Marlin/ultralcd_impl_DOGM.h index f37c7b18b..b4ee92c5f 100644 --- a/Marlin/ultralcd_impl_DOGM.h +++ b/Marlin/ultralcd_impl_DOGM.h @@ -635,7 +635,9 @@ static void lcd_implementation_status_screen() { #if ENABLED(FILAMENT_LCD_DISPLAY) && ENABLED(SDSUPPORT) if (PENDING(millis(), previous_lcd_status_ms + 5000UL)) { //Display both Status message line and Filament display on the last line const char *str = lcd_status_message; - for (uint8_t i = 0; char c = str[i] && i < LCD_WIDTH; ++i) lcd_print(c); + uint8_t i = LCD_WIDTH; + char c; + while (i-- && (c = *str++)) lcd_print(c); } else { lcd_printPGM(PSTR(LCD_STR_FILAM_DIA)); @@ -648,7 +650,9 @@ static void lcd_implementation_status_screen() { } #else const char *str = lcd_status_message; - for (uint8_t i = 0; char c = str[i] && i < LCD_WIDTH; ++i) lcd_print(c); + uint8_t i = LCD_WIDTH; + char c; + while (i-- && (c = *str++)) lcd_print(c); #endif } } diff --git a/Marlin/ultralcd_impl_HD44780.h b/Marlin/ultralcd_impl_HD44780.h index eef964e8d..cbad9698e 100644 --- a/Marlin/ultralcd_impl_HD44780.h +++ b/Marlin/ultralcd_impl_HD44780.h @@ -386,10 +386,10 @@ void lcd_printPGM(const char *str) { } void lcd_print(const char* const str) { - for (uint8_t i = 0; char c = str[i]; ++i) charset_mapper(c); + for (uint8_t i = 0; const char c = str[i]; ++i) charset_mapper(c); } -void lcd_print(char c) { charset_mapper(c); } +void lcd_print(const char c) { charset_mapper(c); } #if ENABLED(SHOW_BOOTSCREEN) @@ -796,7 +796,9 @@ static void lcd_implementation_status_screen() { #endif // FILAMENT_LCD_DISPLAY && SDSUPPORT const char *str = lcd_status_message; - for (uint8_t i = 0; char c = str[i] && i < LCD_WIDTH; ++i) lcd_print(c); + uint8_t i = LCD_WIDTH; + char c; + while (i-- && (c = *str++)) lcd_print(c); } #if ENABLED(ULTIPANEL) From 5e8892d6b5eba32496b305418f9ba182e246e126 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 21 May 2017 12:52:44 -0500 Subject: [PATCH 126/189] Show Restore Failsafe item with EEPROM off --- Marlin/ultralcd.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 7edbdc519..7edb0fef5 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -2507,9 +2507,12 @@ void kill_screen(const char* lcd_msg) { #if ENABLED(EEPROM_SETTINGS) MENU_ITEM(function, MSG_STORE_EEPROM, lcd_store_settings); MENU_ITEM(function, MSG_LOAD_EEPROM, lcd_load_settings); - MENU_ITEM(function, MSG_RESTORE_FAILSAFE, lcd_factory_settings); + #endif + MENU_ITEM(function, MSG_RESTORE_FAILSAFE, lcd_factory_settings); + #if ENABLED(EEPROM_SETTINGS) MENU_ITEM(gcode, MSG_INIT_EEPROM, PSTR("M502\nM500")); // TODO: Add "Are You Sure?" step #endif + END_MENU(); } From 3b4116e73b90cd468ada980d5321b2e534208473 Mon Sep 17 00:00:00 2001 From: cbusillo Date: Sun, 21 May 2017 13:54:20 -0400 Subject: [PATCH 127/189] missing enable for M605 for duplication mode I believe gcode_M605 will not be called when using DUAL_NOZZLE_DUPLICATION_MODE without this change. --- Marlin/Marlin_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 89e4d0798..cef1ca4c9 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -10676,7 +10676,7 @@ void process_next_command() { break; #endif // FILAMENT_CHANGE_FEATURE - #if ENABLED(DUAL_X_CARRIAGE) + #if ENABLED(DUAL_X_CARRIAGE) || ENABLED(DUAL_NOZZLE_DUPLICATION_MODE) case 605: // M605: Set Dual X Carriage movement mode gcode_M605(); break; From 3129260c44656107dfc968c0cd41f6fa615314ea Mon Sep 17 00:00:00 2001 From: Roxy-3D Date: Sun, 21 May 2017 22:09:51 -0500 Subject: [PATCH 128/189] Misc. Clean Up (#6822) * Misc. Clean Up Mostly UBL related clean up. - But fixed a bug in the thermistortables. - Made G26 more responsive to user aborts. - Added sanity checks for older name for UBL_MESH_VALIDATION. - Made G29 P4 able to edit invalidated mesh points - Restore a reasonable Fade Height for UBL when creating new state information - Get UBL's Topology Map to look a little bit better - Make sure the user doesn't see a blank screen when doing Mesh Editing. * Huh??? GitHub Desktop screwed up! * get the planner object in scope * Fix out of scope z_fade_height * Travis timed out... I need a change so I can force a new commit and sync. --- Marlin/G26_Mesh_Validation_Tool.cpp | 96 ++++++++++++++--------------- Marlin/SanityCheck.h | 2 + Marlin/thermistortables.h | 2 +- Marlin/ubl.cpp | 13 ++-- Marlin/ubl_G29.cpp | 82 +++++++++++++----------- Marlin/ultralcd.cpp | 2 + 6 files changed, 106 insertions(+), 91 deletions(-) diff --git a/Marlin/G26_Mesh_Validation_Tool.cpp b/Marlin/G26_Mesh_Validation_Tool.cpp index d605cc70e..ff329bf16 100644 --- a/Marlin/G26_Mesh_Validation_Tool.cpp +++ b/Marlin/G26_Mesh_Validation_Tool.cpp @@ -144,7 +144,7 @@ void un_retract_filament(float where[XYZE]); void retract_filament(float where[XYZE]); - void look_for_lines_to_connect(); + bool look_for_lines_to_connect(); bool parse_G26_parameters(); void move_to(const float&, const float&, const float&, const float&) ; void print_line_from_here_to_there(const float&, const float&, const float&, const float&, const float&, const float&); @@ -249,24 +249,6 @@ } do { - - if (ubl_lcd_clicked()) { // Check if the user wants to stop the Mesh Validation - #if ENABLED(ULTRA_LCD) - lcd_setstatuspgm(PSTR("Mesh Validation Stopped."), 99); - lcd_quick_feedback(); - #endif - while (!ubl_lcd_clicked()) { // Wait until the user is done pressing the - idle(); // Encoder Wheel if that is why we are leaving - lcd_reset_alert_level(); - lcd_setstatuspgm(PSTR("")); - } - while (ubl_lcd_clicked()) { // Wait until the user is done pressing the - idle(); // Encoder Wheel if that is why we are leaving - lcd_setstatuspgm(PSTR("Unpress Wheel"), 99); - } - goto LEAVE; - } - location = continue_with_closest ? find_closest_circle_to_print(current_position[X_AXIS], current_position[Y_AXIS]) : find_closest_circle_to_print(x_pos, y_pos); // Find the closest Mesh Intersection to where we are now. @@ -317,6 +299,27 @@ } for (tmp = start_angle; tmp < end_angle - 0.1; tmp += 30.0) { + + // this sequence to detect an ubl_lcd_clicked() debounce it and leave if it is + // a Press and Hold is repeated in a lot of places (including ubl_G29.cpp). This + // should be redone and compressed. + if (ubl_lcd_clicked()) { // Check if the user wants to stop the Mesh Validation + #if ENABLED(ULTRA_LCD) + lcd_setstatuspgm(PSTR("Mesh Validation Stopped."), 99); + lcd_quick_feedback(); + #endif + while (!ubl_lcd_clicked()) { // Wait until the user is done pressing the + idle(); // Encoder Wheel if that is why we are leaving + lcd_reset_alert_level(); + lcd_setstatuspgm(PSTR("")); + } + while (ubl_lcd_clicked()) { // Wait until the user is done pressing the + idle(); // Encoder Wheel if that is why we are leaving + lcd_setstatuspgm(PSTR("Unpress Wheel"), 99); + } + goto LEAVE; + } + int tmp_div_30 = tmp / 30.0; if (tmp_div_30 < 0) tmp_div_30 += 360 / 30; if (tmp_div_30 > 11) tmp_div_30 -= 360 / 30; @@ -349,14 +352,9 @@ print_line_from_here_to_there(LOGICAL_X_POSITION(x), LOGICAL_Y_POSITION(y), layer_height, LOGICAL_X_POSITION(xe), LOGICAL_Y_POSITION(ye), layer_height); } - - //debug_current_and_destination(PSTR("Looking for lines to connect.")); - look_for_lines_to_connect(); - //debug_current_and_destination(PSTR("Done with line connect.")); + if (look_for_lines_to_connect()) + goto LEAVE; } - - //debug_current_and_destination(PSTR("Done with current circle.")); - } while (--g26_repeats && location.x_index >= 0 && location.y_index >= 0); LEAVE: @@ -432,12 +430,32 @@ return return_val; } - void look_for_lines_to_connect() { + bool look_for_lines_to_connect() { float sx, sy, ex, ey; for (uint8_t i = 0; i < GRID_MAX_POINTS_X; i++) { for (uint8_t j = 0; j < GRID_MAX_POINTS_Y; j++) { + // this sequence to detect an ubl_lcd_clicked() debounce it and leave if it is + // a Press and Hold is repeated in a lot of places (including ubl_G29.cpp). This + // should be redone and compressed. + if (ubl_lcd_clicked()) { // Check if the user wants to stop the Mesh Validation + #if ENABLED(ULTRA_LCD) + lcd_setstatuspgm(PSTR("Mesh Validation Stopped."), 99); + lcd_quick_feedback(); + #endif + while (!ubl_lcd_clicked()) { // Wait until the user is done pressing the + idle(); // Encoder Wheel if that is why we are leaving + lcd_reset_alert_level(); + lcd_setstatuspgm(PSTR("")); + } + while (ubl_lcd_clicked()) { // Wait until the user is done pressing the + idle(); // Encoder Wheel if that is why we are leaving + lcd_setstatuspgm(PSTR("Unpress Wheel"), 99); + } + return true; + } + if (i < GRID_MAX_POINTS_X) { // We can't connect to anything to the right than GRID_MAX_POINTS_X. // This is already a half circle because we are at the edge of the bed. @@ -509,6 +527,7 @@ } } } + return false; } void move_to(const float &x, const float &y, const float &z, const float &e_delta) { @@ -517,11 +536,7 @@ bool has_xy_component = (x != current_position[X_AXIS] || y != current_position[Y_AXIS]); // Check if X or Y is involved in the movement. - //if (ubl.g26_debug_flag) SERIAL_ECHOLNPAIR("in move_to() has_xy_component:", (int)has_xy_component); - if (z != last_z) { - //if (ubl.g26_debug_flag) SERIAL_ECHOLNPAIR("in move_to() changing Z to ", (int)z); - last_z = z; feed_value = planner.max_feedrate_mm_s[Z_AXIS]/(3.0); // Base the feed rate off of the configured Z_AXIS feed rate @@ -534,8 +549,6 @@ stepper.synchronize(); set_destination_to_current(); - - //if (ubl.g26_debug_flag) debug_current_and_destination(PSTR(" in move_to() done with Z move")); } // Check if X or Y is involved in the movement. @@ -548,12 +561,8 @@ destination[Y_AXIS] = y; destination[E_AXIS] += e_delta; - //if (ubl.g26_debug_flag) debug_current_and_destination(PSTR(" in move_to() doing last move")); - G26_line_to_destination(feed_value); - //if (ubl.g26_debug_flag) debug_current_and_destination(PSTR(" in move_to() after last move")); - stepper.synchronize(); set_destination_to_current(); @@ -562,9 +571,7 @@ void retract_filament(float where[XYZE]) { if (!g26_retracted) { // Only retract if we are not already retracted! g26_retracted = true; - //if (ubl.g26_debug_flag) SERIAL_ECHOLNPGM(" Decided to do retract."); move_to(where[X_AXIS], where[Y_AXIS], where[Z_AXIS], -1.0 * retraction_multiplier); - //if (ubl.g26_debug_flag) SERIAL_ECHOLNPGM(" Retraction done."); } } @@ -572,7 +579,6 @@ if (g26_retracted) { // Only un-retract if we are retracted. move_to(where[X_AXIS], where[Y_AXIS], where[Z_AXIS], 1.2 * retraction_multiplier); g26_retracted = false; - //if (ubl.g26_debug_flag) SERIAL_ECHOLNPGM(" unretract done."); } } @@ -605,7 +611,6 @@ // If the end point of the line is closer to the nozzle, flip the direction, // moving from the end to the start. On very small lines the optimization isn't worth it. if (dist_end < dist_start && (SIZE_OF_INTERSECTION_CIRCLES) < abs(line_length)) { - //if (ubl.g26_debug_flag) SERIAL_ECHOLNPGM(" Reversing start and end of print_line_from_here_to_there()"); return print_line_from_here_to_there(ex, ey, ez, sx, sy, sz); } @@ -613,9 +618,6 @@ if (dist_start > 2.0) { retract_filament(destination); - //if (ubl.g26_debug_flag) SERIAL_ECHOLNPGM(" filament retracted."); - - //if (ubl.g26_debug_flag) SERIAL_ECHOLNPGM(" Z bumping by 0.500 to minimize scraping."); //todo: parameterize the bump height with a define move_to(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS] + 0.500, 0.0); // Z bump to minimize scraping move_to(sx, sy, sz + 0.500, 0.0); // Get to the starting point with no extrusion while bumped @@ -626,11 +628,6 @@ const float e_pos_delta = line_length * g26_e_axis_feedrate * extrusion_multiplier; un_retract_filament(destination); - - //if (ubl.g26_debug_flag) { - // SERIAL_ECHOLNPGM(" doing printing move."); - // debug_current_and_destination(PSTR("doing final move_to() inside print_line_from_here_to_there()")); - //} move_to(ex, ey, ez, e_pos_delta); // Get to the ending point with an appropriate amount of extrusion } @@ -754,7 +751,6 @@ } bool exit_from_g26() { - //strcpy(lcd_status_message, "Leaving G26"); // We can't do lcd_setstatus() without having it continue; lcd_reset_alert_level(); lcd_setstatuspgm(PSTR("Leaving G26")); while (ubl_lcd_clicked()) idle(); diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index cc466b233..952200d14 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -160,6 +160,8 @@ #error "UBL_MESH_EDIT_ENABLED is now UBL_G26_MESH_VALIDATION. Please update your configuration." #elif defined(UBL_MESH_EDITING) #error "UBL_MESH_EDITING is now UBL_G26_MESH_VALIDATION. Please update your configuration." +#elif defined(BLTOUCH_HEATERS_OFF) + #error "BLTOUCH_HEATERS_OFF is now PROBING_HEATERS_OFF. Please update your configuration." #elif defined(BEEPER) #error "BEEPER is now BEEPER_PIN. Please update your pins definitions." #elif defined(SDCARDDETECT) diff --git a/Marlin/thermistortables.h b/Marlin/thermistortables.h index 3777cf2e4..164afa5ea 100644 --- a/Marlin/thermistortables.h +++ b/Marlin/thermistortables.h @@ -89,7 +89,7 @@ #include "thermistortable_52.h" #endif #if ANY_THERMISTOR_IS(55) // 100k ATC Semitec 104GT-2 (Used on ParCan) (WITH 1kohm RESISTOR FOR PULLUP, R9 ON SANGUINOLOLU! NOT FOR 4.7kohm PULLUP! THIS IS NOT NORMAL!) - #include "thermistortable_53.h" + #include "thermistortable_55.h" #endif #if ANY_THERMISTOR_IS(60) // Maker's Tool Works Kapton Bed Thermistor #include "thermistortable_60.h" diff --git a/Marlin/ubl.cpp b/Marlin/ubl.cpp index 8ca43c5be..8e6190953 100644 --- a/Marlin/ubl.cpp +++ b/Marlin/ubl.cpp @@ -29,6 +29,8 @@ #include "hex_print_routines.h" #include "temperature.h" + extern Planner planner; + /** * These support functions allow the use of large bit arrays of flags that take very * little RAM. Currently they are limited to being 16x16 in size. Changing the declaration @@ -76,7 +78,7 @@ volatile int unified_bed_leveling::encoder_diff; unified_bed_leveling::unified_bed_leveling() { - ubl_cnt++; // Debug counter to insure we only have one UBL object present in memory. + ubl_cnt++; // Debug counter to insure we only have one UBL object present in memory. We can eliminate this (and all references to ubl_cnt) very soon. reset(); } @@ -84,9 +86,10 @@ state.active = false; state.z_offset = 0; state.storage_slot = -1; - + #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) + planner.z_fade_height = 10.0; + #endif ZERO(z_values); - last_specified_z = -999.9; } @@ -100,7 +103,7 @@ void unified_bed_leveling::display_map(const int map_type) { const bool map0 = map_type == 0; - constexpr uint8_t spaces = 9 * (GRID_MAX_POINTS_X - 2); + constexpr uint8_t spaces = 8 * (GRID_MAX_POINTS_X - 2); if (map0) { SERIAL_PROTOCOLLNPGM("\nBed Topography Report:\n"); @@ -126,7 +129,7 @@ const float f = z_values[i][j]; if (isnan(f)) { - serialprintPGM(map0 ? PSTR(" . ") : PSTR("NAN")); + serialprintPGM(map0 ? PSTR(" . ") : PSTR("NAN")); } else { // if we don't do this, the columns won't line up nicely diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index b8b992baa..1b718dd64 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -1009,6 +1009,9 @@ } } + // this sequence to detect an ubl_lcd_clicked() debounce it and leave if it is + // a Press and Hold is repeated in a lot of places (including G26_Mesh_Validation.cpp). This + // should be redone and compressed. const millis_t nxt = millis() + 1500L; while (ubl_lcd_clicked()) { // debounce and watch for abort idle(); @@ -1327,10 +1330,9 @@ // Get our reference position. Either the nozzle or probe location. const float px = RAW_X_POSITION(lx) - (probe_as_reference == USE_PROBE_AS_REFERENCE ? X_PROBE_OFFSET_FROM_EXTRUDER : 0), - py = RAW_Y_POSITION(ly) - (probe_as_reference == USE_PROBE_AS_REFERENCE ? Y_PROBE_OFFSET_FROM_EXTRUDER : 0), - raw_x = RAW_CURRENT_POSITION(X), raw_y = RAW_CURRENT_POSITION(Y); + py = RAW_Y_POSITION(ly) - (probe_as_reference == USE_PROBE_AS_REFERENCE ? Y_PROBE_OFFSET_FROM_EXTRUDER : 0); - float closest = far_flag ? -99999.99 : 99999.99; + float best_so_far = far_flag ? -99999.99 : 99999.99; for (uint8_t i = 0; i < GRID_MAX_POINTS_X; i++) { for (uint8_t j = 0; j < GRID_MAX_POINTS_Y; j++) { @@ -1339,10 +1341,10 @@ || (type == REAL && !isnan(ubl.z_values[i][j])) || (type == SET_IN_BITMAP && is_bit_set(bits, i, j)) ) { - // We only get here if we found a Mesh Point of the specified type - const float mx = pgm_read_float(&ubl.mesh_index_to_xpos[i]), // Check if we can probe this mesh location + float raw_x = RAW_CURRENT_POSITION(X), raw_y = RAW_CURRENT_POSITION(Y); + const float mx = pgm_read_float(&ubl.mesh_index_to_xpos[i]), my = pgm_read_float(&ubl.mesh_index_to_ypos[j]); // If using the probe as the reference there are some unreachable locations. @@ -1352,10 +1354,10 @@ if (probe_as_reference ? !position_is_reachable_by_probe_raw_xy(mx, my) : !position_is_reachable_raw_xy(mx, my)) continue; - // Reachable. Check if it's the closest location to the nozzle. + // Reachable. Check if it's the best_so_far location to the nozzle. // Add in a weighting factor that considers the current location of the nozzle. - float distance = HYPOT(px - mx, py - my) + HYPOT(raw_x - mx, raw_y - my) * 0.1; + float distance = HYPOT(px - mx, py - my); /** * If doing the far_flag action, we want to be as far as possible @@ -1367,20 +1369,24 @@ if (far_flag) { for (uint8_t k = 0; k < GRID_MAX_POINTS_X; k++) { for (uint8_t l = 0; l < GRID_MAX_POINTS_Y; l++) { - if (!isnan(ubl.z_values[k][l])) { - distance += sq(i - k) * (MESH_X_DIST) * .05 - + sq(j - l) * (MESH_Y_DIST) * .05; + if (i != k && j != l && !isnan(ubl.z_values[k][l])) { +// distance += pow((float) abs(i - k) * (MESH_X_DIST), 2) + pow((float) abs(j - l) * (MESH_Y_DIST), 2); // working here + distance += HYPOT((MESH_X_DIST),(MESH_Y_DIST)) / log(HYPOT((i - k) * (MESH_X_DIST)+.001, (j - l) * (MESH_Y_DIST))+.001); } } } } + else + // factor in the distance from the current location for the normal case + // so the nozzle isn't running all over the bed. + distance += HYPOT(raw_x - mx, raw_y - my) * 0.1; // if far_flag, look for farthest point - if (far_flag == (distance > closest) && distance != closest) { - closest = distance; // We found a closer/farther location with + if (far_flag == (distance > best_so_far) && distance != best_so_far) { + best_so_far = distance; // We found a closer/farther location with out_mesh.x_index = i; // the specified type of mesh value. out_mesh.y_index = j; - out_mesh.distance = closest; + out_mesh.distance = best_so_far; } } } // for j @@ -1408,7 +1414,7 @@ LCD_MESSAGEPGM("Fine Tuning Mesh"); // TODO: Make translatable string - do_blocking_move_to_z(Z_CLEARANCE_DEPLOY_PROBE); + do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); do_blocking_move_to_xy(lx, ly); do { location = find_closest_mesh_point_of_type(SET_IN_BITMAP, lx, ly, USE_NOZZLE_AS_REFERENCE, not_done, false); @@ -1426,42 +1432,48 @@ float new_z = ubl.z_values[location.x_index][location.y_index]; - if (!isnan(new_z)) { //can't fine tune a point that hasn't been probed + if (isnan(new_z)) // if the mesh point is invalid, set it to 0.0 so it can be edited + new_z = 0.0; - do_blocking_move_to_z(Z_CLEARANCE_DEPLOY_PROBE); // Move the nozzle to where we are going to edit - do_blocking_move_to_xy(LOGICAL_X_POSITION(rawx), LOGICAL_Y_POSITION(rawy)); + do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); // Move the nozzle to where we are going to edit + do_blocking_move_to_xy(LOGICAL_X_POSITION(rawx), LOGICAL_Y_POSITION(rawy)); - new_z = floor(new_z * 1000.0) * 0.001; // Chop off digits after the 1000ths place + new_z = floor(new_z * 1000.0) * 0.001; // Chop off digits after the 1000ths place - KEEPALIVE_STATE(PAUSED_FOR_USER); - ubl.has_control_of_lcd_panel = true; + KEEPALIVE_STATE(PAUSED_FOR_USER); + ubl.has_control_of_lcd_panel = true; - if (do_ubl_mesh_map) ubl.display_map(map_type); // show the user which point is being adjusted + if (do_ubl_mesh_map) ubl.display_map(map_type); // show the user which point is being adjusted - lcd_implementation_clear(); + lcd_implementation_clear(); - lcd_mesh_edit_setup(new_z); + lcd_mesh_edit_setup(new_z); - do { - new_z = lcd_mesh_edit(); - idle(); - } while (!ubl_lcd_clicked()); + do { + new_z = lcd_mesh_edit(); + #ifdef UBL_MESH_EDIT_MOVES_Z + do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES+new_z); // Move the nozzle as the point is edited + #endif + idle(); + } while (!ubl_lcd_clicked()); - lcd_return_to_status(); + lcd_return_to_status(); - // The technique used here generates a race condition for the encoder click. - // It could get detected in lcd_mesh_edit (actually _lcd_mesh_fine_tune) or here. - // Let's work on specifying a proper API for the LCD ASAP, OK? - ubl.has_control_of_lcd_panel = true; - } + // The technique used here generates a race condition for the encoder click. + // It could get detected in lcd_mesh_edit (actually _lcd_mesh_fine_tune) or here. + // Let's work on specifying a proper API for the LCD ASAP, OK? + ubl.has_control_of_lcd_panel = true; + // this sequence to detect an ubl_lcd_clicked() debounce it and leave if it is + // a Press and Hold is repeated in a lot of places (including G26_Mesh_Validation.cpp). This + // should be redone and compressed. const millis_t nxt = millis() + 1500UL; while (ubl_lcd_clicked()) { // debounce and watch for abort idle(); if (ELAPSED(millis(), nxt)) { lcd_return_to_status(); //SERIAL_PROTOCOLLNPGM("\nFine Tuning of Mesh Stopped."); - do_blocking_move_to_z(Z_CLEARANCE_DEPLOY_PROBE); + do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); LCD_MESSAGEPGM("Mesh Editing Stopped"); // TODO: Make translatable string while (ubl_lcd_clicked()) idle(); @@ -1485,7 +1497,7 @@ if (do_ubl_mesh_map) ubl.display_map(map_type); ubl.restore_ubl_active_state_and_leave(); - do_blocking_move_to_z(Z_CLEARANCE_DEPLOY_PROBE); + do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); do_blocking_move_to_xy(lx, ly); diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 7edbdc519..894c6276f 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -958,11 +958,13 @@ void kill_screen(const char* lcd_msg) { } void _lcd_mesh_edit() { + lcdDrawUpdate = LCDVIEW_REDRAW_NOW; _lcd_mesh_fine_tune(PSTR("Mesh Editor")); } float lcd_mesh_edit() { lcd_goto_screen(_lcd_mesh_edit_NOP); + lcdDrawUpdate = LCDVIEW_REDRAW_NOW; _lcd_mesh_fine_tune(PSTR("Mesh Editor")); return mesh_edit_value; } From 48f765214392c108026e480dabf9389d9ff94941 Mon Sep 17 00:00:00 2001 From: oldmcg Date: Mon, 22 May 2017 12:33:50 -0500 Subject: [PATCH 129/189] UBL G29 -P3.1 smart fill (#6823) * UBL G29 -P3.1 mesh fill with distance-weighted least squares fit. * Back to original -O0 on G29 for now. --- Marlin/least_squares_fit.cpp | 23 ++------- Marlin/least_squares_fit.h | 41 ++++++++++++++-- Marlin/macros.h | 6 +++ Marlin/ubl_G29.cpp | 92 ++++++++++++++++++++++++++++++++++-- 4 files changed, 135 insertions(+), 27 deletions(-) diff --git a/Marlin/least_squares_fit.cpp b/Marlin/least_squares_fit.cpp index e91c58d17..9d1d84a2a 100644 --- a/Marlin/least_squares_fit.cpp +++ b/Marlin/least_squares_fit.cpp @@ -41,27 +41,12 @@ #include "least_squares_fit.h" -void incremental_LSF_reset(struct linear_fit_data *lsf) { - memset(lsf, 0, sizeof(linear_fit_data)); -} +int finish_incremental_LSF(struct linear_fit_data *lsf) { -void incremental_LSF(struct linear_fit_data *lsf, float x, float y, float z) { - lsf->xbar += x; - lsf->ybar += y; - lsf->zbar += z; - lsf->x2bar += sq(x); - lsf->y2bar += sq(y); - lsf->z2bar += sq(z); - lsf->xybar += x * y; - lsf->xzbar += x * z; - lsf->yzbar += y * z; - lsf->max_absx = max(fabs(x), lsf->max_absx); - lsf->max_absy = max(fabs(y), lsf->max_absy); - lsf->n++; -} + const float N = lsf->N; -int finish_incremental_LSF(struct linear_fit_data *lsf) { - const float N = (float)lsf->n; + if (N == 0.0) + return 1; lsf->xbar /= N; lsf->ybar /= N; diff --git a/Marlin/least_squares_fit.h b/Marlin/least_squares_fit.h index ec863080b..4e0c8a48b 100644 --- a/Marlin/least_squares_fit.h +++ b/Marlin/least_squares_fit.h @@ -41,16 +41,49 @@ #include struct linear_fit_data { - int n; float xbar, ybar, zbar, x2bar, y2bar, z2bar, xybar, xzbar, yzbar, max_absx, max_absy, - A, B, D; + A, B, D, N; }; -void incremental_LSF_reset(struct linear_fit_data *); -void incremental_LSF(struct linear_fit_data *, float x, float y, float z); +void inline incremental_LSF_reset(struct linear_fit_data *lsf) { + memset(lsf, 0, sizeof(linear_fit_data)); +} + +void inline incremental_WLSF(struct linear_fit_data *lsf, float x, float y, float z, float w) { + // weight each accumulator by factor w, including the "number" of samples + // (analagous to calling inc_LSF twice with same values to weight it by 2X) + lsf->xbar += w * x; + lsf->ybar += w * y; + lsf->zbar += w * z; + lsf->x2bar += w * x * x; // don't use sq(x) -- let compiler re-use w*x four times + lsf->y2bar += w * y * y; + lsf->z2bar += w * z * z; + lsf->xybar += w * x * y; + lsf->xzbar += w * x * z; + lsf->yzbar += w * y * z; + lsf->N += w; + lsf->max_absx = max(fabs( w * x ), lsf->max_absx); + lsf->max_absy = max(fabs( w * y ), lsf->max_absy); +} + +void inline incremental_LSF(struct linear_fit_data *lsf, float x, float y, float z) { + lsf->xbar += x; + lsf->ybar += y; + lsf->zbar += z; + lsf->x2bar += sq(x); + lsf->y2bar += sq(y); + lsf->z2bar += sq(z); + lsf->xybar += x * y; + lsf->xzbar += x * z; + lsf->yzbar += y * z; + lsf->max_absx = max(fabs(x), lsf->max_absx); + lsf->max_absy = max(fabs(y), lsf->max_absy); + lsf->N += 1.0; +} + int finish_incremental_LSF(struct linear_fit_data *); #endif diff --git a/Marlin/macros.h b/Marlin/macros.h index 8badc5c85..3e3237a1d 100644 --- a/Marlin/macros.h +++ b/Marlin/macros.h @@ -30,6 +30,12 @@ #define FORCE_INLINE __attribute__((always_inline)) inline +#define _O0 __attribute__((optimize("O0"))) +#define _Os __attribute__((optimize("Os"))) +#define _O1 __attribute__((optimize("O1"))) +#define _O2 __attribute__((optimize("O2"))) +#define _O3 __attribute__((optimize("O3"))) + // Bracket code that shouldn't be interrupted #ifndef CRITICAL_SECTION_START #define CRITICAL_SECTION_START unsigned char _sreg = SREG; cli(); diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 1b718dd64..4f01dc9f3 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -23,8 +23,6 @@ #include "MarlinConfig.h" #if ENABLED(AUTO_BED_LEVELING_UBL) - //#include "vector_3.h" - //#include "qr_solve.h" #include "ubl.h" #include "Marlin.h" @@ -36,6 +34,8 @@ #include #include "least_squares_fit.h" + #define UBL_G29_P31 + extern float destination[XYZE]; extern float current_position[XYZE]; @@ -55,6 +55,7 @@ extern float probe_pt(float x, float y, bool, int); extern bool set_probe_deployed(bool); void smart_fill_mesh(); + void smart_fill_wlsf(float); float measure_business_card_thickness(float &in_height); void manually_probe_remaining_mesh(const float&, const float&, const float&, const float&, const bool); @@ -312,7 +313,7 @@ extern void lcd_setstatus(const char* message, const bool persist); extern void lcd_setstatuspgm(const char* message, const uint8_t level); - void __attribute__((optimize("O0"))) gcode_G29() { + void _O0 gcode_G29() { if (!settings.calc_num_meshes()) { SERIAL_PROTOCOLLNPGM("?You need to enable your EEPROM and initialize it"); @@ -529,7 +530,28 @@ } } } else { - smart_fill_mesh(); // Do a 'Smart' fill using nearby known values + const float cvf = code_value_float(); + switch( (int)truncf( cvf * 10.0 ) - 30 ) { // 3.1 -> 1 + #if ENABLED(UBL_G29_P31) + case 1: { + + // P3.1 use least squares fit to fill missing mesh values + // P3.10 zero weighting for distance, all grid points equal, best fit tilted plane + // P3.11 10X weighting for nearest grid points versus farthest grid points + // P3.12 100X distance weighting + // P3.13 1000X distance weighting, approaches simple average of nearest points + + const float weight_power = (cvf - 3.10) * 100.0; // 3.12345 -> 2.345 + const float weight_factor = weight_power ? pow( 10.0, weight_power ) : 0; + smart_fill_wlsf( weight_factor ); + } + break; + #endif + case 0: // P3 or P3.0 + default: // and anything P3.x that's not P3.1 + smart_fill_mesh(); // Do a 'Smart' fill using nearby known values + break; + } } break; } @@ -1694,4 +1716,66 @@ #endif } + #if ENABLED(UBL_G29_P31) + + // Note: using optimize("O2") for this routine results in smaller + // codegen than default optimize("Os") on A2560. + + void _O2 smart_fill_wlsf( float weight_factor ) { + + // For each undefined mesh point, compute a distance-weighted least squares fit + // from all the originally populated mesh points, weighted toward the point + // being extrapolated so that nearby points will have greater influence on + // the point being extrapolated. Then extrapolate the mesh point from WLSF. + + static_assert( GRID_MAX_POINTS_Y <= 16, "GRID_MAX_POINTS_Y too big" ); + uint16_t bitmap[GRID_MAX_POINTS_X] = {0}; + struct linear_fit_data lsf_results; + + SERIAL_ECHOPGM("Extrapolating mesh..."); + + const float weight_scaled = weight_factor * max(MESH_X_DIST, MESH_Y_DIST); + + for (uint8_t jx = 0; jx < GRID_MAX_POINTS_X; jx++) { + for (uint8_t jy = 0; jy < GRID_MAX_POINTS_Y; jy++) { + if ( !isnan( ubl.z_values[jx][jy] )) { + bitmap[jx] |= (uint16_t)1 << jy; + } + } + } + + for (uint8_t ix = 0; ix < GRID_MAX_POINTS_X; ix++) { + const float px = pgm_read_float(&(ubl.mesh_index_to_xpos[ix])); + for (uint8_t iy = 0; iy < GRID_MAX_POINTS_Y; iy++) { + const float py = pgm_read_float(&(ubl.mesh_index_to_ypos[iy])); + if ( isnan( ubl.z_values[ix][iy] )) { + // undefined mesh point at (px,py), compute weighted LSF from original valid mesh points. + incremental_LSF_reset(&lsf_results); + for (uint8_t jx = 0; jx < GRID_MAX_POINTS_X; jx++) { + const float rx = pgm_read_float(&(ubl.mesh_index_to_xpos[jx])); + for (uint8_t jy = 0; jy < GRID_MAX_POINTS_Y; jy++) { + if ( bitmap[jx] & (uint16_t)1 << jy ) { + const float ry = pgm_read_float(&(ubl.mesh_index_to_ypos[jy])); + const float rz = ubl.z_values[jx][jy]; + const float w = 1.0 + weight_scaled / HYPOT((rx - px),(ry - py)); + incremental_WLSF(&lsf_results, rx, ry, rz, w); + } + } + } + if (finish_incremental_LSF(&lsf_results)) { + SERIAL_ECHOLNPGM("Insufficient data"); + return; + } + const float ez = -lsf_results.D - lsf_results.A * px - lsf_results.B * py; + ubl.z_values[ix][iy] = ez; + idle(); // housekeeping + } + } + } + + SERIAL_ECHOLNPGM("done"); + } + #endif // UBL_G29_P31 + + #endif // AUTO_BED_LEVELING_UBL From ceb62fc7e1f8557fdb38a8a499c549dae4f3f66b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 22 May 2017 17:34:03 -0500 Subject: [PATCH 130/189] Fixes #6828: M428 bug --- Marlin/Marlin_main.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 89e4d0798..97253f805 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -8740,10 +8740,10 @@ void quickstop_stepper() { bool err = false; LOOP_XYZ(i) { if (axis_homed[i]) { - float base = (current_position[i] > (soft_endstop_min[i] + soft_endstop_max[i]) * 0.5) ? base_home_pos((AxisEnum)i) : 0, - diff = current_position[i] - LOGICAL_POSITION(base, i); + const float base = (current_position[i] > (soft_endstop_min[i] + soft_endstop_max[i]) * 0.5) ? base_home_pos((AxisEnum)i) : 0, + diff = base - RAW_POSITION(current_position[i], i); if (WITHIN(diff, -20, 20)) { - set_home_offset((AxisEnum)i, home_offset[i] - diff); + set_home_offset((AxisEnum)i, diff); } else { SERIAL_ERROR_START; From c2ea22da49a6572842568da99f926d24930ddb2a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 22 May 2017 11:39:57 -0500 Subject: [PATCH 131/189] Clean up whitespace --- Marlin/Marlin_main.cpp | 14 +++++++------- .../example_configurations/SCARA/Configuration.h | 2 +- Marlin/example_configurations/TAZ4/Configuration.h | 2 +- .../TinyBoy2/Configuration.h | 2 +- .../example_configurations/WITBOX/Configuration.h | 2 +- .../tvrrug/Round2/Configuration.h | 2 +- Marlin/ubl_G29.cpp | 14 ++++++-------- 7 files changed, 18 insertions(+), 20 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 97253f805..d8f6f26ec 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -5107,9 +5107,9 @@ void home_all_axes() { gcode_G28(true); } * P4-P7 Probe all positions at different locations and average them. * * T Don't calibrate tower angle corrections - * + * * Cn.nn Calibration precision; when omitted calibrates to maximum precision - * + * * Vn Verbose level: * * V0 Dry-run mode. Report settings and probe results. No calibration. @@ -5229,7 +5229,7 @@ void home_all_axes() { gcode_G28(true); } #endif int8_t iterations = 0; - + home_offset[Z_AXIS] -= probe_pt(0.0, 0.0 , true, 1); // 1st probe to set height do_probe_raise(Z_CLEARANCE_BETWEEN_PROBES); @@ -5239,7 +5239,7 @@ void home_all_axes() { gcode_G28(true); } int16_t N = 0; test_precision = zero_std_dev_old != 999.0 ? (zero_std_dev + zero_std_dev_old) / 2 : zero_std_dev; - + iterations++; // Probe the points @@ -5286,7 +5286,7 @@ void home_all_axes() { gcode_G28(true); } } zero_std_dev_old = zero_std_dev; zero_std_dev = round(sqrt(S2 / N) * 1000.0) / 1000.0 + 0.00001; - + if (iterations == 1) home_offset[Z_AXIS] = zh_old; // reset height after 1st probe change // Solve matrices @@ -5416,7 +5416,7 @@ void home_all_axes() { gcode_G28(true); } else { SERIAL_PROTOCOLPGM("std dev:"); SERIAL_PROTOCOL_F(zero_std_dev, 3); - } + } SERIAL_EOL; LCD_MESSAGEPGM("Calibration OK"); // TODO: Make translatable string } @@ -5481,7 +5481,7 @@ void home_all_axes() { gcode_G28(true); } home_delta(); endstops.not_homing(); - } + } while (zero_std_dev < test_precision && zero_std_dev > calibration_precision && iterations < 31); #if ENABLED(DELTA_HOME_TO_SAFE_ZONE) diff --git a/Marlin/example_configurations/SCARA/Configuration.h b/Marlin/example_configurations/SCARA/Configuration.h index 0d86d1338..5fda591bb 100644 --- a/Marlin/example_configurations/SCARA/Configuration.h +++ b/Marlin/example_configurations/SCARA/Configuration.h @@ -903,7 +903,7 @@ #define UBL_PROBE_PT_3_Y 20 #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle - + #elif ENABLED(MESH_BED_LEVELING) //=========================================================================== diff --git a/Marlin/example_configurations/TAZ4/Configuration.h b/Marlin/example_configurations/TAZ4/Configuration.h index 2492fc9ac..528c54e34 100644 --- a/Marlin/example_configurations/TAZ4/Configuration.h +++ b/Marlin/example_configurations/TAZ4/Configuration.h @@ -907,7 +907,7 @@ #define UBL_PROBE_PT_3_Y 20 #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle - + #elif ENABLED(MESH_BED_LEVELING) //=========================================================================== diff --git a/Marlin/example_configurations/TinyBoy2/Configuration.h b/Marlin/example_configurations/TinyBoy2/Configuration.h index 1bdc0f94e..b10d7b114 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration.h @@ -943,7 +943,7 @@ #define UBL_PROBE_PT_3_Y 20 #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle - + #elif ENABLED(MESH_BED_LEVELING) //=========================================================================== diff --git a/Marlin/example_configurations/WITBOX/Configuration.h b/Marlin/example_configurations/WITBOX/Configuration.h index cb06b543c..7df93fc10 100644 --- a/Marlin/example_configurations/WITBOX/Configuration.h +++ b/Marlin/example_configurations/WITBOX/Configuration.h @@ -878,7 +878,7 @@ #define UBL_PROBE_PT_3_Y 20 #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle - + #elif ENABLED(MESH_BED_LEVELING) //=========================================================================== diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration.h b/Marlin/example_configurations/tvrrug/Round2/Configuration.h index 550916356..0af2f5bd9 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration.h @@ -883,7 +883,7 @@ #define UBL_PROBE_PT_3_Y 20 #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle - + #elif ENABLED(MESH_BED_LEVELING) //=========================================================================== diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 4f01dc9f3..506ae6322 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -36,8 +36,7 @@ #define UBL_G29_P31 - extern float destination[XYZE]; - extern float current_position[XYZE]; + extern float destination[XYZE], current_position[XYZE]; void lcd_return_to_status(); bool lcd_clicked(); @@ -63,6 +62,7 @@ #define SIZE_OF_LITTLE_RAISE 1 #define BIG_RAISE_NOT_NEEDED 0 + extern void lcd_status_screen(); typedef void (*screenFunc_t)(); extern void lcd_goto_screen(screenFunc_t screen, const uint32_t encoder = 0); @@ -936,9 +936,7 @@ return current_position[Z_AXIS]; } - static void echo_and_take_a_measurement() { - SERIAL_PROTOCOLLNPGM(" and take a measurement."); - } + static void echo_and_take_a_measurement() { SERIAL_PROTOCOLLNPGM(" and take a measurement."); } float measure_business_card_thickness(float &in_height) { ubl.has_control_of_lcd_panel = true; @@ -1392,8 +1390,8 @@ for (uint8_t k = 0; k < GRID_MAX_POINTS_X; k++) { for (uint8_t l = 0; l < GRID_MAX_POINTS_Y; l++) { if (i != k && j != l && !isnan(ubl.z_values[k][l])) { -// distance += pow((float) abs(i - k) * (MESH_X_DIST), 2) + pow((float) abs(j - l) * (MESH_Y_DIST), 2); // working here - distance += HYPOT((MESH_X_DIST),(MESH_Y_DIST)) / log(HYPOT((i - k) * (MESH_X_DIST)+.001, (j - l) * (MESH_Y_DIST))+.001); + //distance += pow((float) abs(i - k) * (MESH_X_DIST), 2) + pow((float) abs(j - l) * (MESH_Y_DIST), 2); // working here + distance += HYPOT(MESH_X_DIST, MESH_Y_DIST) / log(HYPOT((i - k) * (MESH_X_DIST) + .001, (j - l) * (MESH_Y_DIST)) + .001); } } } @@ -1474,7 +1472,7 @@ do { new_z = lcd_mesh_edit(); #ifdef UBL_MESH_EDIT_MOVES_Z - do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES+new_z); // Move the nozzle as the point is edited + do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES + new_z); // Move the nozzle as the point is edited #endif idle(); } while (!ubl_lcd_clicked()); From e271521c39b6b48ed49018fc05af9eaee0dabeff Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 22 May 2017 11:42:17 -0500 Subject: [PATCH 132/189] Single user_canceled function in G26 --- Marlin/G26_Mesh_Validation_Tool.cpp | 66 ++++++++++++----------------- Marlin/ultralcd.cpp | 6 +-- 2 files changed, 30 insertions(+), 42 deletions(-) diff --git a/Marlin/G26_Mesh_Validation_Tool.cpp b/Marlin/G26_Mesh_Validation_Tool.cpp index ff329bf16..847e516f4 100644 --- a/Marlin/G26_Mesh_Validation_Tool.cpp +++ b/Marlin/G26_Mesh_Validation_Tool.cpp @@ -186,6 +186,30 @@ feedrate_mm_s = save_feedrate; // restore global feed rate } + /** + * Detect ubl_lcd_clicked, debounce it, and return true for cancel + */ + bool user_canceled() { + if (!ubl_lcd_clicked()) return false; + safe_delay(10); // Wait for click to settle + + #if ENABLED(ULTRA_LCD) + lcd_setstatuspgm(PSTR("Mesh Validation Stopped."), 99); + lcd_quick_feedback(); + #endif + lcd_reset_alert_level(); + + while (!ubl_lcd_clicked()) idle(); // Wait for button release + + // If the button is suddenly pressed again, + // ask the user to resolve the issue + lcd_setstatuspgm(PSTR("Release button"), 99); // will never appear... + while (ubl_lcd_clicked()) idle(); // unless this loop happens + lcd_setstatuspgm(PSTR("")); + + return true; + } + /** * G26: Mesh Validation Pattern generation. * @@ -300,25 +324,7 @@ for (tmp = start_angle; tmp < end_angle - 0.1; tmp += 30.0) { - // this sequence to detect an ubl_lcd_clicked() debounce it and leave if it is - // a Press and Hold is repeated in a lot of places (including ubl_G29.cpp). This - // should be redone and compressed. - if (ubl_lcd_clicked()) { // Check if the user wants to stop the Mesh Validation - #if ENABLED(ULTRA_LCD) - lcd_setstatuspgm(PSTR("Mesh Validation Stopped."), 99); - lcd_quick_feedback(); - #endif - while (!ubl_lcd_clicked()) { // Wait until the user is done pressing the - idle(); // Encoder Wheel if that is why we are leaving - lcd_reset_alert_level(); - lcd_setstatuspgm(PSTR("")); - } - while (ubl_lcd_clicked()) { // Wait until the user is done pressing the - idle(); // Encoder Wheel if that is why we are leaving - lcd_setstatuspgm(PSTR("Unpress Wheel"), 99); - } - goto LEAVE; - } + if (user_canceled()) goto LEAVE; // Check if the user wants to stop the Mesh Validation int tmp_div_30 = tmp / 30.0; if (tmp_div_30 < 0) tmp_div_30 += 360 / 30; @@ -436,28 +442,10 @@ for (uint8_t i = 0; i < GRID_MAX_POINTS_X; i++) { for (uint8_t j = 0; j < GRID_MAX_POINTS_Y; j++) { - // this sequence to detect an ubl_lcd_clicked() debounce it and leave if it is - // a Press and Hold is repeated in a lot of places (including ubl_G29.cpp). This - // should be redone and compressed. - if (ubl_lcd_clicked()) { // Check if the user wants to stop the Mesh Validation - #if ENABLED(ULTRA_LCD) - lcd_setstatuspgm(PSTR("Mesh Validation Stopped."), 99); - lcd_quick_feedback(); - #endif - while (!ubl_lcd_clicked()) { // Wait until the user is done pressing the - idle(); // Encoder Wheel if that is why we are leaving - lcd_reset_alert_level(); - lcd_setstatuspgm(PSTR("")); - } - while (ubl_lcd_clicked()) { // Wait until the user is done pressing the - idle(); // Encoder Wheel if that is why we are leaving - lcd_setstatuspgm(PSTR("Unpress Wheel"), 99); - } - return true; - } + if (user_canceled()) return true; // Check if the user wants to stop the Mesh Validation if (i < GRID_MAX_POINTS_X) { // We can't connect to anything to the right than GRID_MAX_POINTS_X. - // This is already a half circle because we are at the edge of the bed. + // This is already a half circle because we are at the edge of the bed. if (is_bit_set(circle_flags, i, j) && is_bit_set(circle_flags, i + 1, j)) { // check if we can do a line to the left if (!is_bit_set(horizontal_mesh_line_flags, i, j)) { diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index aa7118739..dd1590238 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -1480,7 +1480,7 @@ void kill_screen(const char* lcd_msg) { void _lcd_level_bed_get_z() { ENCODER_DIRECTION_NORMAL(); - // Encoder wheel adjusts the Z position + // Encoder knob or keypad buttons adjust the Z position if (encoderPosition) { refresh_cmd_timeout(); current_position[Z_AXIS] += float((int32_t)encoderPosition) * (MBL_Z_STEP); @@ -4202,9 +4202,9 @@ void lcd_reset_alert_level() { lcd_status_message_level = 0; } } #if ENABLED(AUTO_BED_LEVELING_UBL) if (ubl.has_control_of_lcd_panel) { - ubl.encoder_diff = encoderDiff; // Make the encoder's rotation available to G29's Mesh Editor + ubl.encoder_diff = encoderDiff; // Make the encoder's rotation available to G29's Mesh Editor encoderDiff = 0; // We are going to lie to the LCD Panel and claim the encoder - // wheel has not turned. + // knob has not turned. } #endif lastEncoderBits = enc; From ad5638f78ca0260da2854a19893fec501411fffe Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 22 May 2017 13:12:52 -0500 Subject: [PATCH 133/189] Cleanup some fastio code --- Marlin/fastio.h | 16 +++++++++------- Marlin/fastio_AT90USB-Teensy.h | 1 - 2 files changed, 9 insertions(+), 8 deletions(-) diff --git a/Marlin/fastio.h b/Marlin/fastio.h index 62daa409d..430a06626 100644 --- a/Marlin/fastio.h +++ b/Marlin/fastio.h @@ -21,24 +21,24 @@ */ /** - * Contributed by Triffid_Hunter, modified by Kliment, extended by the Marlin team - * Why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html + * Fast I/O Routines + * Use direct port manipulation to save scads of processor time. + * Contributed by Triffid_Hunter. Modified by Kliment and the Marlin team. */ -#ifndef _FASTIO_ARDUINO_H +#ifndef _FASTIO_ARDUINO_H #define _FASTIO_ARDUINO_H #include -/** - * Include Ports and Functions - */ - /** * Enable this option to use Teensy++ 2.0 assignments for AT90USB processors. */ //#define AT90USBxx_TEENSYPP_ASSIGNMENTS +/** + * Include Ports and Functions + */ #if defined(__AVR_ATmega168__) || defined(__AVR_ATmega328__) || defined(__AVR_ATmega328P__) #include "fastio_168.h" #elif defined(__AVR_ATmega644__) || defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644PA__) || defined(__AVR_ATmega1284P__) @@ -65,6 +65,8 @@ * Magic I/O routines * * Now you can simply SET_OUTPUT(PIN); WRITE(PIN, HIGH); WRITE(PIN, LOW); + * + * Why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html */ #define _READ(IO) ((bool)(DIO ## IO ## _RPORT & _BV(DIO ## IO ## _PIN))) diff --git a/Marlin/fastio_AT90USB-Teensy.h b/Marlin/fastio_AT90USB-Teensy.h index 7cafa6901..0cf94454a 100644 --- a/Marlin/fastio_AT90USB-Teensy.h +++ b/Marlin/fastio_AT90USB-Teensy.h @@ -679,5 +679,4 @@ #define PF7_PWM NULL #define PF7_DDR DDRF -#endif // AT90USBxx_TEENSYPP_ASSIGNMENTS Teensyduino assignments #endif // _FASTIO_AT90USB From c99bd69889ba63320695a2946791c6a9c08ead62 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 22 May 2017 13:55:07 -0500 Subject: [PATCH 134/189] Apply const float & more --- Marlin/Marlin_main.cpp | 2 +- Marlin/least_squares_fit.h | 8 ++++---- Marlin/ubl_G29.cpp | 12 ++++++------ 3 files changed, 11 insertions(+), 11 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index d8f6f26ec..5e43a01e9 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -2355,7 +2355,7 @@ static void clean_up_after_endstop_or_probe_move() { * - Raise to the BETWEEN height * - Return the probed Z position */ - float probe_pt(const float x, const float y, const bool stow/*=true*/, const int verbose_level/*=1*/) { + float probe_pt(const float &x, const float &y, const bool stow/*=true*/, const int verbose_level/*=1*/) { #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) { SERIAL_ECHOPAIR(">>> probe_pt(", x); diff --git a/Marlin/least_squares_fit.h b/Marlin/least_squares_fit.h index 4e0c8a48b..a5da16a8a 100644 --- a/Marlin/least_squares_fit.h +++ b/Marlin/least_squares_fit.h @@ -52,7 +52,7 @@ void inline incremental_LSF_reset(struct linear_fit_data *lsf) { memset(lsf, 0, sizeof(linear_fit_data)); } -void inline incremental_WLSF(struct linear_fit_data *lsf, float x, float y, float z, float w) { +void inline incremental_WLSF(struct linear_fit_data *lsf, const float &x, const float &y, const float &z, const float &w) { // weight each accumulator by factor w, including the "number" of samples // (analagous to calling inc_LSF twice with same values to weight it by 2X) lsf->xbar += w * x; @@ -65,11 +65,11 @@ void inline incremental_WLSF(struct linear_fit_data *lsf, float x, float y, floa lsf->xzbar += w * x * z; lsf->yzbar += w * y * z; lsf->N += w; - lsf->max_absx = max(fabs( w * x ), lsf->max_absx); - lsf->max_absy = max(fabs( w * y ), lsf->max_absy); + lsf->max_absx = max(fabs(w * x), lsf->max_absx); + lsf->max_absy = max(fabs(w * y), lsf->max_absy); } -void inline incremental_LSF(struct linear_fit_data *lsf, float x, float y, float z) { +void inline incremental_LSF(struct linear_fit_data *lsf, const float &x, const float &y, const float &z) { lsf->xbar += x; lsf->ybar += y; lsf->zbar += z; diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 506ae6322..c9efd1212 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -51,10 +51,10 @@ extern uint8_t code_value_byte(); extern bool code_value_bool(); extern bool code_has_value(); - extern float probe_pt(float x, float y, bool, int); + extern float probe_pt(const float &x, const float &y, bool, int); extern bool set_probe_deployed(bool); void smart_fill_mesh(); - void smart_fill_wlsf(float); + void smart_fill_wlsf(const float &); float measure_business_card_thickness(float &in_height); void manually_probe_remaining_mesh(const float&, const float&, const float&, const float&, const bool); @@ -531,7 +531,7 @@ } } else { const float cvf = code_value_float(); - switch( (int)truncf( cvf * 10.0 ) - 30 ) { // 3.1 -> 1 + switch((int)truncf(cvf * 10.0) - 30) { // 3.1 -> 1 #if ENABLED(UBL_G29_P31) case 1: { @@ -541,9 +541,9 @@ // P3.12 100X distance weighting // P3.13 1000X distance weighting, approaches simple average of nearest points - const float weight_power = (cvf - 3.10) * 100.0; // 3.12345 -> 2.345 - const float weight_factor = weight_power ? pow( 10.0, weight_power ) : 0; - smart_fill_wlsf( weight_factor ); + const float weight_power = (cvf - 3.10) * 100.0, // 3.12345 -> 2.345 + weight_factor = weight_power ? pow(10.0, weight_power) : 0; + smart_fill_wlsf(weight_factor); } break; #endif From 85b967657e8facbbfed4f0048e426ee6033ad4a3 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 22 May 2017 14:41:09 -0500 Subject: [PATCH 135/189] Embed G26/G29 in ubl class, with enhancements --- Marlin/G26_Mesh_Validation_Tool.cpp | 231 +++++++------- Marlin/Marlin_main.cpp | 12 +- Marlin/fastio.h | 2 +- Marlin/ubl.cpp | 8 +- Marlin/ubl.h | 161 ++++++---- Marlin/ubl_G29.cpp | 457 ++++++++++++++-------------- Marlin/ubl_motion.cpp | 128 ++++---- 7 files changed, 515 insertions(+), 484 deletions(-) diff --git a/Marlin/G26_Mesh_Validation_Tool.cpp b/Marlin/G26_Mesh_Validation_Tool.cpp index 847e516f4..0bae98391 100644 --- a/Marlin/G26_Mesh_Validation_Tool.cpp +++ b/Marlin/G26_Mesh_Validation_Tool.cpp @@ -135,54 +135,44 @@ float code_value_axis_units(const AxisEnum axis); bool code_value_bool(); bool code_has_value(); - void lcd_init(); - void lcd_setstatuspgm(const char* const message, const uint8_t level); void sync_plan_position_e(); void chirp_at_user(); // Private functions - void un_retract_filament(float where[XYZE]); - void retract_filament(float where[XYZE]); - bool look_for_lines_to_connect(); - bool parse_G26_parameters(); - void move_to(const float&, const float&, const float&, const float&) ; - void print_line_from_here_to_there(const float&, const float&, const float&, const float&, const float&, const float&); - bool turn_on_heaters(); - bool prime_nozzle(); - static uint16_t circle_flags[16], horizontal_mesh_line_flags[16], vertical_mesh_line_flags[16]; float g26_e_axis_feedrate = 0.020, - random_deviation = 0.0, - layer_height = LAYER_HEIGHT; + random_deviation = 0.0; static bool g26_retracted = false; // Track the retracted state of the nozzle so mismatched // retracts/recovers won't result in a bad state. float valid_trig_angle(float); - mesh_index_pair find_closest_circle_to_print(const float&, const float&); - static float extrusion_multiplier = EXTRUSION_MULTIPLIER, - retraction_multiplier = RETRACTION_MULTIPLIER, - nozzle = NOZZLE, - filament_diameter = FILAMENT, - prime_length = PRIME_LENGTH, - x_pos, y_pos, - ooze_amount = OOZE_AMOUNT; + float unified_bed_leveling::g26_extrusion_multiplier, + unified_bed_leveling::g26_retraction_multiplier, + unified_bed_leveling::g26_nozzle, + unified_bed_leveling::g26_filament_diameter, + unified_bed_leveling::g26_layer_height, + unified_bed_leveling::g26_prime_length, + unified_bed_leveling::g26_x_pos, + unified_bed_leveling::g26_y_pos, + unified_bed_leveling::g26_ooze_amount; - static int16_t bed_temp = BED_TEMP, - hotend_temp = HOTEND_TEMP; + int16_t unified_bed_leveling::g26_bed_temp, + unified_bed_leveling::g26_hotend_temp; - static int8_t prime_flag = 0; + int8_t unified_bed_leveling::g26_prime_flag; - static bool continue_with_closest, keep_heaters_on; + bool unified_bed_leveling::g26_continue_with_closest, + unified_bed_leveling::g26_keep_heaters_on; - static int16_t g26_repeats; + int16_t unified_bed_leveling::g26_repeats; - void G26_line_to_destination(const float &feed_rate) { + void unified_bed_leveling::G26_line_to_destination(const float &feed_rate) { const float save_feedrate = feedrate_mm_s; feedrate_mm_s = feed_rate; // use specified feed rate - prepare_move_to_destination(); // will ultimately call ubl_line_to_destination_cartesian or ubl_prepare_linear_move_to for UBL_DELTA + prepare_move_to_destination(); // will ultimately call ubl.line_to_destination_cartesian or ubl.prepare_linear_move_to for UBL_DELTA feedrate_mm_s = save_feedrate; // restore global feed rate } @@ -216,7 +206,7 @@ * Used to interactively edit UBL's Mesh by placing the * nozzle in a problem area and doing a G29 P4 R command. */ - void gcode_G26() { + void unified_bed_leveling::G26() { SERIAL_ECHOLNPGM("G26 command started. Waiting for heater(s)."); float tmp, start_angle, end_angle; int i, xi, yi; @@ -237,7 +227,7 @@ current_position[E_AXIS] = 0.0; sync_plan_position_e(); - if (prime_flag && prime_nozzle()) goto LEAVE; + if (g26_prime_flag && prime_nozzle()) goto LEAVE; /** * Bed is preheated @@ -255,11 +245,11 @@ // Move nozzle to the specified height for the first layer set_destination_to_current(); - destination[Z_AXIS] = layer_height; + destination[Z_AXIS] = g26_layer_height; move_to(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], 0.0); - move_to(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], ooze_amount); + move_to(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], g26_ooze_amount); - ubl.has_control_of_lcd_panel = true; + has_control_of_lcd_panel = true; //debug_current_and_destination(PSTR("Starting G26 Mesh Validation Pattern.")); /** @@ -273,13 +263,13 @@ } do { - location = continue_with_closest + location = g26_continue_with_closest ? find_closest_circle_to_print(current_position[X_AXIS], current_position[Y_AXIS]) - : find_closest_circle_to_print(x_pos, y_pos); // Find the closest Mesh Intersection to where we are now. + : find_closest_circle_to_print(g26_x_pos, g26_y_pos); // Find the closest Mesh Intersection to where we are now. if (location.x_index >= 0 && location.y_index >= 0) { - const float circle_x = pgm_read_float(&ubl.mesh_index_to_xpos[location.x_index]), - circle_y = pgm_read_float(&ubl.mesh_index_to_ypos[location.y_index]); + const float circle_x = mesh_index_to_xpos(location.x_index), + circle_y = mesh_index_to_ypos(location.y_index); // If this mesh location is outside the printable_radius, skip it. @@ -288,7 +278,7 @@ xi = location.x_index; // Just to shrink the next few lines and make them easier to understand yi = location.y_index; - if (ubl.g26_debug_flag) { + if (g26_debug_flag) { SERIAL_ECHOPAIR(" Doing circle at: (xi=", xi); SERIAL_ECHOPAIR(", yi=", yi); SERIAL_CHAR(')'); @@ -344,7 +334,7 @@ ye = constrain(ye, Y_MIN_POS + 1, Y_MAX_POS - 1); #endif - //if (ubl.g26_debug_flag) { + //if (g26_debug_flag) { // char ccc, *cptr, seg_msg[50], seg_num[10]; // strcpy(seg_msg, " segment: "); // strcpy(seg_num, " \n"); @@ -355,7 +345,7 @@ // debug_current_and_destination(seg_msg); //} - print_line_from_here_to_there(LOGICAL_X_POSITION(x), LOGICAL_Y_POSITION(y), layer_height, LOGICAL_X_POSITION(xe), LOGICAL_Y_POSITION(ye), layer_height); + print_line_from_here_to_there(LOGICAL_X_POSITION(x), LOGICAL_Y_POSITION(y), g26_layer_height, LOGICAL_X_POSITION(xe), LOGICAL_Y_POSITION(ye), g26_layer_height); } if (look_for_lines_to_connect()) @@ -374,16 +364,16 @@ move_to(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], 0); // Raise the nozzle //debug_current_and_destination(PSTR("done doing Z-Raise.")); - destination[X_AXIS] = x_pos; // Move back to the starting position - destination[Y_AXIS] = y_pos; + destination[X_AXIS] = g26_x_pos; // Move back to the starting position + destination[Y_AXIS] = g26_y_pos; //destination[Z_AXIS] = Z_CLEARANCE_BETWEEN_PROBES; // Keep the nozzle where it is move_to(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], 0); // Move back to the starting position //debug_current_and_destination(PSTR("done doing X/Y move.")); - ubl.has_control_of_lcd_panel = false; // Give back control of the LCD Panel! + has_control_of_lcd_panel = false; // Give back control of the LCD Panel! - if (!keep_heaters_on) { + if (!g26_keep_heaters_on) { #if HAS_TEMP_BED thermalManager.setTargetBed(0); #endif @@ -391,14 +381,13 @@ } } - float valid_trig_angle(float d) { while (d > 360.0) d -= 360.0; while (d < 0.0) d += 360.0; return d; } - mesh_index_pair find_closest_circle_to_print(const float &X, const float &Y) { + mesh_index_pair unified_bed_leveling::find_closest_circle_to_print(const float &X, const float &Y) { float closest = 99999.99; mesh_index_pair return_val; @@ -407,8 +396,8 @@ for (uint8_t i = 0; i < GRID_MAX_POINTS_X; i++) { for (uint8_t j = 0; j < GRID_MAX_POINTS_Y; j++) { if (!is_bit_set(circle_flags, i, j)) { - const float mx = pgm_read_float(&ubl.mesh_index_to_xpos[i]), // We found a circle that needs to be printed - my = pgm_read_float(&ubl.mesh_index_to_ypos[j]); + const float mx = mesh_index_to_xpos(i), // We found a circle that needs to be printed + my = mesh_index_to_ypos(j); // Get the distance to this intersection float f = HYPOT(X - mx, Y - my); @@ -417,7 +406,7 @@ // to let us find the closest circle to the start position. // But if this is not the case, add a small weighting to the // distance calculation to help it choose a better place to continue. - f += HYPOT(x_pos - mx, y_pos - my) / 15.0; + f += HYPOT(g26_x_pos - mx, g26_y_pos - my) / 15.0; // Add in the specified amount of Random Noise to our search if (random_deviation > 1.0) @@ -436,7 +425,7 @@ return return_val; } - bool look_for_lines_to_connect() { + bool unified_bed_leveling::look_for_lines_to_connect() { float sx, sy, ex, ey; for (uint8_t i = 0; i < GRID_MAX_POINTS_X; i++) { @@ -454,16 +443,16 @@ // We found two circles that need a horizontal line to connect them // Print it! // - sx = pgm_read_float(&ubl.mesh_index_to_xpos[ i ]) + (SIZE_OF_INTERSECTION_CIRCLES - (SIZE_OF_CROSSHAIRS)); // right edge - ex = pgm_read_float(&ubl.mesh_index_to_xpos[i + 1]) - (SIZE_OF_INTERSECTION_CIRCLES - (SIZE_OF_CROSSHAIRS)); // left edge + sx = mesh_index_to_xpos( i ) + (SIZE_OF_INTERSECTION_CIRCLES - (SIZE_OF_CROSSHAIRS)); // right edge + ex = mesh_index_to_xpos(i + 1) - (SIZE_OF_INTERSECTION_CIRCLES - (SIZE_OF_CROSSHAIRS)); // left edge sx = constrain(sx, X_MIN_POS + 1, X_MAX_POS - 1); - sy = ey = constrain(pgm_read_float(&ubl.mesh_index_to_ypos[j]), Y_MIN_POS + 1, Y_MAX_POS - 1); + sy = ey = constrain(mesh_index_to_ypos(j), Y_MIN_POS + 1, Y_MAX_POS - 1); ex = constrain(ex, X_MIN_POS + 1, X_MAX_POS - 1); if (position_is_reachable_raw_xy(sx, sy) && position_is_reachable_raw_xy(ex, ey)) { - if (ubl.g26_debug_flag) { + if (g26_debug_flag) { SERIAL_ECHOPAIR(" Connecting with horizontal line (sx=", sx); SERIAL_ECHOPAIR(", sy=", sy); SERIAL_ECHOPAIR(") -> (ex=", ex); @@ -473,7 +462,7 @@ //debug_current_and_destination(PSTR("Connecting horizontal line.")); } - print_line_from_here_to_there(LOGICAL_X_POSITION(sx), LOGICAL_Y_POSITION(sy), layer_height, LOGICAL_X_POSITION(ex), LOGICAL_Y_POSITION(ey), layer_height); + print_line_from_here_to_there(LOGICAL_X_POSITION(sx), LOGICAL_Y_POSITION(sy), g26_layer_height, LOGICAL_X_POSITION(ex), LOGICAL_Y_POSITION(ey), g26_layer_height); } bit_set(horizontal_mesh_line_flags, i, j); // Mark it as done so we don't do it again, even if we skipped it } @@ -488,16 +477,16 @@ // We found two circles that need a vertical line to connect them // Print it! // - sy = pgm_read_float(&ubl.mesh_index_to_ypos[ j ]) + (SIZE_OF_INTERSECTION_CIRCLES - (SIZE_OF_CROSSHAIRS)); // top edge - ey = pgm_read_float(&ubl.mesh_index_to_ypos[j + 1]) - (SIZE_OF_INTERSECTION_CIRCLES - (SIZE_OF_CROSSHAIRS)); // bottom edge + sy = mesh_index_to_ypos( j ) + (SIZE_OF_INTERSECTION_CIRCLES - (SIZE_OF_CROSSHAIRS)); // top edge + ey = mesh_index_to_ypos(j + 1) - (SIZE_OF_INTERSECTION_CIRCLES - (SIZE_OF_CROSSHAIRS)); // bottom edge - sx = ex = constrain(pgm_read_float(&ubl.mesh_index_to_xpos[i]), X_MIN_POS + 1, X_MAX_POS - 1); + sx = ex = constrain(mesh_index_to_xpos(i), X_MIN_POS + 1, X_MAX_POS - 1); sy = constrain(sy, Y_MIN_POS + 1, Y_MAX_POS - 1); ey = constrain(ey, Y_MIN_POS + 1, Y_MAX_POS - 1); if (position_is_reachable_raw_xy(sx, sy) && position_is_reachable_raw_xy(ex, ey)) { - if (ubl.g26_debug_flag) { + if (g26_debug_flag) { SERIAL_ECHOPAIR(" Connecting with vertical line (sx=", sx); SERIAL_ECHOPAIR(", sy=", sy); SERIAL_ECHOPAIR(") -> (ex=", ex); @@ -506,7 +495,7 @@ SERIAL_EOL; debug_current_and_destination(PSTR("Connecting vertical line.")); } - print_line_from_here_to_there(LOGICAL_X_POSITION(sx), LOGICAL_Y_POSITION(sy), layer_height, LOGICAL_X_POSITION(ex), LOGICAL_Y_POSITION(ey), layer_height); + print_line_from_here_to_there(LOGICAL_X_POSITION(sx), LOGICAL_Y_POSITION(sy), g26_layer_height, LOGICAL_X_POSITION(ex), LOGICAL_Y_POSITION(ey), g26_layer_height); } bit_set(vertical_mesh_line_flags, i, j); // Mark it as done so we don't do it again, even if skipped } @@ -518,7 +507,7 @@ return false; } - void move_to(const float &x, const float &y, const float &z, const float &e_delta) { + void unified_bed_leveling::move_to(const float &x, const float &y, const float &z, const float &e_delta) { float feed_value; static float last_z = -999.99; @@ -540,10 +529,10 @@ } // Check if X or Y is involved in the movement. - // Yes: a 'normal' movement. No: a retract() or un_retract() + // Yes: a 'normal' movement. No: a retract() or recover() feed_value = has_xy_component ? PLANNER_XY_FEEDRATE() / 10.0 : planner.max_feedrate_mm_s[E_AXIS] / 1.5; - if (ubl.g26_debug_flag) SERIAL_ECHOLNPAIR("in move_to() feed_value for XY:", feed_value); + if (g26_debug_flag) SERIAL_ECHOLNPAIR("in move_to() feed_value for XY:", feed_value); destination[X_AXIS] = x; destination[Y_AXIS] = y; @@ -556,16 +545,16 @@ } - void retract_filament(float where[XYZE]) { + void unified_bed_leveling::retract_filament(float where[XYZE]) { if (!g26_retracted) { // Only retract if we are not already retracted! g26_retracted = true; - move_to(where[X_AXIS], where[Y_AXIS], where[Z_AXIS], -1.0 * retraction_multiplier); + move_to(where[X_AXIS], where[Y_AXIS], where[Z_AXIS], -1.0 * g26_retraction_multiplier); } } - void un_retract_filament(float where[XYZE]) { + void unified_bed_leveling::recover_filament(float where[XYZE]) { if (g26_retracted) { // Only un-retract if we are retracted. - move_to(where[X_AXIS], where[Y_AXIS], where[Z_AXIS], 1.2 * retraction_multiplier); + move_to(where[X_AXIS], where[Y_AXIS], where[Z_AXIS], 1.2 * g26_retraction_multiplier); g26_retracted = false; } } @@ -585,7 +574,7 @@ * segment of a 'circle'. The time this requires is very short and is easily saved by the other * cases where the optimization comes into play. */ - void print_line_from_here_to_there(const float &sx, const float &sy, const float &sz, const float &ex, const float &ey, const float &ez) { + void unified_bed_leveling::print_line_from_here_to_there(const float &sx, const float &sy, const float &sz, const float &ex, const float &ey, const float &ez) { const float dx_s = current_position[X_AXIS] - sx, // find our distance from the start of the actual line segment dy_s = current_position[Y_AXIS] - sy, dist_start = HYPOT2(dx_s, dy_s), // We don't need to do a sqrt(), we can compare the distance^2 @@ -613,9 +602,9 @@ move_to(sx, sy, sz, 0.0); // Get to the starting point with no extrusion / un-Z bump - const float e_pos_delta = line_length * g26_e_axis_feedrate * extrusion_multiplier; + const float e_pos_delta = line_length * g26_e_axis_feedrate * g26_extrusion_multiplier; - un_retract_filament(destination); + recover_filament(destination); move_to(ex, ey, ez, e_pos_delta); // Get to the ending point with an appropriate amount of extrusion } @@ -624,33 +613,33 @@ * parameters it made sense to turn them into static globals and get * this code out of sight of the main routine. */ - bool parse_G26_parameters() { - - extrusion_multiplier = EXTRUSION_MULTIPLIER; - retraction_multiplier = RETRACTION_MULTIPLIER; - nozzle = NOZZLE; - filament_diameter = FILAMENT; - layer_height = LAYER_HEIGHT; - prime_length = PRIME_LENGTH; - bed_temp = BED_TEMP; - hotend_temp = HOTEND_TEMP; - prime_flag = 0; - - ooze_amount = code_seen('O') && code_has_value() ? code_value_linear_units() : OOZE_AMOUNT; - keep_heaters_on = code_seen('K') && code_value_bool(); - continue_with_closest = code_seen('C') && code_value_bool(); + bool unified_bed_leveling::parse_G26_parameters() { + + g26_extrusion_multiplier = EXTRUSION_MULTIPLIER; + g26_retraction_multiplier = RETRACTION_MULTIPLIER; + g26_nozzle = NOZZLE; + g26_filament_diameter = FILAMENT; + g26_layer_height = LAYER_HEIGHT; + g26_prime_length = PRIME_LENGTH; + g26_bed_temp = BED_TEMP; + g26_hotend_temp = HOTEND_TEMP; + g26_prime_flag = 0; + + g26_ooze_amount = code_seen('O') && code_has_value() ? code_value_linear_units() : OOZE_AMOUNT; + g26_keep_heaters_on = code_seen('K') && code_value_bool(); + g26_continue_with_closest = code_seen('C') && code_value_bool(); if (code_seen('B')) { - bed_temp = code_value_temp_abs(); - if (!WITHIN(bed_temp, 15, 140)) { + g26_bed_temp = code_value_temp_abs(); + if (!WITHIN(g26_bed_temp, 15, 140)) { SERIAL_PROTOCOLLNPGM("?Specified bed temperature not plausible."); return UBL_ERR; } } if (code_seen('L')) { - layer_height = code_value_linear_units(); - if (!WITHIN(layer_height, 0.0, 2.0)) { + g26_layer_height = code_value_linear_units(); + if (!WITHIN(g26_layer_height, 0.0, 2.0)) { SERIAL_PROTOCOLLNPGM("?Specified layer height not plausible."); return UBL_ERR; } @@ -658,8 +647,8 @@ if (code_seen('Q')) { if (code_has_value()) { - retraction_multiplier = code_value_float(); - if (!WITHIN(retraction_multiplier, 0.05, 15.0)) { + g26_retraction_multiplier = code_value_float(); + if (!WITHIN(g26_retraction_multiplier, 0.05, 15.0)) { SERIAL_PROTOCOLLNPGM("?Specified Retraction Multiplier not plausible."); return UBL_ERR; } @@ -671,8 +660,8 @@ } if (code_seen('S')) { - nozzle = code_value_float(); - if (!WITHIN(nozzle, 0.1, 1.0)) { + g26_nozzle = code_value_float(); + if (!WITHIN(g26_nozzle, 0.1, 1.0)) { SERIAL_PROTOCOLLNPGM("?Specified nozzle size not plausible."); return UBL_ERR; } @@ -680,11 +669,11 @@ if (code_seen('P')) { if (!code_has_value()) - prime_flag = -1; + g26_prime_flag = -1; else { - prime_flag++; - prime_length = code_value_linear_units(); - if (!WITHIN(prime_length, 0.0, 25.0)) { + g26_prime_flag++; + g26_prime_length = code_value_linear_units(); + if (!WITHIN(g26_prime_length, 0.0, 25.0)) { SERIAL_PROTOCOLLNPGM("?Specified prime length not plausible."); return UBL_ERR; } @@ -692,21 +681,21 @@ } if (code_seen('F')) { - filament_diameter = code_value_linear_units(); - if (!WITHIN(filament_diameter, 1.0, 4.0)) { + g26_filament_diameter = code_value_linear_units(); + if (!WITHIN(g26_filament_diameter, 1.0, 4.0)) { SERIAL_PROTOCOLLNPGM("?Specified filament size not plausible."); return UBL_ERR; } } - extrusion_multiplier *= sq(1.75) / sq(filament_diameter); // If we aren't using 1.75mm filament, we need to + g26_extrusion_multiplier *= sq(1.75) / sq(g26_filament_diameter); // If we aren't using 1.75mm filament, we need to // scale up or down the length needed to get the // same volume of filament - extrusion_multiplier *= filament_diameter * sq(nozzle) / sq(0.3); // Scale up by nozzle size + g26_extrusion_multiplier *= g26_filament_diameter * sq(g26_nozzle) / sq(0.3); // Scale up by nozzle size if (code_seen('H')) { - hotend_temp = code_value_temp_abs(); - if (!WITHIN(hotend_temp, 165, 280)) { + g26_hotend_temp = code_value_temp_abs(); + if (!WITHIN(g26_hotend_temp, 165, 280)) { SERIAL_PROTOCOLLNPGM("?Specified nozzle temperature not plausible."); return UBL_ERR; } @@ -723,9 +712,9 @@ return UBL_ERR; } - x_pos = code_seen('X') ? code_value_linear_units() : current_position[X_AXIS]; - y_pos = code_seen('Y') ? code_value_linear_units() : current_position[Y_AXIS]; - if (!position_is_reachable_xy(x_pos, y_pos)) { + g26_x_pos = code_seen('X') ? code_value_linear_units() : current_position[X_AXIS]; + g26_y_pos = code_seen('Y') ? code_value_linear_units() : current_position[Y_AXIS]; + if (!position_is_reachable_xy(g26_x_pos, g26_y_pos)) { SERIAL_PROTOCOLLNPGM("?Specified X,Y coordinate out of bounds."); return UBL_ERR; } @@ -733,12 +722,12 @@ /** * Wait until all parameters are verified before altering the state! */ - ubl.state.active = !code_seen('D'); + state.active = !code_seen('D'); return UBL_OK; } - bool exit_from_g26() { + bool unified_bed_leveling::exit_from_g26() { lcd_reset_alert_level(); lcd_setstatuspgm(PSTR("Leaving G26")); while (ubl_lcd_clicked()) idle(); @@ -749,18 +738,18 @@ * Turn on the bed and nozzle heat and * wait for them to get up to temperature. */ - bool turn_on_heaters() { + bool unified_bed_leveling::turn_on_heaters() { millis_t next; #if HAS_TEMP_BED #if ENABLED(ULTRA_LCD) - if (bed_temp > 25) { + if (g26_bed_temp > 25) { lcd_setstatuspgm(PSTR("G26 Heating Bed."), 99); lcd_quick_feedback(); #endif - ubl.has_control_of_lcd_panel = true; - thermalManager.setTargetBed(bed_temp); + has_control_of_lcd_panel = true; + thermalManager.setTargetBed(g26_bed_temp); next = millis() + 5000UL; - while (abs(thermalManager.degBed() - bed_temp) > 3) { + while (abs(thermalManager.degBed() - g26_bed_temp) > 3) { if (ubl_lcd_clicked()) return exit_from_g26(); if (PENDING(millis(), next)) { next = millis() + 5000UL; @@ -776,8 +765,8 @@ #endif // Start heating the nozzle and wait for it to reach temperature. - thermalManager.setTargetHotend(hotend_temp, 0); - while (abs(thermalManager.degHotend(0) - hotend_temp) > 3) { + thermalManager.setTargetHotend(g26_hotend_temp, 0); + while (abs(thermalManager.degHotend(0) - g26_hotend_temp) > 3) { if (ubl_lcd_clicked()) return exit_from_g26(); if (PENDING(millis(), next)) { next = millis() + 5000UL; @@ -798,19 +787,19 @@ /** * Prime the nozzle if needed. Return true on error. */ - bool prime_nozzle() { + bool unified_bed_leveling::prime_nozzle() { float Total_Prime = 0.0; - if (prime_flag == -1) { // The user wants to control how much filament gets purged + if (g26_prime_flag == -1) { // The user wants to control how much filament gets purged - ubl.has_control_of_lcd_panel = true; + has_control_of_lcd_panel = true; lcd_setstatuspgm(PSTR("User-Controlled Prime"), 99); chirp_at_user(); set_destination_to_current(); - un_retract_filament(destination); // Make sure G26 doesn't think the filament is retracted(). + recover_filament(destination); // Make sure G26 doesn't think the filament is retracted(). while (!ubl_lcd_clicked()) { chirp_at_user(); @@ -838,7 +827,7 @@ lcd_quick_feedback(); #endif - ubl.has_control_of_lcd_panel = false; + has_control_of_lcd_panel = false; } else { @@ -847,7 +836,7 @@ lcd_quick_feedback(); #endif set_destination_to_current(); - destination[E_AXIS] += prime_length; + destination[E_AXIS] += g26_prime_length; G26_line_to_destination(planner.max_feedrate_mm_s[E_AXIS] / 15.0); stepper.synchronize(); set_destination_to_current(); diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 5e43a01e9..bf88d8abd 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -3416,8 +3416,8 @@ inline void gcode_G7( return; } - destination[X_AXIS] = hasI ? pgm_read_float(&ubl.mesh_index_to_xpos[ix]) : current_position[X_AXIS]; - destination[Y_AXIS] = hasJ ? pgm_read_float(&ubl.mesh_index_to_ypos[iy]) : current_position[Y_AXIS]; + destination[X_AXIS] = hasI ? ubl.mesh_index_to_xpos(ix) : current_position[X_AXIS]; + destination[Y_AXIS] = hasJ ? ubl.mesh_index_to_ypos(iy) : current_position[Y_AXIS]; destination[Z_AXIS] = current_position[Z_AXIS]; //todo: perhaps add Z-move support? destination[E_AXIS] = current_position[E_AXIS]; @@ -8704,7 +8704,7 @@ void quickstop_stepper() { const bool hasZ = code_seen('Z'), hasQ = !hasZ && code_seen('Q'); if (hasC) { - const mesh_index_pair location = find_closest_mesh_point_of_type(REAL, current_position[X_AXIS], current_position[Y_AXIS], USE_NOZZLE_AS_REFERENCE, NULL, false); + const mesh_index_pair location = ubl.find_closest_mesh_point_of_type(REAL, current_position[X_AXIS], current_position[Y_AXIS], USE_NOZZLE_AS_REFERENCE, NULL, false); ix = location.x_index; iy = location.y_index; } @@ -11467,7 +11467,7 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) { #if ENABLED(AUTO_BED_LEVELING_UBL) const float fr_scaled = MMS_SCALED(feedrate_mm_s); if (ubl.state.active) { - ubl_line_to_destination_cartesian(fr_scaled, active_extruder); + ubl.line_to_destination_cartesian(fr_scaled, active_extruder); return true; } else @@ -11612,14 +11612,14 @@ void prepare_move_to_destination() { if ( #if IS_KINEMATIC #if UBL_DELTA - ubl_prepare_linear_move_to(destination, feedrate_mm_s) + ubl.prepare_linear_move_to(destination, feedrate_mm_s) #else prepare_kinematic_move_to(destination) #endif #elif ENABLED(DUAL_X_CARRIAGE) prepare_move_to_destination_dualx() #elif UBL_DELTA // will work for CARTESIAN too (smaller segments follow mesh more closely) - ubl_prepare_linear_move_to(destination, feedrate_mm_s) + ubl.prepare_linear_move_to(destination, feedrate_mm_s) #else prepare_move_to_destination_cartesian() #endif diff --git a/Marlin/fastio.h b/Marlin/fastio.h index 430a06626..402e1ba49 100644 --- a/Marlin/fastio.h +++ b/Marlin/fastio.h @@ -58,7 +58,7 @@ #endif #ifndef _BV - #define _BV(PIN) (1 << PIN) + #define _BV(PIN) (1UL << PIN) #endif /** diff --git a/Marlin/ubl.cpp b/Marlin/ubl.cpp index 8e6190953..cdfc401ad 100644 --- a/Marlin/ubl.cpp +++ b/Marlin/ubl.cpp @@ -69,8 +69,8 @@ // 15 is the maximum nubmer of grid points supported + 1 safety margin for now, // until determinism prevails - constexpr float unified_bed_leveling::mesh_index_to_xpos[16], - unified_bed_leveling::mesh_index_to_ypos[16]; + constexpr float unified_bed_leveling::_mesh_index_to_xpos[16], + unified_bed_leveling::_mesh_index_to_ypos[16]; bool unified_bed_leveling::g26_debug_flag = false, unified_bed_leveling::has_control_of_lcd_panel = false; @@ -117,8 +117,8 @@ SERIAL_EOL; } - const float current_xi = ubl.get_cell_index_x(current_position[X_AXIS] + (MESH_X_DIST) / 2.0), - current_yi = ubl.get_cell_index_y(current_position[Y_AXIS] + (MESH_Y_DIST) / 2.0); + const float current_xi = get_cell_index_x(current_position[X_AXIS] + (MESH_X_DIST) / 2.0), + current_yi = get_cell_index_y(current_position[Y_AXIS] + (MESH_Y_DIST) / 2.0); for (int8_t j = GRID_MAX_POINTS_Y - 1; j >= 0; j--) { for (uint8_t i = 0; i < GRID_MAX_POINTS_X; i++) { diff --git a/Marlin/ubl.h b/Marlin/ubl.h index b1a6b9f7e..028eff52f 100644 --- a/Marlin/ubl.h +++ b/Marlin/ubl.h @@ -53,30 +53,16 @@ // ubl_motion.cpp void debug_current_and_destination(const char * const title); - void ubl_line_to_destination_cartesian(const float&, uint8_t); - bool ubl_prepare_linear_move_to(const float ltarget[XYZE], const float &feedrate ); // ubl_G29.cpp enum MeshPointType { INVALID, REAL, SET_IN_BITMAP }; - void dump(char * const str, const float &f); - void probe_entire_mesh(const float&, const float&, const bool, const bool, const bool); - float measure_business_card_thickness(float&); - mesh_index_pair find_closest_mesh_point_of_type(const MeshPointType, const float&, const float&, const bool, unsigned int[16], bool); - void shift_mesh_height(); - void fine_tune_mesh(const float&, const float&, const bool); - bool g29_parameter_parsing(); - void g29_eeprom_dump(); - void g29_compare_current_mesh_to_stored_mesh(); - // External references char *ftostr43sign(const float&, char); bool ubl_lcd_clicked(); void home_all_axes(); - void gcode_G26(); - void gcode_G29(); extern uint8_t ubl_cnt; @@ -101,26 +87,81 @@ static float last_specified_z; + static int g29_verbose_level, + g29_phase_value, + g29_repetition_cnt, + g29_storage_slot, + g29_map_type, + g29_grid_size; + static bool g29_c_flag, g29_x_flag, g29_y_flag; + static float g29_x_pos, g29_y_pos, + g29_card_thickness, + g29_constant; + + #if ENABLED(UBL_G26_MESH_VALIDATION) + static float g26_extrusion_multiplier, + g26_retraction_multiplier, + g26_nozzle, + g26_filament_diameter, + g26_prime_length, + g26_x_pos, g26_y_pos, + g26_ooze_amount, + g26_layer_height; + static int16_t g26_bed_temp, + g26_hotend_temp, + g26_repeats; + static int8_t g26_prime_flag; + static bool g26_continue_with_closest, g26_keep_heaters_on; + #endif + + static float measure_point_with_encoder(); + static float measure_business_card_thickness(float&); + static bool g29_parameter_parsing(); + static void find_mean_mesh_height(); + static void shift_mesh_height(); + static void probe_entire_mesh(const float &lx, const float &ly, const bool do_ubl_mesh_map, const bool stow_probe, bool do_furthest); + static void manually_probe_remaining_mesh(const float&, const float&, const float&, const float&, const bool); + static void tilt_mesh_based_on_3pts(const float &z1, const float &z2, const float &z3); + static void tilt_mesh_based_on_probed_grid(const bool do_ubl_mesh_map); + static void g29_what_command(); + static void g29_eeprom_dump(); + static void g29_compare_current_mesh_to_stored_mesh(); + static void fine_tune_mesh(const float &lx, const float &ly, const bool do_ubl_mesh_map); + static bool smart_fill_one(const uint8_t x, const uint8_t y, const int8_t xdir, const int8_t ydir); + static void smart_fill_mesh(); + + #if ENABLED(UBL_G26_MESH_VALIDATION) + static bool exit_from_g26(); + static bool parse_G26_parameters(); + static void G26_line_to_destination(const float &feed_rate); + static mesh_index_pair find_closest_circle_to_print(const float&, const float&); + static bool look_for_lines_to_connect(); + static bool turn_on_heaters(); + static bool prime_nozzle(); + static void retract_filament(float where[XYZE]); + static void recover_filament(float where[XYZE]); + static void print_line_from_here_to_there(const float&, const float&, const float&, const float&, const float&, const float&); + static void move_to(const float&, const float&, const float&, const float&); + #endif + public: - void echo_name(); - void report_state(); - void find_mean_mesh_height(); - void shift_mesh_height(); - void probe_entire_mesh(const float &lx, const float &ly, const bool do_ubl_mesh_map, const bool stow_probe, bool do_furthest); - void tilt_mesh_based_on_3pts(const float &z1, const float &z2, const float &z3); - void tilt_mesh_based_on_probed_grid(const bool do_ubl_mesh_map); - void save_ubl_active_state_and_disable(); - void restore_ubl_active_state_and_leave(); - void g29_what_command(); - void g29_eeprom_dump(); - void g29_compare_current_mesh_to_stored_mesh(); - void fine_tune_mesh(const float &lx, const float &ly, const bool do_ubl_mesh_map); - void smart_fill_mesh(); - void display_map(const int); - void reset(); - void invalidate(); - bool sanity_check(); + static void echo_name(); + 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); + static mesh_index_pair find_closest_mesh_point_of_type(const MeshPointType, const float&, const float&, const bool, unsigned int[16], bool); + static void reset(); + static void invalidate(); + static bool sanity_check(); + + static void G29() _O0; // O0 for no optimization + static void smart_fill_wlsf(const float &) _O2; // O2 gives smaller code than Os on A2560 + + #if ENABLED(UBL_G26_MESH_VALIDATION) + static void G26(); + #endif static ubl_state state; @@ -128,7 +169,7 @@ // 15 is the maximum nubmer of grid points supported + 1 safety margin for now, // until determinism prevails - constexpr static float mesh_index_to_xpos[16] PROGMEM = { + constexpr static float _mesh_index_to_xpos[16] PROGMEM = { UBL_MESH_MIN_X + 0 * (MESH_X_DIST), UBL_MESH_MIN_X + 1 * (MESH_X_DIST), UBL_MESH_MIN_X + 2 * (MESH_X_DIST), UBL_MESH_MIN_X + 3 * (MESH_X_DIST), UBL_MESH_MIN_X + 4 * (MESH_X_DIST), UBL_MESH_MIN_X + 5 * (MESH_X_DIST), @@ -139,7 +180,7 @@ UBL_MESH_MIN_X + 14 * (MESH_X_DIST), UBL_MESH_MIN_X + 15 * (MESH_X_DIST) }; - constexpr static float mesh_index_to_ypos[16] PROGMEM = { + constexpr static float _mesh_index_to_ypos[16] PROGMEM = { UBL_MESH_MIN_Y + 0 * (MESH_Y_DIST), UBL_MESH_MIN_Y + 1 * (MESH_Y_DIST), UBL_MESH_MIN_Y + 2 * (MESH_Y_DIST), UBL_MESH_MIN_Y + 3 * (MESH_Y_DIST), UBL_MESH_MIN_Y + 4 * (MESH_Y_DIST), UBL_MESH_MIN_Y + 5 * (MESH_Y_DIST), @@ -156,16 +197,16 @@ unified_bed_leveling(); - FORCE_INLINE void set_z(const int8_t px, const int8_t py, const float &z) { z_values[px][py] = z; } + FORCE_INLINE static void set_z(const int8_t px, const int8_t py, const float &z) { z_values[px][py] = z; } - int8_t get_cell_index_x(const float &x) { + static int8_t get_cell_index_x(const float &x) { const int8_t cx = (x - (UBL_MESH_MIN_X)) * (1.0 / (MESH_X_DIST)); return constrain(cx, 0, (GRID_MAX_POINTS_X) - 1); // -1 is appropriate if we want all movement to the X_MAX } // position. But with this defined this way, it is possible // to extrapolate off of this point even further out. Probably // that is OK because something else should be keeping that from // happening and should not be worried about at this level. - int8_t get_cell_index_y(const float &y) { + static int8_t get_cell_index_y(const float &y) { const int8_t cy = (y - (UBL_MESH_MIN_Y)) * (1.0 / (MESH_Y_DIST)); return constrain(cy, 0, (GRID_MAX_POINTS_Y) - 1); // -1 is appropriate if we want all movement to the Y_MAX } // position. But with this defined this way, it is possible @@ -173,12 +214,12 @@ // that is OK because something else should be keeping that from // happening and should not be worried about at this level. - int8_t find_closest_x_index(const float &x) { + static int8_t find_closest_x_index(const float &x) { const int8_t px = (x - (UBL_MESH_MIN_X) + (MESH_X_DIST) * 0.5) * (1.0 / (MESH_X_DIST)); return WITHIN(px, 0, GRID_MAX_POINTS_X - 1) ? px : -1; } - int8_t find_closest_y_index(const float &y) { + static int8_t find_closest_y_index(const float &y) { const int8_t py = (y - (UBL_MESH_MIN_Y) + (MESH_Y_DIST) * 0.5) * (1.0 / (MESH_Y_DIST)); return WITHIN(py, 0, GRID_MAX_POINTS_Y - 1) ? py : -1; } @@ -198,7 +239,7 @@ * It is fairly expensive with its 4 floating point additions and 2 floating point * multiplications. */ - FORCE_INLINE float calc_z0(const float &a0, const float &a1, const float &z1, const float &a2, const float &z2) { + FORCE_INLINE static float calc_z0(const float &a0, const float &a1, const float &z1, const float &a2, const float &z2) { return z1 + (z2 - z1) * (a0 - a1) / (a2 - a1); } @@ -206,7 +247,7 @@ * z_correction_for_x_on_horizontal_mesh_line is an optimization for * the rare occasion when a point lies exactly on a Mesh line (denoted by index yi). */ - inline float z_correction_for_x_on_horizontal_mesh_line(const float &lx0, const int x1_i, const int yi) { + inline static float z_correction_for_x_on_horizontal_mesh_line(const float &lx0, const int x1_i, const int yi) { if (!WITHIN(x1_i, 0, GRID_MAX_POINTS_X - 1) || !WITHIN(yi, 0, GRID_MAX_POINTS_Y - 1)) { serialprintPGM( !WITHIN(x1_i, 0, GRID_MAX_POINTS_X - 1) ? PSTR("x1l_i") : PSTR("yi") ); SERIAL_ECHOPAIR(" out of bounds in z_correction_for_x_on_horizontal_mesh_line(lx0=", lx0); @@ -217,7 +258,7 @@ return NAN; } - const float xratio = (RAW_X_POSITION(lx0) - pgm_read_float(&mesh_index_to_xpos[x1_i])) * (1.0 / (MESH_X_DIST)), + const float xratio = (RAW_X_POSITION(lx0) - mesh_index_to_xpos(x1_i)) * (1.0 / (MESH_X_DIST)), z1 = z_values[x1_i][yi]; return z1 + xratio * (z_values[x1_i + 1][yi] - z1); @@ -226,7 +267,7 @@ // // See comments above for z_correction_for_x_on_horizontal_mesh_line // - inline float z_correction_for_y_on_vertical_mesh_line(const float &ly0, const int xi, const int y1_i) { + inline static float z_correction_for_y_on_vertical_mesh_line(const float &ly0, const int xi, const int y1_i) { if (!WITHIN(xi, 0, GRID_MAX_POINTS_X - 1) || !WITHIN(y1_i, 0, GRID_MAX_POINTS_Y - 1)) { serialprintPGM( !WITHIN(xi, 0, GRID_MAX_POINTS_X - 1) ? PSTR("xi") : PSTR("yl_i") ); SERIAL_ECHOPAIR(" out of bounds in z_correction_for_y_on_vertical_mesh_line(ly0=", ly0); @@ -237,7 +278,7 @@ return NAN; } - const float yratio = (RAW_Y_POSITION(ly0) - pgm_read_float(&mesh_index_to_ypos[y1_i])) * (1.0 / (MESH_Y_DIST)), + const float yratio = (RAW_Y_POSITION(ly0) - mesh_index_to_ypos(y1_i)) * (1.0 / (MESH_Y_DIST)), z1 = z_values[xi][y1_i]; return z1 + yratio * (z_values[xi][y1_i + 1] - z1); @@ -249,7 +290,7 @@ * Z-Height at both ends. Then it does a linear interpolation of these heights based * on the Y position within the cell. */ - float get_z_correction(const float &lx0, const float &ly0) { + static float get_z_correction(const float &lx0, const float &ly0) { const int8_t cx = get_cell_index_x(RAW_X_POSITION(lx0)), cy = get_cell_index_y(RAW_Y_POSITION(ly0)); @@ -268,16 +309,16 @@ } const float z1 = calc_z0(RAW_X_POSITION(lx0), - pgm_read_float(&mesh_index_to_xpos[cx]), z_values[cx][cy], - pgm_read_float(&mesh_index_to_xpos[cx + 1]), z_values[cx + 1][cy]); + mesh_index_to_xpos(cx), z_values[cx][cy], + mesh_index_to_xpos(cx + 1), z_values[cx + 1][cy]); const float z2 = calc_z0(RAW_X_POSITION(lx0), - pgm_read_float(&mesh_index_to_xpos[cx]), z_values[cx][cy + 1], - pgm_read_float(&mesh_index_to_xpos[cx + 1]), z_values[cx + 1][cy + 1]); + mesh_index_to_xpos(cx), z_values[cx][cy + 1], + mesh_index_to_xpos(cx + 1), z_values[cx + 1][cy + 1]); float z0 = calc_z0(RAW_Y_POSITION(ly0), - pgm_read_float(&mesh_index_to_ypos[cy]), z1, - pgm_read_float(&mesh_index_to_ypos[cy + 1]), z2); + mesh_index_to_ypos(cy), z1, + mesh_index_to_ypos(cy + 1), z2); #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(MESH_ADJUST)) { @@ -324,7 +365,7 @@ * Returns 0.0 if Z is past the specified 'Fade Height'. */ #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - inline float fade_scaling_factor_for_z(const float &lz) { + static inline float fade_scaling_factor_for_z(const float &lz) { if (planner.z_fade_height == 0.0) return 1.0; static float fade_scaling_factor = 1.0; const float rz = RAW_Z_POSITION(lz); @@ -338,14 +379,24 @@ return fade_scaling_factor; } #else - inline float fade_scaling_factor_for_z(const float &lz) { - return 1.0; - } + FORCE_INLINE static float fade_scaling_factor_for_z(const float &lz) { return 1.0; } #endif + FORCE_INLINE static float mesh_index_to_xpos(const uint8_t i) { return pgm_read_float(&_mesh_index_to_xpos[i]); } + FORCE_INLINE static float mesh_index_to_ypos(const uint8_t i) { return pgm_read_float(&_mesh_index_to_ypos[i]); } + + static bool prepare_linear_move_to(const float ltarget[XYZE], const float &feedrate); + static void line_to_destination_cartesian(const float &fr, uint8_t e); + }; // class unified_bed_leveling extern unified_bed_leveling ubl; + #if ENABLED(UBL_G26_MESH_VALIDATION) + FORCE_INLINE void gcode_G26() { ubl.G26(); } + #endif + + FORCE_INLINE void gcode_G29() { ubl.G29(); } + #endif // AUTO_BED_LEVELING_UBL #endif // UNIFIED_BED_LEVELING_H diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index c9efd1212..381ab28ab 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -53,12 +53,6 @@ extern bool code_has_value(); extern float probe_pt(const float &x, const float &y, bool, int); extern bool set_probe_deployed(bool); - void smart_fill_mesh(); - void smart_fill_wlsf(const float &); - float measure_business_card_thickness(float &in_height); - void manually_probe_remaining_mesh(const float&, const float&, const float&, const float&, const bool); - - bool ProbeStay = true; #define SIZE_OF_LITTLE_RAISE 1 #define BIG_RAISE_NOT_NEEDED 0 @@ -66,6 +60,22 @@ extern void lcd_status_screen(); typedef void (*screenFunc_t)(); extern void lcd_goto_screen(screenFunc_t screen, const uint32_t encoder = 0); + extern void lcd_setstatus(const char* message, const bool persist); + extern void lcd_setstatuspgm(const char* message, const uint8_t level); + + int unified_bed_leveling::g29_verbose_level, + unified_bed_leveling::g29_phase_value, + unified_bed_leveling::g29_repetition_cnt, + unified_bed_leveling::g29_storage_slot = 0, + unified_bed_leveling::g29_map_type, + unified_bed_leveling::g29_grid_size; + bool unified_bed_leveling::g29_c_flag, + unified_bed_leveling::g29_x_flag, + unified_bed_leveling::g29_y_flag; + float unified_bed_leveling::g29_x_pos, + unified_bed_leveling::g29_y_pos, + unified_bed_leveling::g29_card_thickness = 0.0, + unified_bed_leveling::g29_constant = 0.0; /** * G29: Unified Bed Leveling by Roxy @@ -304,16 +314,7 @@ * we now have the functionality and features of all three systems combined. */ - // The simple parameter flags and values are 'static' so parameter parsing can be in a support routine. - static int g29_verbose_level, phase_value, repetition_cnt, - storage_slot = 0, map_type, grid_size; - static bool repeat_flag, c_flag, x_flag, y_flag; - static float x_pos, y_pos, card_thickness = 0.0, ubl_constant = 0.0; - - extern void lcd_setstatus(const char* message, const bool persist); - extern void lcd_setstatuspgm(const char* message, const uint8_t level); - - void _O0 gcode_G29() { + void unified_bed_leveling::G29() { if (!settings.calc_num_meshes()) { SERIAL_PROTOCOLLNPGM("?You need to enable your EEPROM and initialize it"); @@ -340,15 +341,15 @@ // it directly specifies the repetition count and does not use the 'R' parameter. if (code_seen('I')) { uint8_t cnt = 0; - repetition_cnt = code_has_value() ? code_value_int() : 1; - while (repetition_cnt--) { + g29_repetition_cnt = code_has_value() ? code_value_int() : 1; + while (g29_repetition_cnt--) { if (cnt > 20) { cnt = 0; idle(); } - const mesh_index_pair location = find_closest_mesh_point_of_type(REAL, x_pos, y_pos, USE_NOZZLE_AS_REFERENCE, NULL, false); + const mesh_index_pair location = find_closest_mesh_point_of_type(REAL, g29_x_pos, g29_y_pos, USE_NOZZLE_AS_REFERENCE, NULL, false); if (location.x_index < 0) { SERIAL_PROTOCOLLNPGM("Entire Mesh invalidated.\n"); break; // No more invalid Mesh Points to populate } - ubl.z_values[location.x_index][location.y_index] = NAN; + z_values[location.x_index][location.y_index] = NAN; cnt++; } SERIAL_PROTOCOLLNPGM("Locations invalidated.\n"); @@ -370,30 +371,30 @@ for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) { // a poorly calibrated Delta. const float p1 = 0.5 * (GRID_MAX_POINTS_X) - x, p2 = 0.5 * (GRID_MAX_POINTS_Y) - y; - ubl.z_values[x][y] += 2.0 * HYPOT(p1, p2); + z_values[x][y] += 2.0 * HYPOT(p1, p2); } } break; case 1: for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) { // Create a diagonal line several Mesh cells thick that is raised - ubl.z_values[x][x] += 9.999; - ubl.z_values[x][x + (x < GRID_MAX_POINTS_Y - 1) ? 1 : -1] += 9.999; // We want the altered line several mesh points thick + z_values[x][x] += 9.999; + z_values[x][x + (x < GRID_MAX_POINTS_Y - 1) ? 1 : -1] += 9.999; // We want the altered line several mesh points thick } break; case 2: // Allow the user to specify the height because 10mm is a little extreme in some cases. for (uint8_t x = (GRID_MAX_POINTS_X) / 3; x < 2 * (GRID_MAX_POINTS_X) / 3; x++) // Create a rectangular raised area in for (uint8_t y = (GRID_MAX_POINTS_Y) / 3; y < 2 * (GRID_MAX_POINTS_Y) / 3; y++) // the center of the bed - ubl.z_values[x][y] += code_seen('C') ? ubl_constant : 9.99; + z_values[x][y] += code_seen('C') ? g29_constant : 9.99; break; } } if (code_seen('J')) { - if (grid_size) { // if not 0 it is a normal n x n grid being probed - ubl.save_ubl_active_state_and_disable(); - ubl.tilt_mesh_based_on_probed_grid(code_seen('T')); - ubl.restore_ubl_active_state_and_leave(); + if (g29_grid_size) { // if not 0 it is a normal n x n grid being probed + save_ubl_active_state_and_disable(); + tilt_mesh_based_on_probed_grid(code_seen('T')); + restore_ubl_active_state_and_leave(); } else { // grid_size == 0 : A 3-Point leveling has been requested float z3, z2, z1 = probe_pt(LOGICAL_X_POSITION(UBL_PROBE_PT_1_X), LOGICAL_Y_POSITION(UBL_PROBE_PT_1_Y), false, g29_verbose_level); @@ -413,29 +414,29 @@ // doesn't mean the Mesh is tilted! (Compensate each probe point by what the Mesh says // its height is.) - ubl.save_ubl_active_state_and_disable(); - z1 -= ubl.get_z_correction(LOGICAL_X_POSITION(UBL_PROBE_PT_1_X), LOGICAL_Y_POSITION(UBL_PROBE_PT_1_Y)) /* + zprobe_zoffset */ ; - z2 -= ubl.get_z_correction(LOGICAL_X_POSITION(UBL_PROBE_PT_2_X), LOGICAL_Y_POSITION(UBL_PROBE_PT_2_Y)) /* + zprobe_zoffset */ ; - z3 -= ubl.get_z_correction(LOGICAL_X_POSITION(UBL_PROBE_PT_3_X), LOGICAL_Y_POSITION(UBL_PROBE_PT_3_Y)) /* + zprobe_zoffset */ ; + save_ubl_active_state_and_disable(); + z1 -= get_z_correction(LOGICAL_X_POSITION(UBL_PROBE_PT_1_X), LOGICAL_Y_POSITION(UBL_PROBE_PT_1_Y)) /* + zprobe_zoffset */ ; + z2 -= get_z_correction(LOGICAL_X_POSITION(UBL_PROBE_PT_2_X), LOGICAL_Y_POSITION(UBL_PROBE_PT_2_Y)) /* + zprobe_zoffset */ ; + z3 -= get_z_correction(LOGICAL_X_POSITION(UBL_PROBE_PT_3_X), LOGICAL_Y_POSITION(UBL_PROBE_PT_3_Y)) /* + zprobe_zoffset */ ; do_blocking_move_to_xy(0.5 * (UBL_MESH_MAX_X - (UBL_MESH_MIN_X)), 0.5 * (UBL_MESH_MAX_Y - (UBL_MESH_MIN_Y))); - ubl.tilt_mesh_based_on_3pts(z1, z2, z3); - ubl.restore_ubl_active_state_and_leave(); + tilt_mesh_based_on_3pts(z1, z2, z3); + restore_ubl_active_state_and_leave(); } } if (code_seen('P')) { - if (WITHIN(phase_value, 0, 1) && ubl.state.storage_slot == -1) { - ubl.state.storage_slot = 0; + if (WITHIN(g29_phase_value, 0, 1) && state.storage_slot == -1) { + state.storage_slot = 0; SERIAL_PROTOCOLLNPGM("Default storage slot 0 selected."); } - switch (phase_value) { + switch (g29_phase_value) { case 0: // // Zero Mesh Data // - ubl.reset(); + reset(); SERIAL_PROTOCOLLNPGM("Mesh zeroed."); break; @@ -444,16 +445,16 @@ // Invalidate Entire Mesh and Automatically Probe Mesh in areas that can be reached by the probe // if (!code_seen('C')) { - ubl.invalidate(); + invalidate(); SERIAL_PROTOCOLLNPGM("Mesh invalidated. Probing mesh."); } if (g29_verbose_level > 1) { - SERIAL_PROTOCOLPAIR("Probing Mesh Points Closest to (", x_pos); + SERIAL_PROTOCOLPAIR("Probing Mesh Points Closest to (", g29_x_pos); SERIAL_PROTOCOLCHAR(','); - SERIAL_PROTOCOL(y_pos); + SERIAL_PROTOCOL(g29_y_pos); SERIAL_PROTOCOLLNPGM(").\n"); } - ubl.probe_entire_mesh(x_pos + X_PROBE_OFFSET_FROM_EXTRUDER, y_pos + Y_PROBE_OFFSET_FROM_EXTRUDER, + probe_entire_mesh(g29_x_pos + X_PROBE_OFFSET_FROM_EXTRUDER, g29_y_pos + Y_PROBE_OFFSET_FROM_EXTRUDER, code_seen('T'), code_seen('E'), code_seen('U')); break; @@ -463,7 +464,7 @@ // SERIAL_PROTOCOLLNPGM("Manually probing unreachable mesh locations."); do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); - if (!x_flag && !y_flag) { + if (!g29_x_flag && !g29_y_flag) { /** * Use a good default location for the path. * The flipped > and < operators in these comparisons is intentional. @@ -472,25 +473,25 @@ * Until that is decided, this can be forced with the X and Y parameters. */ #if IS_KINEMATIC - x_pos = X_HOME_POS; - y_pos = Y_HOME_POS; + g29_x_pos = X_HOME_POS; + g29_y_pos = Y_HOME_POS; #else // cartesian - x_pos = X_PROBE_OFFSET_FROM_EXTRUDER > 0 ? X_MAX_POS : X_MIN_POS; - y_pos = Y_PROBE_OFFSET_FROM_EXTRUDER < 0 ? Y_MAX_POS : Y_MIN_POS; + g29_x_pos = X_PROBE_OFFSET_FROM_EXTRUDER > 0 ? X_MAX_POS : X_MIN_POS; + g29_y_pos = Y_PROBE_OFFSET_FROM_EXTRUDER < 0 ? Y_MAX_POS : Y_MIN_POS; #endif } if (code_seen('C')) { - x_pos = current_position[X_AXIS]; - y_pos = current_position[Y_AXIS]; + g29_x_pos = current_position[X_AXIS]; + g29_y_pos = current_position[Y_AXIS]; } float height = Z_CLEARANCE_BETWEEN_PROBES; if (code_seen('B')) { - card_thickness = code_has_value() ? code_value_float() : measure_business_card_thickness(height); + g29_card_thickness = code_has_value() ? code_value_float() : measure_business_card_thickness(height); - if (fabs(card_thickness) > 1.5) { + if (fabs(g29_card_thickness) > 1.5) { SERIAL_PROTOCOLLNPGM("?Error in Business Card measurement."); return; } @@ -498,12 +499,12 @@ if (code_seen('H') && code_has_value()) height = code_value_float(); - if (!position_is_reachable_xy(x_pos, y_pos)) { + if (!position_is_reachable_xy(g29_x_pos, g29_y_pos)) { SERIAL_PROTOCOLLNPGM("(X,Y) outside printable radius."); return; } - manually_probe_remaining_mesh(x_pos, y_pos, height, card_thickness, code_seen('T')); + manually_probe_remaining_mesh(g29_x_pos, g29_y_pos, height, g29_card_thickness, code_seen('T')); SERIAL_PROTOCOLLNPGM("G29 P2 finished."); } break; @@ -514,19 +515,19 @@ * - Specify a constant with the 'C' parameter. * - Allow 'G29 P3' to choose a 'reasonable' constant. */ - if (c_flag) { - if (repetition_cnt >= GRID_MAX_POINTS) { + if (g29_c_flag) { + if (g29_repetition_cnt >= GRID_MAX_POINTS) { for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) { for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) { - ubl.z_values[x][y] = ubl_constant; + z_values[x][y] = g29_constant; } } } else { - while (repetition_cnt--) { // this only populates reachable mesh points near - const mesh_index_pair location = find_closest_mesh_point_of_type(INVALID, x_pos, y_pos, USE_NOZZLE_AS_REFERENCE, NULL, false); + while (g29_repetition_cnt--) { // this only populates reachable mesh points near + const mesh_index_pair location = find_closest_mesh_point_of_type(INVALID, g29_x_pos, g29_y_pos, USE_NOZZLE_AS_REFERENCE, NULL, false); if (location.x_index < 0) break; // No more reachable invalid Mesh Points to populate - ubl.z_values[location.x_index][location.y_index] = ubl_constant; + z_values[location.x_index][location.y_index] = g29_constant; } } } else { @@ -561,13 +562,13 @@ // Fine Tune (i.e., Edit) the Mesh // - fine_tune_mesh(x_pos, y_pos, code_seen('T')); + fine_tune_mesh(g29_x_pos, g29_y_pos, code_seen('T')); break; - case 5: ubl.find_mean_mesh_height(); break; + case 5: find_mean_mesh_height(); break; - case 6: ubl.shift_mesh_height(); break; + case 6: shift_mesh_height(); break; } } @@ -575,7 +576,7 @@ // Much of the 'What?' command can be eliminated. But until we are fully debugged, it is // good to have the extra information. Soon... we prune this to just a few items // - if (code_seen('W')) ubl.g29_what_command(); + if (code_seen('W')) g29_what_command(); // // When we are fully debugged, this may go away. But there are some valid @@ -590,7 +591,7 @@ // if (code_seen('L')) { // Load Current Mesh Data - storage_slot = code_has_value() ? code_value_int() : ubl.state.storage_slot; + g29_storage_slot = code_has_value() ? code_value_int() : state.storage_slot; int16_t a = settings.calc_num_meshes(); @@ -599,14 +600,14 @@ return; } - if (!WITHIN(storage_slot, 0, a - 1)) { + if (!WITHIN(g29_storage_slot, 0, a - 1)) { SERIAL_PROTOCOLLNPGM("?Invalid storage slot."); SERIAL_PROTOCOLLNPAIR("?Use 0 to ", a - 1); return; } - settings.load_mesh(storage_slot); - ubl.state.storage_slot = storage_slot; + settings.load_mesh(g29_storage_slot); + state.storage_slot = g29_storage_slot; SERIAL_PROTOCOLLNPGM("Done."); } @@ -616,19 +617,19 @@ // if (code_seen('S')) { // Store (or Save) Current Mesh Data - storage_slot = code_has_value() ? code_value_int() : ubl.state.storage_slot; + g29_storage_slot = code_has_value() ? code_value_int() : state.storage_slot; - if (storage_slot == -1) { // Special case, we are going to 'Export' the mesh to the + if (g29_storage_slot == -1) { // Special case, we are going to 'Export' the mesh to the SERIAL_ECHOLNPGM("G29 I 999"); // host in a form it can be reconstructed on a different machine for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) - if (!isnan(ubl.z_values[x][y])) { + if (!isnan(z_values[x][y])) { SERIAL_ECHOPAIR("M421 I ", x); SERIAL_ECHOPAIR(" J ", y); SERIAL_ECHOPGM(" Z "); - SERIAL_ECHO_F(ubl.z_values[x][y], 6); - SERIAL_ECHOPAIR(" ; X ", LOGICAL_X_POSITION(pgm_read_float(&ubl.mesh_index_to_xpos[x]))); - SERIAL_ECHOPAIR(", Y ", LOGICAL_Y_POSITION(pgm_read_float(&ubl.mesh_index_to_ypos[y]))); + SERIAL_ECHO_F(z_values[x][y], 6); + SERIAL_ECHOPAIR(" ; X ", LOGICAL_X_POSITION(mesh_index_to_xpos(x))); + SERIAL_ECHOPAIR(", Y ", LOGICAL_Y_POSITION(mesh_index_to_ypos(y))); SERIAL_EOL; } return; @@ -641,32 +642,32 @@ goto LEAVE; } - if (!WITHIN(storage_slot, 0, a - 1)) { + if (!WITHIN(g29_storage_slot, 0, a - 1)) { SERIAL_PROTOCOLLNPGM("?Invalid storage slot."); SERIAL_PROTOCOLLNPAIR("?Use 0 to ", a - 1); goto LEAVE; } - settings.store_mesh(storage_slot); - ubl.state.storage_slot = storage_slot; + settings.store_mesh(g29_storage_slot); + state.storage_slot = g29_storage_slot; SERIAL_PROTOCOLLNPGM("Done."); } if (code_seen('T')) - ubl.display_map(code_has_value() ? code_value_int() : 0); + display_map(code_has_value() ? code_value_int() : 0); /* * This code may not be needed... Prepare for its removal... * if (code_seen('Z')) { if (code_has_value()) - ubl.state.z_offset = code_value_float(); // do the simple case. Just lock in the specified value + state.z_offset = code_value_float(); // do the simple case. Just lock in the specified value else { - ubl.save_ubl_active_state_and_disable(); - //float measured_z = probe_pt(x_pos + X_PROBE_OFFSET_FROM_EXTRUDER, y_pos + Y_PROBE_OFFSET_FROM_EXTRUDER, ProbeDeployAndStow, g29_verbose_level); + save_ubl_active_state_and_disable(); + //float measured_z = probe_pt(g29_x_pos + X_PROBE_OFFSET_FROM_EXTRUDER, g29_y_pos + Y_PROBE_OFFSET_FROM_EXTRUDER, ProbeDeployAndStow, g29_verbose_level); - ubl.has_control_of_lcd_panel = true; // Grab the LCD Hardware + has_control_of_lcd_panel = true; // Grab the LCD Hardware float measured_z = 1.5; do_blocking_move_to_z(measured_z); // Get close to the bed, but leave some space so we don't damage anything // The user is not going to be locking in a new Z-Offset very often so @@ -682,7 +683,7 @@ do_blocking_move_to_z(measured_z); } while (!ubl_lcd_clicked()); - ubl.has_control_of_lcd_panel = true; // There is a race condition for the encoder click. + has_control_of_lcd_panel = true; // There is a race condition for the encoder click. // It could get detected in lcd_mesh_edit (actually _lcd_mesh_fine_tune) // or here. So, until we are done looking for a long encoder press, // we need to take control of the panel @@ -698,17 +699,17 @@ SERIAL_PROTOCOLLNPGM("\nZ-Offset Adjustment Stopped."); do_blocking_move_to_z(Z_CLEARANCE_DEPLOY_PROBE); LCD_MESSAGEPGM("Z-Offset Stopped"); // TODO: Make translatable string - ubl.restore_ubl_active_state_and_leave(); + restore_ubl_active_state_and_leave(); goto LEAVE; } } - ubl.has_control_of_lcd_panel = false; + has_control_of_lcd_panel = false; safe_delay(20); // We don't want any switch noise. - ubl.state.z_offset = measured_z; + state.z_offset = measured_z; lcd_implementation_clear(); - ubl.restore_ubl_active_state_and_leave(); + restore_ubl_active_state_and_leave(); } } */ @@ -719,7 +720,7 @@ LCD_MESSAGEPGM(""); lcd_quick_feedback(); - ubl.has_control_of_lcd_panel = false; + has_control_of_lcd_panel = false; } void unified_bed_leveling::find_mean_mesh_height() { @@ -727,8 +728,8 @@ int n = 0; for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) - if (!isnan(ubl.z_values[x][y])) { - sum += ubl.z_values[x][y]; + if (!isnan(z_values[x][y])) { + sum += z_values[x][y]; n++; } @@ -740,8 +741,8 @@ float sum_of_diff_squared = 0.0; for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) - if (!isnan(ubl.z_values[x][y])) - sum_of_diff_squared += sq(ubl.z_values[x][y] - mean); + if (!isnan(z_values[x][y])) + sum_of_diff_squared += sq(z_values[x][y] - mean); SERIAL_ECHOLNPAIR("# of samples: ", n); SERIAL_ECHOPGM("Mean Mesh Height: "); @@ -753,18 +754,18 @@ SERIAL_ECHO_F(sigma, 6); SERIAL_EOL; - if (c_flag) + if (g29_c_flag) for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) - if (!isnan(ubl.z_values[x][y])) - ubl.z_values[x][y] -= mean + ubl_constant; + if (!isnan(z_values[x][y])) + z_values[x][y] -= mean + g29_constant; } void unified_bed_leveling::shift_mesh_height() { for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) - if (!isnan(ubl.z_values[x][y])) - ubl.z_values[x][y] += ubl_constant; + if (!isnan(z_values[x][y])) + z_values[x][y] += g29_constant; } /** @@ -774,8 +775,8 @@ void unified_bed_leveling::probe_entire_mesh(const float &lx, const float &ly, const bool do_ubl_mesh_map, const bool stow_probe, bool close_or_far) { mesh_index_pair location; - ubl.has_control_of_lcd_panel = true; - ubl.save_ubl_active_state_and_disable(); // we don't do bed level correction because we want the raw data when we probe + has_control_of_lcd_panel = true; + save_ubl_active_state_and_disable(); // we don't do bed level correction because we want the raw data when we probe DEPLOY_PROBE(); uint16_t max_iterations = GRID_MAX_POINTS; @@ -786,8 +787,8 @@ lcd_quick_feedback(); STOW_PROBE(); while (ubl_lcd_clicked()) idle(); - ubl.has_control_of_lcd_panel = false; - ubl.restore_ubl_active_state_and_leave(); + has_control_of_lcd_panel = false; + restore_ubl_active_state_and_leave(); safe_delay(50); // Debounce the Encoder wheel return; } @@ -795,19 +796,19 @@ location = find_closest_mesh_point_of_type(INVALID, lx, ly, USE_PROBE_AS_REFERENCE, NULL, close_or_far); if (location.x_index >= 0) { // mesh point found and is reachable by probe - const float rawx = pgm_read_float(&ubl.mesh_index_to_xpos[location.x_index]), - rawy = pgm_read_float(&ubl.mesh_index_to_ypos[location.y_index]); + const float rawx = mesh_index_to_xpos(location.x_index), + rawy = mesh_index_to_ypos(location.y_index); const float measured_z = probe_pt(LOGICAL_X_POSITION(rawx), LOGICAL_Y_POSITION(rawy), stow_probe, g29_verbose_level); // TODO: Needs error handling - ubl.z_values[location.x_index][location.y_index] = measured_z; + z_values[location.x_index][location.y_index] = measured_z; } - if (do_ubl_mesh_map) ubl.display_map(map_type); + if (do_ubl_mesh_map) display_map(g29_map_type); } while (location.x_index >= 0 && --max_iterations); STOW_PROBE(); - ubl.restore_ubl_active_state_and_leave(); + restore_ubl_active_state_and_leave(); do_blocking_move_to_xy( constrain(lx - (X_PROBE_OFFSET_FROM_EXTRUDER), UBL_MESH_MIN_X, UBL_MESH_MAX_X), @@ -886,9 +887,9 @@ for (uint8_t i = 0; i < GRID_MAX_POINTS_X; i++) { for (uint8_t j = 0; j < GRID_MAX_POINTS_Y; j++) { - float x_tmp = pgm_read_float(&ubl.mesh_index_to_xpos[i]), - y_tmp = pgm_read_float(&ubl.mesh_index_to_ypos[j]), - z_tmp = ubl.z_values[i][j]; + float x_tmp = mesh_index_to_xpos(i), + y_tmp = mesh_index_to_ypos(j), + z_tmp = z_values[i][j]; #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) { SERIAL_ECHOPGM("before rotation = ["); @@ -914,12 +915,12 @@ safe_delay(55); } #endif - ubl.z_values[i][j] += z_tmp - d; + z_values[i][j] += z_tmp - d; } } } - float use_encoder_wheel_to_measure_point() { + float unified_bed_leveling::measure_point_with_encoder() { while (ubl_lcd_clicked()) delay(50); // wait for user to release encoder wheel delay(50); // debounce @@ -927,9 +928,9 @@ KEEPALIVE_STATE(PAUSED_FOR_USER); while (!ubl_lcd_clicked()) { // we need the loop to move the nozzle based on the encoder wheel here! idle(); - if (ubl.encoder_diff) { - do_blocking_move_to_z(current_position[Z_AXIS] + 0.01 * float(ubl.encoder_diff)); - ubl.encoder_diff = 0; + if (encoder_diff) { + do_blocking_move_to_z(current_position[Z_AXIS] + 0.01 * float(encoder_diff)); + encoder_diff = 0; } } KEEPALIVE_STATE(IN_HANDLER); @@ -938,9 +939,9 @@ static void echo_and_take_a_measurement() { SERIAL_PROTOCOLLNPGM(" and take a measurement."); } - float measure_business_card_thickness(float &in_height) { - ubl.has_control_of_lcd_panel = true; - ubl.save_ubl_active_state_and_disable(); // Disable bed level correction for probing + float unified_bed_leveling::measure_business_card_thickness(float &in_height) { + has_control_of_lcd_panel = true; + save_ubl_active_state_and_disable(); // Disable bed level correction for probing do_blocking_move_to_z(in_height); do_blocking_move_to_xy(0.5 * (UBL_MESH_MAX_X - (UBL_MESH_MIN_X)), 0.5 * (UBL_MESH_MAX_Y - (UBL_MESH_MIN_Y))); @@ -952,7 +953,7 @@ lcd_goto_screen(lcd_status_screen); echo_and_take_a_measurement(); - const float z1 = use_encoder_wheel_to_measure_point(); + const float z1 = measure_point_with_encoder(); do_blocking_move_to_z(current_position[Z_AXIS] + SIZE_OF_LITTLE_RAISE); stepper.synchronize(); @@ -960,7 +961,7 @@ LCD_MESSAGEPGM("Remove & measure bed"); // TODO: Make translatable string echo_and_take_a_measurement(); - const float z2 = use_encoder_wheel_to_measure_point(); + const float z2 = measure_point_with_encoder(); do_blocking_move_to_z(current_position[Z_AXIS] + Z_CLEARANCE_BETWEEN_PROBES); @@ -974,17 +975,17 @@ in_height = current_position[Z_AXIS]; // do manual probing at lower height - ubl.has_control_of_lcd_panel = false; + has_control_of_lcd_panel = false; - ubl.restore_ubl_active_state_and_leave(); + restore_ubl_active_state_and_leave(); return thickness; } - void manually_probe_remaining_mesh(const float &lx, const float &ly, const float &z_clearance, const float &card_thickness, const bool do_ubl_mesh_map) { + void unified_bed_leveling::manually_probe_remaining_mesh(const float &lx, const float &ly, const float &z_clearance, const float &thick, const bool do_ubl_mesh_map) { - ubl.has_control_of_lcd_panel = true; - ubl.save_ubl_active_state_and_disable(); // we don't do bed level correction because we want the raw data when we probe + has_control_of_lcd_panel = true; + save_ubl_active_state_and_disable(); // we don't do bed level correction because we want the raw data when we probe do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); do_blocking_move_to_xy(lx, ly); @@ -995,8 +996,8 @@ // It doesn't matter if the probe can't reach the NAN location. This is a manual probe. if (location.x_index < 0 && location.y_index < 0) continue; - const float rawx = pgm_read_float(&ubl.mesh_index_to_xpos[location.x_index]), - rawy = pgm_read_float(&ubl.mesh_index_to_ypos[location.y_index]), + const float rawx = mesh_index_to_xpos(location.x_index), + rawy = mesh_index_to_ypos(location.y_index), xProbe = LOGICAL_X_POSITION(rawx), yProbe = LOGICAL_Y_POSITION(rawy); @@ -1010,9 +1011,9 @@ do_blocking_move_to_z(z_clearance); KEEPALIVE_STATE(PAUSED_FOR_USER); - ubl.has_control_of_lcd_panel = true; + has_control_of_lcd_panel = true; - if (do_ubl_mesh_map) ubl.display_map(map_type); // show user where we're probing + if (do_ubl_mesh_map) display_map(g29_map_type); // show user where we're probing if (code_seen('B')) LCD_MESSAGEPGM("Place shim & measure"); // TODO: Make translatable string @@ -1023,9 +1024,9 @@ delay(50); // debounce while (!ubl_lcd_clicked()) { // we need the loop to move the nozzle based on the encoder wheel here! idle(); - if (ubl.encoder_diff) { - do_blocking_move_to_z(current_position[Z_AXIS] + float(ubl.encoder_diff) / 100.0); - ubl.encoder_diff = 0; + if (encoder_diff) { + do_blocking_move_to_z(current_position[Z_AXIS] + float(encoder_diff) / 100.0); + encoder_diff = 0; } } @@ -1040,48 +1041,47 @@ do_blocking_move_to_z(Z_CLEARANCE_DEPLOY_PROBE); lcd_quick_feedback(); while (ubl_lcd_clicked()) idle(); - ubl.has_control_of_lcd_panel = false; + has_control_of_lcd_panel = false; KEEPALIVE_STATE(IN_HANDLER); - ubl.restore_ubl_active_state_and_leave(); + restore_ubl_active_state_and_leave(); return; } } - ubl.z_values[location.x_index][location.y_index] = current_position[Z_AXIS] - card_thickness; + z_values[location.x_index][location.y_index] = current_position[Z_AXIS] - thick; if (g29_verbose_level > 2) { SERIAL_PROTOCOLPGM("Mesh Point Measured at: "); - SERIAL_PROTOCOL_F(ubl.z_values[location.x_index][location.y_index], 6); + SERIAL_PROTOCOL_F(z_values[location.x_index][location.y_index], 6); SERIAL_EOL; } } while (location.x_index >= 0 && location.y_index >= 0); - if (do_ubl_mesh_map) ubl.display_map(map_type); + if (do_ubl_mesh_map) display_map(g29_map_type); - ubl.restore_ubl_active_state_and_leave(); + restore_ubl_active_state_and_leave(); KEEPALIVE_STATE(IN_HANDLER); do_blocking_move_to_z(Z_CLEARANCE_DEPLOY_PROBE); do_blocking_move_to_xy(lx, ly); } - bool g29_parameter_parsing() { + bool unified_bed_leveling::g29_parameter_parsing() { bool err_flag = false; LCD_MESSAGEPGM("Doing G29 UBL!"); // TODO: Make translatable string lcd_quick_feedback(); - ubl_constant = 0.0; - repetition_cnt = 0; + g29_constant = 0.0; + g29_repetition_cnt = 0; - x_flag = code_seen('X') && code_has_value(); - x_pos = x_flag ? code_value_float() : current_position[X_AXIS]; - y_flag = code_seen('Y') && code_has_value(); - y_pos = y_flag ? code_value_float() : current_position[Y_AXIS]; + g29_x_flag = code_seen('X') && code_has_value(); + g29_x_pos = g29_x_flag ? code_value_float() : current_position[X_AXIS]; + g29_y_flag = code_seen('Y') && code_has_value(); + g29_y_pos = g29_y_flag ? code_value_float() : current_position[Y_AXIS]; - repeat_flag = code_seen('R'); - if (repeat_flag) { - repetition_cnt = code_has_value() ? code_value_int() : GRID_MAX_POINTS; - NOMORE(repetition_cnt, GRID_MAX_POINTS); - if (repetition_cnt < 1) { + if (code_seen('R')) { + g29_repetition_cnt = code_has_value() ? code_value_int() : GRID_MAX_POINTS; + NOMORE(g29_repetition_cnt, GRID_MAX_POINTS); + if (g29_repetition_cnt < 1) { SERIAL_PROTOCOLLNPGM("?(R)epetition count invalid (1+).\n"); return UBL_ERR; } @@ -1094,31 +1094,31 @@ } if (code_seen('P')) { - phase_value = code_value_int(); - if (!WITHIN(phase_value, 0, 6)) { + g29_phase_value = code_value_int(); + if (!WITHIN(g29_phase_value, 0, 6)) { SERIAL_PROTOCOLLNPGM("?(P)hase value invalid (0-6).\n"); err_flag = true; } } if (code_seen('J')) { - grid_size = code_has_value() ? code_value_int() : 0; - if (grid_size!=0 && !WITHIN(grid_size, 2, 9)) { + g29_grid_size = code_has_value() ? code_value_int() : 0; + if (g29_grid_size && !WITHIN(g29_grid_size, 2, 9)) { SERIAL_PROTOCOLLNPGM("?Invalid grid size (J) specified (2-9).\n"); err_flag = true; } } - if (x_flag != y_flag) { + if (g29_x_flag != g29_y_flag) { SERIAL_PROTOCOLLNPGM("Both X & Y locations must be specified.\n"); err_flag = true; } - if (!WITHIN(RAW_X_POSITION(x_pos), X_MIN_POS, X_MAX_POS)) { + if (!WITHIN(RAW_X_POSITION(g29_x_pos), X_MIN_POS, X_MAX_POS)) { SERIAL_PROTOCOLLNPGM("Invalid X location specified.\n"); err_flag = true; } - if (!WITHIN(RAW_Y_POSITION(y_pos), Y_MIN_POS, Y_MAX_POS)) { + if (!WITHIN(RAW_Y_POSITION(g29_y_pos), Y_MIN_POS, Y_MAX_POS)) { SERIAL_PROTOCOLLNPGM("Invalid Y location specified.\n"); err_flag = true; } @@ -1131,17 +1131,17 @@ SERIAL_PROTOCOLLNPGM("?Can't activate and deactivate at the same time.\n"); return UBL_ERR; } - ubl.state.active = true; - ubl.report_state(); + state.active = true; + report_state(); } else if (code_seen('D')) { - ubl.state.active = false; - ubl.report_state(); + state.active = false; + report_state(); } // Set global 'C' flag and its value - if ((c_flag = code_seen('C'))) - ubl_constant = code_value_float(); + if ((g29_c_flag = code_seen('C'))) + g29_constant = code_value_float(); #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) if (code_seen('F') && code_has_value()) { @@ -1154,8 +1154,8 @@ } #endif - map_type = code_seen('T') && code_has_value() ? code_value_int() : 0; - if (!WITHIN(map_type, 0, 1)) { + g29_map_type = code_seen('T') && code_has_value() ? code_value_int() : 0; + if (!WITHIN(g29_map_type, 0, 1)) { SERIAL_PROTOCOLLNPGM("Invalid map type.\n"); return UBL_ERR; } @@ -1173,8 +1173,8 @@ lcd_quick_feedback(); return; } - ubl_state_at_invocation = ubl.state.active; - ubl.state.active = 0; + ubl_state_at_invocation = state.active; + state.active = 0; } void unified_bed_leveling::restore_ubl_active_state_and_leave() { @@ -1184,7 +1184,7 @@ lcd_quick_feedback(); return; } - ubl.state.active = ubl_state_at_invocation; + state.active = ubl_state_at_invocation; } /** @@ -1232,7 +1232,7 @@ SERIAL_PROTOCOLPGM("X-Axis Mesh Points at: "); for (uint8_t i = 0; i < GRID_MAX_POINTS_X; i++) { - SERIAL_PROTOCOL_F(LOGICAL_X_POSITION(pgm_read_float(&mesh_index_to_xpos[i])), 3); + SERIAL_PROTOCOL_F(LOGICAL_X_POSITION(mesh_index_to_xpos(i)), 3); SERIAL_PROTOCOLPGM(" "); safe_delay(25); } @@ -1240,7 +1240,7 @@ SERIAL_PROTOCOLPGM("Y-Axis Mesh Points at: "); for (uint8_t i = 0; i < GRID_MAX_POINTS_Y; i++) { - SERIAL_PROTOCOL_F(LOGICAL_Y_POSITION(pgm_read_float(&mesh_index_to_ypos[i])), 3); + SERIAL_PROTOCOL_F(LOGICAL_Y_POSITION(mesh_index_to_ypos(i)), 3); SERIAL_PROTOCOLPGM(" "); safe_delay(25); } @@ -1286,7 +1286,7 @@ * When we are fully debugged, the EEPROM dump command will get deleted also. But * right now, it is good to have the extra information. Soon... we prune this. */ - void g29_eeprom_dump() { + void unified_bed_leveling::g29_eeprom_dump() { unsigned char cccc; uint16_t kkkk; @@ -1311,7 +1311,7 @@ * When we are fully debugged, this may go away. But there are some valid * use cases for the users. So we can wait and see what to do with it. */ - void g29_compare_current_mesh_to_stored_mesh() { + void unified_bed_leveling::g29_compare_current_mesh_to_stored_mesh() { int16_t a = settings.calc_num_meshes(); if (!a) { @@ -1325,26 +1325,26 @@ return; } - storage_slot = code_value_int(); + g29_storage_slot = code_value_int(); - if (!WITHIN(storage_slot, 0, a - 1)) { + if (!WITHIN(g29_storage_slot, 0, a - 1)) { SERIAL_PROTOCOLLNPGM("?Invalid storage slot."); SERIAL_PROTOCOLLNPAIR("?Use 0 to ", a - 1); return; } float tmp_z_values[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y]; - settings.load_mesh(storage_slot, &tmp_z_values); + settings.load_mesh(g29_storage_slot, &tmp_z_values); - SERIAL_PROTOCOLPAIR("Subtracting mesh in slot ", storage_slot); + SERIAL_PROTOCOLPAIR("Subtracting mesh in slot ", g29_storage_slot); SERIAL_PROTOCOLLNPGM(" from current mesh."); for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) - ubl.z_values[x][y] -= tmp_z_values[x][y]; + z_values[x][y] -= tmp_z_values[x][y]; } - mesh_index_pair find_closest_mesh_point_of_type(const MeshPointType type, const float &lx, const float &ly, const bool probe_as_reference, unsigned int bits[16], const bool far_flag) { + mesh_index_pair unified_bed_leveling::find_closest_mesh_point_of_type(const MeshPointType type, const float &lx, const float &ly, const bool probe_as_reference, unsigned int bits[16], const bool far_flag) { mesh_index_pair out_mesh; out_mesh.x_index = out_mesh.y_index = -1; @@ -1357,15 +1357,15 @@ for (uint8_t i = 0; i < GRID_MAX_POINTS_X; i++) { for (uint8_t j = 0; j < GRID_MAX_POINTS_Y; j++) { - if ( (type == INVALID && isnan(ubl.z_values[i][j])) // Check to see if this location holds the right thing - || (type == REAL && !isnan(ubl.z_values[i][j])) + if ( (type == INVALID && isnan(z_values[i][j])) // Check to see if this location holds the right thing + || (type == REAL && !isnan(z_values[i][j])) || (type == SET_IN_BITMAP && is_bit_set(bits, i, j)) ) { // We only get here if we found a Mesh Point of the specified type float raw_x = RAW_CURRENT_POSITION(X), raw_y = RAW_CURRENT_POSITION(Y); - const float mx = pgm_read_float(&ubl.mesh_index_to_xpos[i]), - my = pgm_read_float(&ubl.mesh_index_to_ypos[j]); + const float mx = mesh_index_to_xpos(i), + my = mesh_index_to_ypos(j); // If using the probe as the reference there are some unreachable locations. // Also for round beds, there are grid points outside the bed the nozzle can't reach. @@ -1389,7 +1389,7 @@ if (far_flag) { for (uint8_t k = 0; k < GRID_MAX_POINTS_X; k++) { for (uint8_t l = 0; l < GRID_MAX_POINTS_Y; l++) { - if (i != k && j != l && !isnan(ubl.z_values[k][l])) { + if (i != k && j != l && !isnan(z_values[k][l])) { //distance += pow((float) abs(i - k) * (MESH_X_DIST), 2) + pow((float) abs(j - l) * (MESH_Y_DIST), 2); // working here distance += HYPOT(MESH_X_DIST, MESH_Y_DIST) / log(HYPOT((i - k) * (MESH_X_DIST) + .001, (j - l) * (MESH_Y_DIST)) + .001); } @@ -1415,20 +1415,19 @@ return out_mesh; } - void fine_tune_mesh(const float &lx, const float &ly, const bool do_ubl_mesh_map) { + void unified_bed_leveling::fine_tune_mesh(const float &lx, const float &ly, const bool do_ubl_mesh_map) { if (!code_seen('R')) // fine_tune_mesh() is special. If no repetition count flag is specified - repetition_cnt = 1; // do exactly one mesh location. Otherwise use what the parser decided. + g29_repetition_cnt = 1; // do exactly one mesh location. Otherwise use what the parser decided. mesh_index_pair location; uint16_t not_done[16]; - int32_t round_off; if (!position_is_reachable_xy(lx, ly)) { SERIAL_PROTOCOLLNPGM("(X,Y) outside printable radius."); return; } - ubl.save_ubl_active_state_and_disable(); + save_ubl_active_state_and_disable(); memset(not_done, 0xFF, sizeof(not_done)); @@ -1444,13 +1443,13 @@ bit_clear(not_done, location.x_index, location.y_index); // Mark this location as 'adjusted' so we will find a // different location the next time through the loop - const float rawx = pgm_read_float(&ubl.mesh_index_to_xpos[location.x_index]), - rawy = pgm_read_float(&ubl.mesh_index_to_ypos[location.y_index]); + const float rawx = mesh_index_to_xpos(location.x_index), + rawy = mesh_index_to_ypos(location.y_index); if (!position_is_reachable_raw_xy(rawx, rawy)) // SHOULD NOT OCCUR because find_closest_mesh_point_of_type will only return reachable break; - float new_z = ubl.z_values[location.x_index][location.y_index]; + float new_z = z_values[location.x_index][location.y_index]; if (isnan(new_z)) // if the mesh point is invalid, set it to 0.0 so it can be edited new_z = 0.0; @@ -1461,9 +1460,9 @@ new_z = floor(new_z * 1000.0) * 0.001; // Chop off digits after the 1000ths place KEEPALIVE_STATE(PAUSED_FOR_USER); - ubl.has_control_of_lcd_panel = true; + has_control_of_lcd_panel = true; - if (do_ubl_mesh_map) ubl.display_map(map_type); // show the user which point is being adjusted + if (do_ubl_mesh_map) display_map(g29_map_type); // show the user which point is being adjusted lcd_implementation_clear(); @@ -1482,7 +1481,7 @@ // The technique used here generates a race condition for the encoder click. // It could get detected in lcd_mesh_edit (actually _lcd_mesh_fine_tune) or here. // Let's work on specifying a proper API for the LCD ASAP, OK? - ubl.has_control_of_lcd_panel = true; + has_control_of_lcd_panel = true; // this sequence to detect an ubl_lcd_clicked() debounce it and leave if it is // a Press and Hold is repeated in a lot of places (including G26_Mesh_Validation.cpp). This @@ -1504,19 +1503,19 @@ safe_delay(20); // We don't want any switch noise. - ubl.z_values[location.x_index][location.y_index] = new_z; + z_values[location.x_index][location.y_index] = new_z; lcd_implementation_clear(); - } while (location.x_index >= 0 && --repetition_cnt > 0); + } while (location.x_index >= 0 && --g29_repetition_cnt > 0); FINE_TUNE_EXIT: - ubl.has_control_of_lcd_panel = false; + has_control_of_lcd_panel = false; KEEPALIVE_STATE(IN_HANDLER); - if (do_ubl_mesh_map) ubl.display_map(map_type); - ubl.restore_ubl_active_state_and_leave(); + if (do_ubl_mesh_map) display_map(g29_map_type); + restore_ubl_active_state_and_leave(); do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); do_blocking_move_to_xy(lx, ly); @@ -1531,15 +1530,15 @@ * calculate a 'reasonable' value for the unprobed mesh point. */ - bool smart_fill_one(const uint8_t x, const uint8_t y, const int8_t xdir, const int8_t ydir) { + bool unified_bed_leveling::smart_fill_one(const uint8_t x, const uint8_t y, const int8_t xdir, const int8_t ydir) { const int8_t x1 = x + xdir, x2 = x1 + xdir, y1 = y + ydir, y2 = y1 + ydir; // A NAN next to a pair of real values? - if (isnan(ubl.z_values[x][y]) && !isnan(ubl.z_values[x1][y1]) && !isnan(ubl.z_values[x2][y2])) { - if (ubl.z_values[x1][y1] < ubl.z_values[x2][y2]) // Angled downward? - ubl.z_values[x][y] = ubl.z_values[x1][y1]; // Use nearest (maybe a little too high.) + if (isnan(z_values[x][y]) && !isnan(z_values[x1][y1]) && !isnan(z_values[x2][y2])) { + if (z_values[x1][y1] < z_values[x2][y2]) // Angled downward? + z_values[x][y] = z_values[x1][y1]; // Use nearest (maybe a little too high.) else - ubl.z_values[x][y] = 2.0 * ubl.z_values[x1][y1] - ubl.z_values[x2][y2]; // Angled upward... + z_values[x][y] = 2.0 * z_values[x1][y1] - z_values[x2][y2]; // Angled upward... return true; } return false; @@ -1547,7 +1546,7 @@ typedef struct { uint8_t sx, ex, sy, ey; bool yfirst; } smart_fill_info; - void smart_fill_mesh() { + void unified_bed_leveling::smart_fill_mesh() { const smart_fill_info info[] = { { 0, GRID_MAX_POINTS_X, 0, GRID_MAX_POINTS_Y - 2, false }, // Bottom of the mesh looking up { 0, GRID_MAX_POINTS_X, GRID_MAX_POINTS_Y - 1, 0, false }, // Top of the mesh looking down @@ -1577,17 +1576,17 @@ y_min = max(MIN_PROBE_Y, UBL_MESH_MIN_Y), y_max = min(MAX_PROBE_Y, UBL_MESH_MAX_Y); - const float dx = float(x_max - x_min) / (grid_size - 1.0), - dy = float(y_max - y_min) / (grid_size - 1.0); + const float dx = float(x_max - x_min) / (g29_grid_size - 1.0), + dy = float(y_max - y_min) / (g29_grid_size - 1.0); struct linear_fit_data lsf_results; incremental_LSF_reset(&lsf_results); bool zig_zag = false; - for (uint8_t ix = 0; ix < grid_size; ix++) { + for (uint8_t ix = 0; ix < g29_grid_size; ix++) { const float x = float(x_min) + ix * dx; - for (int8_t iy = 0; iy < grid_size; iy++) { - const float y = float(y_min) + dy * (zig_zag ? grid_size - 1 - iy : iy); + for (int8_t iy = 0; iy < g29_grid_size; iy++) { + const float y = float(y_min) + dy * (zig_zag ? g29_grid_size - 1 - iy : iy); float measured_z = probe_pt(LOGICAL_X_POSITION(x), LOGICAL_Y_POSITION(y), code_seen('E'), g29_verbose_level); // TODO: Needs error handling #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) { @@ -1654,8 +1653,8 @@ for (uint8_t i = 0; i < GRID_MAX_POINTS_X; i++) { for (uint8_t j = 0; j < GRID_MAX_POINTS_Y; j++) { - float x_tmp = pgm_read_float(&mesh_index_to_xpos[i]), - y_tmp = pgm_read_float(&mesh_index_to_ypos[j]), + float x_tmp = mesh_index_to_xpos(i), + y_tmp = mesh_index_to_ypos(j), z_tmp = z_values[i][j]; #if ENABLED(DEBUG_LEVELING_FEATURE) @@ -1715,47 +1714,40 @@ } #if ENABLED(UBL_G29_P31) - - // Note: using optimize("O2") for this routine results in smaller - // codegen than default optimize("Os") on A2560. - - void _O2 smart_fill_wlsf( float weight_factor ) { + void unified_bed_leveling::smart_fill_wlsf(const float &weight_factor) { // For each undefined mesh point, compute a distance-weighted least squares fit // from all the originally populated mesh points, weighted toward the point // being extrapolated so that nearby points will have greater influence on // the point being extrapolated. Then extrapolate the mesh point from WLSF. - static_assert( GRID_MAX_POINTS_Y <= 16, "GRID_MAX_POINTS_Y too big" ); - uint16_t bitmap[GRID_MAX_POINTS_X] = {0}; + static_assert(GRID_MAX_POINTS_Y <= 16, "GRID_MAX_POINTS_Y too big"); + uint16_t bitmap[GRID_MAX_POINTS_X] = { 0 }; struct linear_fit_data lsf_results; SERIAL_ECHOPGM("Extrapolating mesh..."); const float weight_scaled = weight_factor * max(MESH_X_DIST, MESH_Y_DIST); - for (uint8_t jx = 0; jx < GRID_MAX_POINTS_X; jx++) { - for (uint8_t jy = 0; jy < GRID_MAX_POINTS_Y; jy++) { - if ( !isnan( ubl.z_values[jx][jy] )) { - bitmap[jx] |= (uint16_t)1 << jy; - } - } - } + for (uint8_t jx = 0; jx < GRID_MAX_POINTS_X; jx++) + for (uint8_t jy = 0; jy < GRID_MAX_POINTS_Y; jy++) + if (!isnan(z_values[jx][jy])) + SBI(bitmap[jx], jy); for (uint8_t ix = 0; ix < GRID_MAX_POINTS_X; ix++) { - const float px = pgm_read_float(&(ubl.mesh_index_to_xpos[ix])); + const float px = mesh_index_to_xpos(ix); for (uint8_t iy = 0; iy < GRID_MAX_POINTS_Y; iy++) { - const float py = pgm_read_float(&(ubl.mesh_index_to_ypos[iy])); - if ( isnan( ubl.z_values[ix][iy] )) { + const float py = mesh_index_to_ypos(iy); + if (isnan(z_values[ix][iy])) { // undefined mesh point at (px,py), compute weighted LSF from original valid mesh points. incremental_LSF_reset(&lsf_results); for (uint8_t jx = 0; jx < GRID_MAX_POINTS_X; jx++) { - const float rx = pgm_read_float(&(ubl.mesh_index_to_xpos[jx])); + const float rx = mesh_index_to_xpos(jx); for (uint8_t jy = 0; jy < GRID_MAX_POINTS_Y; jy++) { - if ( bitmap[jx] & (uint16_t)1 << jy ) { - const float ry = pgm_read_float(&(ubl.mesh_index_to_ypos[jy])); - const float rz = ubl.z_values[jx][jy]; - const float w = 1.0 + weight_scaled / HYPOT((rx - px),(ry - py)); + if (TEST(bitmap[jx], jy)) { + const float ry = mesh_index_to_ypos(jy), + rz = z_values[jx][jy], + w = 1.0 + weight_scaled / HYPOT((rx - px), (ry - py)); incremental_WLSF(&lsf_results, rx, ry, rz, w); } } @@ -1765,7 +1757,7 @@ return; } const float ez = -lsf_results.D - lsf_results.A * px - lsf_results.B * py; - ubl.z_values[ix][iy] = ez; + z_values[ix][iy] = ez; idle(); // housekeeping } } @@ -1775,5 +1767,4 @@ } #endif // UBL_G29_P31 - #endif // AUTO_BED_LEVELING_UBL diff --git a/Marlin/ubl_motion.cpp b/Marlin/ubl_motion.cpp index 64aac5e17..3bd8165d1 100644 --- a/Marlin/ubl_motion.cpp +++ b/Marlin/ubl_motion.cpp @@ -85,7 +85,7 @@ } - void ubl_line_to_destination_cartesian(const float &feed_rate, uint8_t extruder) { + void unified_bed_leveling::line_to_destination_cartesian(const float &feed_rate, uint8_t extruder) { /** * Much of the nozzle movement will be within the same cell. So we will do as little computation * as possible to determine if this is the case. If this move is within the same cell, we will @@ -104,19 +104,19 @@ destination[E_AXIS] }; - const int cell_start_xi = ubl.get_cell_index_x(RAW_X_POSITION(start[X_AXIS])), - cell_start_yi = ubl.get_cell_index_y(RAW_Y_POSITION(start[Y_AXIS])), - cell_dest_xi = ubl.get_cell_index_x(RAW_X_POSITION(end[X_AXIS])), - cell_dest_yi = ubl.get_cell_index_y(RAW_Y_POSITION(end[Y_AXIS])); + const int cell_start_xi = get_cell_index_x(RAW_X_POSITION(start[X_AXIS])), + cell_start_yi = get_cell_index_y(RAW_Y_POSITION(start[Y_AXIS])), + cell_dest_xi = get_cell_index_x(RAW_X_POSITION(end[X_AXIS])), + cell_dest_yi = get_cell_index_y(RAW_Y_POSITION(end[Y_AXIS])); - if (ubl.g26_debug_flag) { - SERIAL_ECHOPAIR(" ubl_line_to_destination(xe=", end[X_AXIS]); + if (g26_debug_flag) { + SERIAL_ECHOPAIR(" ubl.line_to_destination(xe=", end[X_AXIS]); SERIAL_ECHOPAIR(", ye=", end[Y_AXIS]); SERIAL_ECHOPAIR(", ze=", end[Z_AXIS]); SERIAL_ECHOPAIR(", ee=", end[E_AXIS]); SERIAL_CHAR(')'); SERIAL_EOL; - debug_current_and_destination(PSTR("Start of ubl_line_to_destination()")); + debug_current_and_destination(PSTR("Start of ubl.line_to_destination()")); } if (cell_start_xi == cell_dest_xi && cell_start_yi == cell_dest_yi) { // if the whole move is within the same cell, @@ -132,11 +132,11 @@ // Note: There is no Z Correction in this case. We are off the grid and don't know what // a reasonable correction would be. - planner._buffer_line(end[X_AXIS], end[Y_AXIS], end[Z_AXIS] + ubl.state.z_offset, end[E_AXIS], feed_rate, extruder); + planner._buffer_line(end[X_AXIS], end[Y_AXIS], end[Z_AXIS] + state.z_offset, end[E_AXIS], feed_rate, extruder); set_current_to_destination(); - if (ubl.g26_debug_flag) - debug_current_and_destination(PSTR("out of bounds in ubl_line_to_destination()")); + if (g26_debug_flag) + debug_current_and_destination(PSTR("out of bounds in ubl.line_to_destination()")); return; } @@ -152,20 +152,20 @@ * to create a 1-over number for us. That will allow us to do a floating point multiply instead of a floating point divide. */ - const float xratio = (RAW_X_POSITION(end[X_AXIS]) - pgm_read_float(&ubl.mesh_index_to_xpos[cell_dest_xi])) * (1.0 / (MESH_X_DIST)), - z1 = ubl.z_values[cell_dest_xi ][cell_dest_yi ] + xratio * - (ubl.z_values[cell_dest_xi + 1][cell_dest_yi ] - ubl.z_values[cell_dest_xi][cell_dest_yi ]), - z2 = ubl.z_values[cell_dest_xi ][cell_dest_yi + 1] + xratio * - (ubl.z_values[cell_dest_xi + 1][cell_dest_yi + 1] - ubl.z_values[cell_dest_xi][cell_dest_yi + 1]); + const float xratio = (RAW_X_POSITION(end[X_AXIS]) - mesh_index_to_xpos(cell_dest_xi)) * (1.0 / (MESH_X_DIST)), + z1 = z_values[cell_dest_xi ][cell_dest_yi ] + xratio * + (z_values[cell_dest_xi + 1][cell_dest_yi ] - z_values[cell_dest_xi][cell_dest_yi ]), + z2 = z_values[cell_dest_xi ][cell_dest_yi + 1] + xratio * + (z_values[cell_dest_xi + 1][cell_dest_yi + 1] - z_values[cell_dest_xi][cell_dest_yi + 1]); // we are done with the fractional X distance into the cell. Now with the two Z-Heights we have calculated, we // are going to apply the Y-Distance into the cell to interpolate the final Z correction. - const float yratio = (RAW_Y_POSITION(end[Y_AXIS]) - pgm_read_float(&ubl.mesh_index_to_ypos[cell_dest_yi])) * (1.0 / (MESH_Y_DIST)); + const float yratio = (RAW_Y_POSITION(end[Y_AXIS]) - mesh_index_to_ypos(cell_dest_yi)) * (1.0 / (MESH_Y_DIST)); float z0 = z1 + (z2 - z1) * yratio; - z0 *= ubl.fade_scaling_factor_for_z(end[Z_AXIS]); + z0 *= fade_scaling_factor_for_z(end[Z_AXIS]); /** * If part of the Mesh is undefined, it will show up as NAN @@ -176,10 +176,10 @@ */ if (isnan(z0)) z0 = 0.0; - planner._buffer_line(end[X_AXIS], end[Y_AXIS], end[Z_AXIS] + z0 + ubl.state.z_offset, end[E_AXIS], feed_rate, extruder); + planner._buffer_line(end[X_AXIS], end[Y_AXIS], end[Z_AXIS] + z0 + state.z_offset, end[E_AXIS], feed_rate, extruder); - if (ubl.g26_debug_flag) - debug_current_and_destination(PSTR("FINAL_MOVE in ubl_line_to_destination()")); + if (g26_debug_flag) + debug_current_and_destination(PSTR("FINAL_MOVE in ubl.line_to_destination()")); set_current_to_destination(); return; @@ -240,7 +240,7 @@ current_yi += down_flag; // Line is heading down, we just want to go to the bottom while (current_yi != cell_dest_yi + down_flag) { current_yi += dyi; - const float next_mesh_line_y = LOGICAL_Y_POSITION(pgm_read_float(&ubl.mesh_index_to_ypos[current_yi])); + const float next_mesh_line_y = LOGICAL_Y_POSITION(mesh_index_to_ypos(current_yi)); /** * if the slope of the line is infinite, we won't do the calculations @@ -249,9 +249,9 @@ */ const float x = inf_m_flag ? start[X_AXIS] : (next_mesh_line_y - c) / m; - float z0 = ubl.z_correction_for_x_on_horizontal_mesh_line(x, current_xi, current_yi); + float z0 = z_correction_for_x_on_horizontal_mesh_line(x, current_xi, current_yi); - z0 *= ubl.fade_scaling_factor_for_z(end[Z_AXIS]); + z0 *= fade_scaling_factor_for_z(end[Z_AXIS]); /** * If part of the Mesh is undefined, it will show up as NAN @@ -262,7 +262,7 @@ */ if (isnan(z0)) z0 = 0.0; - const float y = LOGICAL_Y_POSITION(pgm_read_float(&ubl.mesh_index_to_ypos[current_yi])); + const float y = LOGICAL_Y_POSITION(mesh_index_to_ypos(current_yi)); /** * Without this check, it is possible for the algorithm to generate a zero length move in the case @@ -281,12 +281,12 @@ z_position = end[Z_AXIS]; } - planner._buffer_line(x, y, z_position + z0 + ubl.state.z_offset, e_position, feed_rate, extruder); + planner._buffer_line(x, y, z_position + z0 + state.z_offset, e_position, feed_rate, extruder); } //else printf("FIRST MOVE PRUNED "); } - if (ubl.g26_debug_flag) - debug_current_and_destination(PSTR("vertical move done in ubl_line_to_destination()")); + if (g26_debug_flag) + debug_current_and_destination(PSTR("vertical move done in ubl.line_to_destination()")); // // Check if we are at the final destination. Usually, we won't be, but if it is on a Y Mesh Line, we are done. @@ -311,12 +311,12 @@ // edge of this cell for the first move. while (current_xi != cell_dest_xi + left_flag) { current_xi += dxi; - const float next_mesh_line_x = LOGICAL_X_POSITION(pgm_read_float(&ubl.mesh_index_to_xpos[current_xi])), + const float next_mesh_line_x = LOGICAL_X_POSITION(mesh_index_to_xpos(current_xi)), y = m * next_mesh_line_x + c; // Calculate Y at the next X mesh line - float z0 = ubl.z_correction_for_y_on_vertical_mesh_line(y, current_xi, current_yi); + float z0 = z_correction_for_y_on_vertical_mesh_line(y, current_xi, current_yi); - z0 *= ubl.fade_scaling_factor_for_z(end[Z_AXIS]); + z0 *= fade_scaling_factor_for_z(end[Z_AXIS]); /** * If part of the Mesh is undefined, it will show up as NAN @@ -327,7 +327,7 @@ */ if (isnan(z0)) z0 = 0.0; - const float x = LOGICAL_X_POSITION(pgm_read_float(&ubl.mesh_index_to_xpos[current_xi])); + const float x = LOGICAL_X_POSITION(mesh_index_to_xpos(current_xi)); /** * Without this check, it is possible for the algorithm to generate a zero length move in the case @@ -346,12 +346,12 @@ z_position = end[Z_AXIS]; } - planner._buffer_line(x, y, z_position + z0 + ubl.state.z_offset, e_position, feed_rate, extruder); + planner._buffer_line(x, y, z_position + z0 + state.z_offset, e_position, feed_rate, extruder); } //else printf("FIRST MOVE PRUNED "); } - if (ubl.g26_debug_flag) - debug_current_and_destination(PSTR("horizontal move done in ubl_line_to_destination()")); + if (g26_debug_flag) + debug_current_and_destination(PSTR("horizontal move done in ubl.line_to_destination()")); if (current_position[X_AXIS] != end[X_AXIS] || current_position[Y_AXIS] != end[Y_AXIS]) goto FINAL_MOVE; @@ -377,8 +377,8 @@ while (xi_cnt > 0 || yi_cnt > 0) { - const float next_mesh_line_x = LOGICAL_X_POSITION(pgm_read_float(&ubl.mesh_index_to_xpos[current_xi + dxi])), - next_mesh_line_y = LOGICAL_Y_POSITION(pgm_read_float(&ubl.mesh_index_to_ypos[current_yi + dyi])), + const float next_mesh_line_x = LOGICAL_X_POSITION(mesh_index_to_xpos(current_xi + dxi)), + next_mesh_line_y = LOGICAL_Y_POSITION(mesh_index_to_ypos(current_yi + dyi)), y = m * next_mesh_line_x + c, // Calculate Y at the next X mesh line x = (next_mesh_line_y - c) / m; // Calculate X at the next Y mesh line // (No need to worry about m being zero. @@ -387,9 +387,9 @@ if (left_flag == (x > next_mesh_line_x)) { // Check if we hit the Y line first // Yes! Crossing a Y Mesh Line next - float z0 = ubl.z_correction_for_x_on_horizontal_mesh_line(x, current_xi - left_flag, current_yi + dyi); + float z0 = z_correction_for_x_on_horizontal_mesh_line(x, current_xi - left_flag, current_yi + dyi); - z0 *= ubl.fade_scaling_factor_for_z(end[Z_AXIS]); + z0 *= fade_scaling_factor_for_z(end[Z_AXIS]); /** * If part of the Mesh is undefined, it will show up as NAN @@ -409,15 +409,15 @@ e_position = end[E_AXIS]; z_position = end[Z_AXIS]; } - planner._buffer_line(x, next_mesh_line_y, z_position + z0 + ubl.state.z_offset, e_position, feed_rate, extruder); + planner._buffer_line(x, next_mesh_line_y, z_position + z0 + state.z_offset, e_position, feed_rate, extruder); current_yi += dyi; yi_cnt--; } else { // Yes! Crossing a X Mesh Line next - float z0 = ubl.z_correction_for_y_on_vertical_mesh_line(y, current_xi + dxi, current_yi - down_flag); + float z0 = z_correction_for_y_on_vertical_mesh_line(y, current_xi + dxi, current_yi - down_flag); - z0 *= ubl.fade_scaling_factor_for_z(end[Z_AXIS]); + z0 *= fade_scaling_factor_for_z(end[Z_AXIS]); /** * If part of the Mesh is undefined, it will show up as NAN @@ -438,7 +438,7 @@ z_position = end[Z_AXIS]; } - planner._buffer_line(next_mesh_line_x, y, z_position + z0 + ubl.state.z_offset, e_position, feed_rate, extruder); + planner._buffer_line(next_mesh_line_x, y, z_position + z0 + state.z_offset, e_position, feed_rate, extruder); current_xi += dxi; xi_cnt--; } @@ -446,8 +446,8 @@ if (xi_cnt < 0 || yi_cnt < 0) break; // we've gone too far, so exit the loop and move on to FINAL_MOVE } - if (ubl.g26_debug_flag) - debug_current_and_destination(PSTR("generic move done in ubl_line_to_destination()")); + if (g26_debug_flag) + debug_current_and_destination(PSTR("generic move done in ubl.line_to_destination()")); if (current_position[X_AXIS] != end[X_AXIS] || current_position[Y_AXIS] != end[Y_AXIS]) goto FINAL_MOVE; @@ -502,7 +502,7 @@ * Returns true if the caller did NOT update current_position, otherwise false. */ - static bool ubl_prepare_linear_move_to(const float ltarget[XYZE], const float &feedrate) { + static bool unified_bed_leveling::prepare_linear_move_to(const float ltarget[XYZE], const float &feedrate) { if (!position_is_reachable_xy(ltarget[X_AXIS], ltarget[Y_AXIS])) // fail if moving outside reachable boundary return true; // did not move, so current_position still accurate @@ -554,9 +554,9 @@ // Only compute leveling per segment if ubl active and target below z_fade_height. - if (!ubl.state.active || above_fade_height) { // no mesh leveling + if (!state.active || above_fade_height) { // no mesh leveling - const float z_offset = ubl.state.active ? ubl.state.z_offset : 0.0; + const float z_offset = state.active ? state.z_offset : 0.0; float seg_dest[XYZE]; // per-segment destination, COPY_XYZE(seg_dest, current_position); // starting from current position @@ -579,7 +579,7 @@ // Otherwise perform per-segment leveling #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - const float fade_scaling_factor = ubl.fade_scaling_factor_for_z(ltarget[Z_AXIS]); + const float fade_scaling_factor = fade_scaling_factor_for_z(ltarget[Z_AXIS]); #endif float seg_dest[XYZE]; // per-segment destination, initialize to first segment @@ -591,7 +591,7 @@ float rx = RAW_X_POSITION(seg_dest[X_AXIS]), // assume raw vs logical coordinates shifted but not scaled. ry = RAW_Y_POSITION(seg_dest[Y_AXIS]); - do { // for each mesh cell encountered during the move + for(;;) { // for each mesh cell encountered during the move // Compute mesh cell invariants that remain constant for all segments within cell. // Note for cell index, if point is outside the mesh grid (in MESH_INSET perimeter) @@ -606,19 +606,19 @@ cell_xi = constrain(cell_xi, 0, (GRID_MAX_POINTS_X) - 1); cell_yi = constrain(cell_yi, 0, (GRID_MAX_POINTS_Y) - 1); - const float x0 = pgm_read_float(&(ubl.mesh_index_to_xpos[cell_xi ])), // 64 byte table lookup avoids mul+add - y0 = pgm_read_float(&(ubl.mesh_index_to_ypos[cell_yi ])), // 64 byte table lookup avoids mul+add - x1 = pgm_read_float(&(ubl.mesh_index_to_xpos[cell_xi+1])), // 64 byte table lookup avoids mul+add - y1 = pgm_read_float(&(ubl.mesh_index_to_ypos[cell_yi+1])); // 64 byte table lookup avoids mul+add + const float x0 = pgm_read_float(&(mesh_index_to_xpos[cell_xi ])), // 64 byte table lookup avoids mul+add + y0 = pgm_read_float(&(mesh_index_to_ypos[cell_yi ])), // 64 byte table lookup avoids mul+add + x1 = pgm_read_float(&(mesh_index_to_xpos[cell_xi+1])), // 64 byte table lookup avoids mul+add + y1 = pgm_read_float(&(mesh_index_to_ypos[cell_yi+1])); // 64 byte table lookup avoids mul+add float cx = rx - x0, // cell-relative x cy = ry - y0, // cell-relative y - z_x0y0 = ubl.z_values[cell_xi ][cell_yi ], // z at lower left corner - z_x1y0 = ubl.z_values[cell_xi+1][cell_yi ], // z at upper left corner - z_x0y1 = ubl.z_values[cell_xi ][cell_yi+1], // z at lower right corner - z_x1y1 = ubl.z_values[cell_xi+1][cell_yi+1]; // z at upper right corner + z_x0y0 = z_values[cell_xi ][cell_yi ], // z at lower left corner + z_x1y0 = z_values[cell_xi+1][cell_yi ], // z at upper left corner + z_x0y1 = z_values[cell_xi ][cell_yi+1], // z at lower right corner + z_x1y1 = z_values[cell_xi+1][cell_yi+1]; // z at upper right corner - if (isnan(z_x0y0)) z_x0y0 = 0; // ideally activating ubl.state.active (G29 A) + if (isnan(z_x0y0)) z_x0y0 = 0; // ideally activating state.active (G29 A) if (isnan(z_x1y0)) z_x1y0 = 0; // should refuse if any invalid mesh points if (isnan(z_x0y1)) z_x0y1 = 0; // in order to avoid isnan tests per cell, if (isnan(z_x1y1)) z_x1y1 = 0; // thus guessing zero for undefined points @@ -642,7 +642,7 @@ const float z_sxy0 = z_xmy0 * dx_seg, // per-segment adjustment to z_cxy0 z_sxym = (z_xmy1 - z_xmy0) * (1.0 / (MESH_Y_DIST)) * dx_seg; // per-segment adjustment to z_cxym - do { // for all segments within this mesh cell + for(;;) { // for all segments within this mesh cell float z_cxcy = z_cxy0 + z_cxym * cy; // interpolated mesh z height along cx at cy @@ -650,7 +650,7 @@ z_cxcy *= fade_scaling_factor; // apply fade factor to interpolated mesh height #endif - z_cxcy += ubl.state.z_offset; // add fixed mesh offset from G29 Z + z_cxcy += state.z_offset; // add fixed mesh offset from G29 Z if (--segments == 0) { // if this is last segment, use ltarget for exact COPY_XYZE(seg_dest, ltarget); @@ -681,9 +681,9 @@ z_cxy0 += z_sxy0; // adjust z_cxy0 by per-segment z_sxy0 z_cxym += z_sxym; // adjust z_cxym by per-segment z_sxym - } while (true); // per-segment loop exits by break after last segment within cell, or by return on final segment - } while (true); // per-cell loop - } // end of function + } // segment loop + } // cell loop + } #endif // UBL_DELTA From 34cfbc90cdb95288e5ec928baf5484f580426e9c Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 22 May 2017 13:47:43 -0500 Subject: [PATCH 136/189] Use new attribute macros in more places --- Marlin/macros.h | 12 ++++++------ Marlin/nozzle.cpp | 32 ++++++++++++++++---------------- Marlin/nozzle.h | 42 +++++++++++++++++++++--------------------- Marlin/spi.h | 31 ++++++++++--------------------- Marlin/temperature.cpp | 2 +- Marlin/temperature.h | 3 +-- 6 files changed, 55 insertions(+), 67 deletions(-) diff --git a/Marlin/macros.h b/Marlin/macros.h index 3e3237a1d..e7283f867 100644 --- a/Marlin/macros.h +++ b/Marlin/macros.h @@ -29,12 +29,12 @@ #define XYZ 3 #define FORCE_INLINE __attribute__((always_inline)) inline - -#define _O0 __attribute__((optimize("O0"))) -#define _Os __attribute__((optimize("Os"))) -#define _O1 __attribute__((optimize("O1"))) -#define _O2 __attribute__((optimize("O2"))) -#define _O3 __attribute__((optimize("O3"))) +#define _UNUSED __attribute__((unused)) +#define _O0 __attribute__((optimize("O0"))) +#define _Os __attribute__((optimize("Os"))) +#define _O1 __attribute__((optimize("O1"))) +#define _O2 __attribute__((optimize("O2"))) +#define _O3 __attribute__((optimize("O3"))) // Bracket code that shouldn't be interrupted #ifndef CRITICAL_SECTION_START diff --git a/Marlin/nozzle.cpp b/Marlin/nozzle.cpp index 92f697df1..569fba62a 100644 --- a/Marlin/nozzle.cpp +++ b/Marlin/nozzle.cpp @@ -12,9 +12,9 @@ * @param strokes number of strokes to execute */ void Nozzle::stroke( - __attribute__((unused)) point_t const &start, - __attribute__((unused)) point_t const &end, - __attribute__((unused)) uint8_t const &strokes + _UNUSED point_t const &start, + _UNUSED point_t const &end, + _UNUSED uint8_t const &strokes ) { #if ENABLED(NOZZLE_CLEAN_FEATURE) @@ -56,10 +56,10 @@ void Nozzle::stroke( * @param objects number of objects to create */ void Nozzle::zigzag( - __attribute__((unused)) point_t const &start, - __attribute__((unused)) point_t const &end, - __attribute__((unused)) uint8_t const &strokes, - __attribute__((unused)) uint8_t const &objects + _UNUSED point_t const &start, + _UNUSED point_t const &end, + _UNUSED uint8_t const &strokes, + _UNUSED uint8_t const &objects ) { #if ENABLED(NOZZLE_CLEAN_FEATURE) const float A = nozzle_clean_horizontal ? nozzle_clean_height : nozzle_clean_length, // [twice the] Amplitude @@ -114,10 +114,10 @@ void Nozzle::zigzag( * @param radius radius of circle */ void Nozzle::circle( - __attribute__((unused)) point_t const &start, - __attribute__((unused)) point_t const &middle, - __attribute__((unused)) uint8_t const &strokes, - __attribute__((unused)) float const &radius + _UNUSED point_t const &start, + _UNUSED point_t const &middle, + _UNUSED uint8_t const &strokes, + _UNUSED float const &radius ) { #if ENABLED(NOZZLE_CLEAN_FEATURE) if (strokes == 0) return; @@ -177,10 +177,10 @@ void Nozzle::circle( * @param argument depends on the cleaning pattern */ void Nozzle::clean( - __attribute__((unused)) uint8_t const &pattern, - __attribute__((unused)) uint8_t const &strokes, - __attribute__((unused)) float const &radius, - __attribute__((unused)) uint8_t const &objects + _UNUSED uint8_t const &pattern, + _UNUSED uint8_t const &strokes, + _UNUSED float const &radius, + _UNUSED uint8_t const &objects ) { #if ENABLED(NOZZLE_CLEAN_FEATURE) #if ENABLED(DELTA) @@ -209,7 +209,7 @@ void Nozzle::clean( } void Nozzle::park( - __attribute__((unused)) uint8_t const &z_action + _UNUSED uint8_t const &z_action ) { #if ENABLED(NOZZLE_PARK_FEATURE) float const z = current_position[Z_AXIS]; diff --git a/Marlin/nozzle.h b/Marlin/nozzle.h index 944dd5d21..39c007f63 100644 --- a/Marlin/nozzle.h +++ b/Marlin/nozzle.h @@ -50,10 +50,10 @@ class Nozzle { * @param strokes number of strokes to execute */ static void stroke( - __attribute__((unused)) point_t const &start, - __attribute__((unused)) point_t const &end, - __attribute__((unused)) uint8_t const &strokes - ) __attribute__((optimize ("Os"))); + _UNUSED point_t const &start, + _UNUSED point_t const &end, + _UNUSED uint8_t const &strokes + ) _Os; /** * @brief Zig-zag clean pattern @@ -65,11 +65,11 @@ class Nozzle { * @param objects number of objects to create */ static void zigzag( - __attribute__((unused)) point_t const &start, - __attribute__((unused)) point_t const &end, - __attribute__((unused)) uint8_t const &strokes, - __attribute__((unused)) uint8_t const &objects - ) __attribute__((optimize ("Os"))); + _UNUSED point_t const &start, + _UNUSED point_t const &end, + _UNUSED uint8_t const &strokes, + _UNUSED uint8_t const &objects + ) _Os; /** * @brief Circular clean pattern @@ -80,11 +80,11 @@ class Nozzle { * @param radius radius of circle */ static void circle( - __attribute__((unused)) point_t const &start, - __attribute__((unused)) point_t const &middle, - __attribute__((unused)) uint8_t const &strokes, - __attribute__((unused)) float const &radius - ) __attribute__((optimize ("Os"))); + _UNUSED point_t const &start, + _UNUSED point_t const &middle, + _UNUSED uint8_t const &strokes, + _UNUSED float const &radius + ) _Os; public: /** @@ -95,15 +95,15 @@ class Nozzle { * @param argument depends on the cleaning pattern */ static void clean( - __attribute__((unused)) uint8_t const &pattern, - __attribute__((unused)) uint8_t const &strokes, - __attribute__((unused)) float const &radius, - __attribute__((unused)) uint8_t const &objects = 0 - ) __attribute__((optimize ("Os"))); + _UNUSED uint8_t const &pattern, + _UNUSED uint8_t const &strokes, + _UNUSED float const &radius, + _UNUSED uint8_t const &objects = 0 + ) _Os; static void park( - __attribute__((unused)) uint8_t const &z_action - ) __attribute__((optimize ("Os"))); + _UNUSED uint8_t const &z_action + ) _Os; }; #endif diff --git a/Marlin/spi.h b/Marlin/spi.h index 349246952..c4b86005a 100644 --- a/Marlin/spi.h +++ b/Marlin/spi.h @@ -27,37 +27,26 @@ #include "softspi.h" template -class Spi { - static SoftSPI softSpi; +class SPI { + static SoftSPI softSPI; public: - inline __attribute__((always_inline)) - static void init() { - softSpi.begin(); - } - inline __attribute__((always_inline)) - static void send(uint8_t data) { - softSpi.send(data); - } - inline __attribute__((always_inline)) - static uint8_t receive() { - return softSpi.receive(); - } + FORCE_INLINE static void init() { softSPI.begin(); } + FORCE_INLINE static void send(uint8_t data) { softSPI.send(data); } + FORCE_INLINE static uint8_t receive() { return softSPI.receive(); } }; -//hardware spi +// Hardware SPI template<> -class Spi { +class SPI { public: - inline __attribute__((always_inline)) - static void init() { + FORCE_INLINE static void init() { OUT_WRITE(SCK_PIN, LOW); OUT_WRITE(MOSI_PIN, HIGH); SET_INPUT(MISO_PIN); WRITE(MISO_PIN, HIGH); } - inline __attribute__((always_inline)) - static uint8_t receive() { + FORCE_INLINE static uint8_t receive() { SPDR = 0; for (;!TEST(SPSR, SPIF);); return SPDR; @@ -65,4 +54,4 @@ class Spi { }; -#endif +#endif // __SPI_H__ diff --git a/Marlin/temperature.cpp b/Marlin/temperature.cpp index d7d681430..f94d98b96 100644 --- a/Marlin/temperature.cpp +++ b/Marlin/temperature.cpp @@ -935,7 +935,7 @@ void Temperature::updateTemperaturesFromRawValues() { #ifndef MAX6675_DO_PIN #define MAX6675_DO_PIN MISO_PIN #endif - Spi max6675_spi; + SPI max6675_spi; #endif /** diff --git a/Marlin/temperature.h b/Marlin/temperature.h index a3c4372df..9b85bbde1 100644 --- a/Marlin/temperature.h +++ b/Marlin/temperature.h @@ -288,8 +288,7 @@ class Temperature { /** * Call periodically to manage heaters */ - //static void manage_heater(); // changed to address compiler error - static void manage_heater() __attribute__((__optimize__("O2"))); + static void manage_heater() _O2; // Added _O2 to work around a compiler error /** * Preheating hotends From 26ffa558a32146ba6451d300391d01aa54e8b09e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 22 May 2017 18:34:05 -0500 Subject: [PATCH 137/189] Use redraw flag for both types of LCD --- Marlin/ultralcd.cpp | 20 +++++++------------- 1 file changed, 7 insertions(+), 13 deletions(-) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index dd1590238..642bb16fd 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -470,7 +470,7 @@ uint16_t max_display_update_time = 0; // For LCD_PROGRESS_BAR re-initialize custom characters lcd_set_custom_characters(screen == lcd_status_screen); #endif - lcdDrawUpdate = LCDVIEW_CALL_REDRAW_NEXT; + lcdDrawUpdate = LCDVIEW_KEEP_REDRAWING; screen_changed = true; #if ENABLED(DOGLCD) drawing_screen = false; @@ -716,7 +716,7 @@ void kill_screen(const char* lcd_msg) { void toggle_case_light() { case_light_on ^= true; - lcdDrawUpdate = LCDVIEW_CALL_REDRAW_NEXT; + lcdDrawUpdate = LCDVIEW_KEEP_REDRAWING; update_case_light(); } @@ -879,7 +879,7 @@ void kill_screen(const char* lcd_msg) { if (encoderPosition) { const int babystep_increment = (int32_t)encoderPosition * (BABYSTEP_MULTIPLICATOR); encoderPosition = 0; - lcdDrawUpdate = LCDVIEW_REDRAW_NOW; + lcdDrawUpdate = LCDVIEW_KEEP_REDRAWING; thermalManager.babystep_axis(axis, babystep_increment); babysteps_done += babystep_increment; } @@ -912,7 +912,7 @@ void kill_screen(const char* lcd_msg) { zprobe_zoffset = new_zoffset; refresh_zprobe_zoffset(true); - lcdDrawUpdate = LCDVIEW_REDRAW_NOW; + lcdDrawUpdate = LCDVIEW_KEEP_REDRAWING; } } if (lcdDrawUpdate) @@ -943,7 +943,7 @@ void kill_screen(const char* lcd_msg) { mesh_edit_accumulator += float(ubl_encoderPosition) * 0.005 / 2.0; mesh_edit_value = mesh_edit_accumulator; encoderPosition = 0; - lcdDrawUpdate = LCDVIEW_REDRAW_NOW; + lcdDrawUpdate = LCDVIEW_KEEP_REDRAWING; const int32_t rounded = (int32_t)(mesh_edit_value * 1000.0); mesh_edit_value = float(rounded - (rounded % 5L)) / 1000.0; @@ -957,14 +957,8 @@ void kill_screen(const char* lcd_msg) { defer_return_to_status = true; } - void _lcd_mesh_edit() { - lcdDrawUpdate = LCDVIEW_REDRAW_NOW; - _lcd_mesh_fine_tune(PSTR("Mesh Editor")); - } - float lcd_mesh_edit() { lcd_goto_screen(_lcd_mesh_edit_NOP); - lcdDrawUpdate = LCDVIEW_REDRAW_NOW; _lcd_mesh_fine_tune(PSTR("Mesh Editor")); return mesh_edit_value; } @@ -2278,7 +2272,7 @@ void kill_screen(const char* lcd_msg) { manual_move_to_current(axis); encoderPosition = 0; - lcdDrawUpdate = LCDVIEW_REDRAW_NOW; + lcdDrawUpdate = LCDVIEW_KEEP_REDRAWING; } if (lcdDrawUpdate) lcd_implementation_drawedit(name, ftostr41sign(current_position[axis])); } @@ -2300,7 +2294,7 @@ void kill_screen(const char* lcd_msg) { , eindex #endif ); - lcdDrawUpdate = LCDVIEW_REDRAW_NOW; + lcdDrawUpdate = LCDVIEW_KEEP_REDRAWING; } if (lcdDrawUpdate) { PGM_P pos_label; From 82ca6248e2d1ae3cc5b02f88e1f698d768154dd2 Mon Sep 17 00:00:00 2001 From: Brian Date: Sun, 21 May 2017 16:47:09 -0400 Subject: [PATCH 138/189] Move G7 to G42 See: #6777 --- Marlin/Marlin_main.cpp | 147 +++++++++++++++++++++-------------------- 1 file changed, 74 insertions(+), 73 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 9dea99c50..5729e7c37 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -45,30 +45,30 @@ * * "G" Codes * - * G0 -> G1 - * G1 - Coordinated Movement X Y Z E - * G2 - CW ARC - * G3 - CCW ARC - * G4 - Dwell S or P - * G5 - Cubic B-spline with XYZE destination and IJPQ offsets - * G7 - Coordinated move between UBL mesh points (I & J) - * G10 - Retract filament according to settings of M207 - * G11 - Retract recover filament according to settings of M208 - * G12 - Clean tool - * G20 - Set input units to inches - * G21 - Set input units to millimeters - * G26 - Mesh Validation Pattern (Requires UBL_G26_MESH_VALIDATION) - * G27 - Park Nozzle (Requires NOZZLE_PARK_FEATURE) - * G28 - Home one or more axes - * G29 - Detailed Z probe, probes the bed at 3 or more points. Will fail if you haven't homed yet. - * G30 - Single Z probe, probes bed at X Y location (defaults to current XY location) - * G31 - Dock sled (Z_PROBE_SLED only) - * G32 - Undock sled (Z_PROBE_SLED only) - * G33 - Delta Auto-Calibration (Requires DELTA_AUTO_CALIBRATION) - * G38 - Probe target - similar to G28 except it uses the Z_MIN_PROBE for all three axes - * G90 - Use Absolute Coordinates - * G91 - Use Relative Coordinates - * G92 - Set current position to coordinates given + * G0 -> G1 + * G1 - Coordinated Movement X Y Z E + * G2 - CW ARC + * G3 - CCW ARC + * G4 - Dwell S or P + * G5 - Cubic B-spline with XYZE destination and IJPQ offsets + * G10 - Retract filament according to settings of M207 + * G11 - Retract recover filament according to settings of M208 + * G12 - Clean tool + * G20 - Set input units to inches + * G21 - Set input units to millimeters + * G26 - Mesh Validation Pattern (Requires UBL_G26_MESH_VALIDATION) + * G27 - Park Nozzle (Requires NOZZLE_PARK_FEATURE) + * G28 - Home one or more axes + * G29 - Detailed Z probe, probes the bed at 3 or more points. Will fail if you haven't homed yet. + * G30 - Single Z probe, probes bed at X Y location (defaults to current XY location) + * G31 - Dock sled (Z_PROBE_SLED only) + * G32 - Undock sled (Z_PROBE_SLED only) + * G33 - Delta Auto-Calibration (Requires DELTA_AUTO_CALIBRATION) + * G38 - Probe target - similar to G28 except it uses the Z_MIN_PROBE for all three axes + * G42 - Coordinated move to a mesh point (Requires AUTO_BED_LEVELING_UBL) + * G90 - Use Absolute Coordinates + * G91 - Use Relative Coordinates + * G92 - Set current position to coordinates given * * "M" Codes * @@ -3396,44 +3396,6 @@ inline void gcode_G4() { #endif // BEZIER_CURVE_SUPPORT -#if ENABLED(AUTO_BED_LEVELING_UBL) //todo: enable for other leveling systems? -/** - * G7: Move X & Y axes to mesh coordinates - */ -inline void gcode_G7( - #if IS_SCARA - bool fast_move=false - #endif -) { - if (IsRunning()) { - const bool hasI = code_seen('I'); - const int8_t ix = code_has_value() ? code_value_int() : 0; - const bool hasJ = code_seen('J'); - const int8_t iy = code_has_value() ? code_value_int() : 0; - - if ((hasI && !WITHIN(ix, 0, GRID_MAX_POINTS_X - 1)) || (hasJ && !WITHIN(iy, 0, GRID_MAX_POINTS_Y - 1))) { - SERIAL_ECHOLNPGM(MSG_ERR_MESH_XY); - return; - } - - destination[X_AXIS] = hasI ? ubl.mesh_index_to_xpos(ix) : current_position[X_AXIS]; - destination[Y_AXIS] = hasJ ? ubl.mesh_index_to_ypos(iy) : current_position[Y_AXIS]; - destination[Z_AXIS] = current_position[Z_AXIS]; //todo: perhaps add Z-move support? - destination[E_AXIS] = current_position[E_AXIS]; - - if (code_seen('F') && code_value_linear_units() > 0.0) - feedrate_mm_s = MMM_TO_MMS(code_value_linear_units()); - - #if IS_SCARA - fast_move ? prepare_uninterpolated_move_to_destination() : prepare_move_to_destination(); - #else - prepare_move_to_destination(); - #endif - } -} -#endif - - #if ENABLED(FWRETRACT) /** @@ -5500,7 +5462,6 @@ void home_all_axes() { gcode_G28(true); } #endif // HAS_BED_PROBE - #if ENABLED(G38_PROBE_TARGET) static bool G38_run_probe() { @@ -5590,6 +5551,45 @@ void home_all_axes() { gcode_G28(true); } #endif // G38_PROBE_TARGET +#if ENABLED(AUTO_BED_LEVELING_UBL) + + /** + * G42: Move X & Y axes to mesh coordinates (I & J) + */ + inline void gcode_G42( + #if IS_SCARA + bool fast_move=false + #endif + ) { + if (IsRunning()) { + const bool hasI = code_seen('I'); + const int8_t ix = code_has_value() ? code_value_int() : 0; + const bool hasJ = code_seen('J'); + const int8_t iy = code_has_value() ? code_value_int() : 0; + + if ((hasI && !WITHIN(ix, 0, GRID_MAX_POINTS_X - 1)) || (hasJ && !WITHIN(iy, 0, GRID_MAX_POINTS_Y - 1))) { + SERIAL_ECHOLNPGM(MSG_ERR_MESH_XY); + return; + } + + destination[X_AXIS] = hasI ? ubl.mesh_index_to_xpos(ix) : current_position[X_AXIS]; + destination[Y_AXIS] = hasJ ? ubl.mesh_index_to_ypos(iy) : current_position[Y_AXIS]; + destination[Z_AXIS] = current_position[Z_AXIS]; //todo: perhaps add Z-move support? + destination[E_AXIS] = current_position[E_AXIS]; + + if (code_seen('F') && code_value_linear_units() > 0.0) + feedrate_mm_s = MMM_TO_MMS(code_value_linear_units()); + + #if IS_SCARA + fast_move ? prepare_uninterpolated_move_to_destination() : prepare_move_to_destination(); + #else + prepare_move_to_destination(); + #endif + } + } + +#endif // AUTO_BED_LEVELING_UBL + /** * G92: Set current position to given X Y Z E */ @@ -10061,16 +10061,6 @@ void process_next_command() { break; #endif // BEZIER_CURVE_SUPPORT - #if ENABLED(AUTO_BED_LEVELING_UBL) - case 7: - #if IS_SCARA - gcode_G7(codenum == 0); - #else - gcode_G7(); - #endif - break; - #endif - #if ENABLED(FWRETRACT) case 10: // G10: retract case 11: // G11: retract_recover @@ -10162,6 +10152,17 @@ void process_next_command() { case 92: // G92 gcode_G92(); break; + + #if ENABLED(AUTO_BED_LEVELING_UBL) + case 42: + #if IS_SCARA + gcode_G42(codenum == 0); + #else + gcode_G42(); + #endif + break; + #endif + } break; From 2881f0a48d7f86ed5531119666deb2785ce33d14 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 23 May 2017 03:53:54 -0500 Subject: [PATCH 139/189] Fix, extend G42 with P (probe) parameter - Also fix handling of SCARA and misuse of `codenum`. --- Marlin/Marlin_main.cpp | 45 ++++++++++++++++++++++++------------------ 1 file changed, 26 insertions(+), 19 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 5729e7c37..2e5d08e76 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -5551,16 +5551,12 @@ void home_all_axes() { gcode_G28(true); } #endif // G38_PROBE_TARGET -#if ENABLED(AUTO_BED_LEVELING_UBL) +#if ENABLED(AUTO_BED_LEVELING_BILINEAR) || ENABLED(AUTO_BED_LEVELING_UBL) || ENABLED(MESH_BED_LEVELING) /** * G42: Move X & Y axes to mesh coordinates (I & J) */ - inline void gcode_G42( - #if IS_SCARA - bool fast_move=false - #endif - ) { + inline void gcode_G42() { if (IsRunning()) { const bool hasI = code_seen('I'); const int8_t ix = code_has_value() ? code_value_int() : 0; @@ -5572,16 +5568,31 @@ void home_all_axes() { gcode_G28(true); } return; } - destination[X_AXIS] = hasI ? ubl.mesh_index_to_xpos(ix) : current_position[X_AXIS]; - destination[Y_AXIS] = hasJ ? ubl.mesh_index_to_ypos(iy) : current_position[Y_AXIS]; - destination[Z_AXIS] = current_position[Z_AXIS]; //todo: perhaps add Z-move support? - destination[E_AXIS] = current_position[E_AXIS]; + #if ENABLED(AUTO_BED_LEVELING_BILINEAR) + #define _GET_MESH_X(I) bilinear_start[X_AXIS] + I * bilinear_grid_spacing[X_AXIS] + #define _GET_MESH_Y(J) bilinear_start[Y_AXIS] + J * bilinear_grid_spacing[Y_AXIS] + #elif ENABLED(AUTO_BED_LEVELING_UBL) + #define _GET_MESH_X(I) ubl.mesh_index_to_xpos(I) + #define _GET_MESH_Y(J) ubl.mesh_index_to_ypos(J) + #elif ENABLED(MESH_BED_LEVELING) + #define _GET_MESH_X(I) mbl.index_to_xpos[I] + #define _GET_MESH_Y(J) mbl.index_to_ypos[J] + #endif + + set_destination_to_current(); + if (hasI) destination[X_AXIS] = LOGICAL_X_POSITION(_GET_MESH_X(ix)); + if (hasJ) destination[Y_AXIS] = LOGICAL_Y_POSITION(_GET_MESH_Y(iy)); + if (code_seen('P') && code_value_bool()) { + if (hasI) destination[X_AXIS] -= X_PROBE_OFFSET_FROM_EXTRUDER; + if (hasJ) destination[Y_AXIS] -= Y_PROBE_OFFSET_FROM_EXTRUDER; + } if (code_seen('F') && code_value_linear_units() > 0.0) feedrate_mm_s = MMM_TO_MMS(code_value_linear_units()); + // SCARA kinematic has "safe" XY raw moves #if IS_SCARA - fast_move ? prepare_uninterpolated_move_to_destination() : prepare_move_to_destination(); + prepare_uninterpolated_move_to_destination(); #else prepare_move_to_destination(); #endif @@ -6399,8 +6410,8 @@ inline void gcode_M42() { bool stow_probe_after_each = code_seen('E'); - float X_probe_location = code_seen('X') ? code_value_linear_units() : X_current + X_PROBE_OFFSET_FROM_EXTRUDER; - float Y_probe_location = code_seen('Y') ? code_value_linear_units() : Y_current + Y_PROBE_OFFSET_FROM_EXTRUDER; + const float X_probe_location = code_seen('X') ? code_value_linear_units() : X_current + X_PROBE_OFFSET_FROM_EXTRUDER, + Y_probe_location = code_seen('Y') ? code_value_linear_units() : Y_current + Y_PROBE_OFFSET_FROM_EXTRUDER; #if DISABLED(DELTA) if (!WITHIN(X_probe_location, LOGICAL_X_POSITION(MIN_PROBE_X), LOGICAL_X_POSITION(MAX_PROBE_X))) { @@ -10153,13 +10164,9 @@ void process_next_command() { gcode_G92(); break; - #if ENABLED(AUTO_BED_LEVELING_UBL) + #if ENABLED(AUTO_BED_LEVELING_BILINEAR) || ENABLED(AUTO_BED_LEVELING_UBL) || ENABLED(MESH_BED_LEVELING) case 42: - #if IS_SCARA - gcode_G42(codenum == 0); - #else - gcode_G42(); - #endif + gcode_G42(); break; #endif From ad915b667e0b6d7419527a7d13adf96d1b095d34 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 23 May 2017 13:02:50 -0500 Subject: [PATCH 140/189] One more mesh_index_to_npos update Followup to #6827 --- Marlin/ubl_motion.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/ubl_motion.cpp b/Marlin/ubl_motion.cpp index 3bd8165d1..e733d75ca 100644 --- a/Marlin/ubl_motion.cpp +++ b/Marlin/ubl_motion.cpp @@ -606,10 +606,10 @@ cell_xi = constrain(cell_xi, 0, (GRID_MAX_POINTS_X) - 1); cell_yi = constrain(cell_yi, 0, (GRID_MAX_POINTS_Y) - 1); - const float x0 = pgm_read_float(&(mesh_index_to_xpos[cell_xi ])), // 64 byte table lookup avoids mul+add - y0 = pgm_read_float(&(mesh_index_to_ypos[cell_yi ])), // 64 byte table lookup avoids mul+add - x1 = pgm_read_float(&(mesh_index_to_xpos[cell_xi+1])), // 64 byte table lookup avoids mul+add - y1 = pgm_read_float(&(mesh_index_to_ypos[cell_yi+1])); // 64 byte table lookup avoids mul+add + const float x0 = mesh_index_to_xpos(cell_xi), // 64 byte table lookup avoids mul+add + y0 = mesh_index_to_ypos(cell_yi), // 64 byte table lookup avoids mul+add + x1 = mesh_index_to_xpos(cell_xi + 1), // 64 byte table lookup avoids mul+add + y1 = mesh_index_to_ypos(cell_yi + 1); // 64 byte table lookup avoids mul+add float cx = rx - x0, // cell-relative x cy = ry - y0, // cell-relative y From 002a06c5075ad13e1c1bcfc1ce8a2868dcfdb180 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 20 May 2017 03:03:00 -0500 Subject: [PATCH 141/189] New GCode Parser - Configuration --- Marlin/Configuration_adv.h | 5 +++++ Marlin/example_configurations/Cartesio/Configuration_adv.h | 5 +++++ Marlin/example_configurations/Felix/Configuration_adv.h | 5 +++++ .../FolgerTech-i3-2020/Configuration_adv.h | 5 +++++ Marlin/example_configurations/Hephestos/Configuration_adv.h | 5 +++++ .../example_configurations/Hephestos_2/Configuration_adv.h | 5 +++++ Marlin/example_configurations/K8200/Configuration_adv.h | 5 +++++ Marlin/example_configurations/K8400/Configuration_adv.h | 5 +++++ Marlin/example_configurations/RigidBot/Configuration_adv.h | 5 +++++ Marlin/example_configurations/SCARA/Configuration_adv.h | 5 +++++ Marlin/example_configurations/TAZ4/Configuration_adv.h | 5 +++++ Marlin/example_configurations/TinyBoy2/Configuration_adv.h | 5 +++++ Marlin/example_configurations/WITBOX/Configuration_adv.h | 5 +++++ .../delta/FLSUN/auto_calibrate/Configuration_adv.h | 5 +++++ .../delta/FLSUN/kossel_mini/Configuration_adv.h | 5 +++++ .../example_configurations/delta/generic/Configuration_adv.h | 5 +++++ .../delta/kossel_mini/Configuration_adv.h | 5 +++++ .../delta/kossel_pro/Configuration_adv.h | 5 +++++ .../delta/kossel_xl/Configuration_adv.h | 5 +++++ .../gCreate_gMax1.5+/Configuration_adv.h | 5 +++++ Marlin/example_configurations/makibox/Configuration_adv.h | 5 +++++ .../example_configurations/tvrrug/Round2/Configuration_adv.h | 5 +++++ Marlin/example_configurations/wt150/Configuration_adv.h | 5 +++++ 23 files changed, 115 insertions(+) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 173113830..515e66493 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1226,4 +1226,9 @@ */ #define PROPORTIONAL_FONT_RATIO 1.0 +/** + * Spend 28 bytes of SRAM to optimize the GCode parser + */ +#define FASTER_GCODE_PARSER + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/Cartesio/Configuration_adv.h b/Marlin/example_configurations/Cartesio/Configuration_adv.h index 29f57a9d1..9e942e7cd 100644 --- a/Marlin/example_configurations/Cartesio/Configuration_adv.h +++ b/Marlin/example_configurations/Cartesio/Configuration_adv.h @@ -1219,4 +1219,9 @@ */ #define PROPORTIONAL_FONT_RATIO 1.0 +/** + * Spend 28 bytes of SRAM to optimize the GCode parser + */ +#define FASTER_GCODE_PARSER + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/Felix/Configuration_adv.h b/Marlin/example_configurations/Felix/Configuration_adv.h index 10bf0a853..f3329be78 100644 --- a/Marlin/example_configurations/Felix/Configuration_adv.h +++ b/Marlin/example_configurations/Felix/Configuration_adv.h @@ -1219,4 +1219,9 @@ */ #define PROPORTIONAL_FONT_RATIO 1.0 +/** + * Spend 28 bytes of SRAM to optimize the GCode parser + */ +#define FASTER_GCODE_PARSER + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h index dcbb34130..e2cd30cc2 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h @@ -1230,4 +1230,9 @@ */ #define PROPORTIONAL_FONT_RATIO 1.5 +/** + * Spend 28 bytes of SRAM to optimize the GCode parser + */ +#define FASTER_GCODE_PARSER + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/Hephestos/Configuration_adv.h b/Marlin/example_configurations/Hephestos/Configuration_adv.h index dc3cce298..4504ea3c9 100644 --- a/Marlin/example_configurations/Hephestos/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos/Configuration_adv.h @@ -1219,4 +1219,9 @@ */ #define PROPORTIONAL_FONT_RATIO 1.0 +/** + * Spend 28 bytes of SRAM to optimize the GCode parser + */ +#define FASTER_GCODE_PARSER + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h index 86cddce71..c8629af1a 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h @@ -1203,4 +1203,9 @@ */ #define PROPORTIONAL_FONT_RATIO 1.0 +/** + * Spend 28 bytes of SRAM to optimize the GCode parser + */ +#define FASTER_GCODE_PARSER + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/K8200/Configuration_adv.h b/Marlin/example_configurations/K8200/Configuration_adv.h index c591d39a2..821ea345d 100644 --- a/Marlin/example_configurations/K8200/Configuration_adv.h +++ b/Marlin/example_configurations/K8200/Configuration_adv.h @@ -1232,4 +1232,9 @@ */ #define PROPORTIONAL_FONT_RATIO 1.0 +/** + * Spend 28 bytes of SRAM to optimize the GCode parser + */ +#define FASTER_GCODE_PARSER + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/K8400/Configuration_adv.h b/Marlin/example_configurations/K8400/Configuration_adv.h index a9115994c..f85b55e99 100644 --- a/Marlin/example_configurations/K8400/Configuration_adv.h +++ b/Marlin/example_configurations/K8400/Configuration_adv.h @@ -1219,4 +1219,9 @@ */ #define PROPORTIONAL_FONT_RATIO 1.0 +/** + * Spend 28 bytes of SRAM to optimize the GCode parser + */ +#define FASTER_GCODE_PARSER + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/RigidBot/Configuration_adv.h b/Marlin/example_configurations/RigidBot/Configuration_adv.h index 188522253..8b278778c 100644 --- a/Marlin/example_configurations/RigidBot/Configuration_adv.h +++ b/Marlin/example_configurations/RigidBot/Configuration_adv.h @@ -1219,4 +1219,9 @@ */ #define PROPORTIONAL_FONT_RATIO 1.0 +/** + * Spend 28 bytes of SRAM to optimize the GCode parser + */ +#define FASTER_GCODE_PARSER + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/SCARA/Configuration_adv.h b/Marlin/example_configurations/SCARA/Configuration_adv.h index 8ace9a94c..e3e327588 100644 --- a/Marlin/example_configurations/SCARA/Configuration_adv.h +++ b/Marlin/example_configurations/SCARA/Configuration_adv.h @@ -1219,4 +1219,9 @@ */ #define PROPORTIONAL_FONT_RATIO 1.0 +/** + * Spend 28 bytes of SRAM to optimize the GCode parser + */ +#define FASTER_GCODE_PARSER + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/TAZ4/Configuration_adv.h b/Marlin/example_configurations/TAZ4/Configuration_adv.h index f9ed3dc76..86d5353df 100644 --- a/Marlin/example_configurations/TAZ4/Configuration_adv.h +++ b/Marlin/example_configurations/TAZ4/Configuration_adv.h @@ -1219,4 +1219,9 @@ */ #define PROPORTIONAL_FONT_RATIO 1.0 +/** + * Spend 28 bytes of SRAM to optimize the GCode parser + */ +#define FASTER_GCODE_PARSER + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h index d0aa44293..82c1f030d 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h @@ -1222,4 +1222,9 @@ */ #define PROPORTIONAL_FONT_RATIO 1.0 +/** + * Spend 28 bytes of SRAM to optimize the GCode parser + */ +#define FASTER_GCODE_PARSER + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/WITBOX/Configuration_adv.h b/Marlin/example_configurations/WITBOX/Configuration_adv.h index dc3cce298..4504ea3c9 100644 --- a/Marlin/example_configurations/WITBOX/Configuration_adv.h +++ b/Marlin/example_configurations/WITBOX/Configuration_adv.h @@ -1219,4 +1219,9 @@ */ #define PROPORTIONAL_FONT_RATIO 1.0 +/** + * Spend 28 bytes of SRAM to optimize the GCode parser + */ +#define FASTER_GCODE_PARSER + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h index 8ac6fde4b..5e5f5ca73 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h @@ -1224,4 +1224,9 @@ */ #define PROPORTIONAL_FONT_RATIO 1.0 +/** + * Spend 28 bytes of SRAM to optimize the GCode parser + */ +#define FASTER_GCODE_PARSER + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h index 9fa70a736..fa5a1de66 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h @@ -1223,4 +1223,9 @@ */ #define PROPORTIONAL_FONT_RATIO 1.0 +/** + * Spend 28 bytes of SRAM to optimize the GCode parser + */ +#define FASTER_GCODE_PARSER + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/delta/generic/Configuration_adv.h b/Marlin/example_configurations/delta/generic/Configuration_adv.h index d7fe9281c..e0d7e538d 100644 --- a/Marlin/example_configurations/delta/generic/Configuration_adv.h +++ b/Marlin/example_configurations/delta/generic/Configuration_adv.h @@ -1221,4 +1221,9 @@ */ #define PROPORTIONAL_FONT_RATIO 1.0 +/** + * Spend 28 bytes of SRAM to optimize the GCode parser + */ +#define FASTER_GCODE_PARSER + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h index d7fe9281c..e0d7e538d 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h @@ -1221,4 +1221,9 @@ */ #define PROPORTIONAL_FONT_RATIO 1.0 +/** + * Spend 28 bytes of SRAM to optimize the GCode parser + */ +#define FASTER_GCODE_PARSER + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h index b2431d7e0..d7e7c7ebc 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h @@ -1226,4 +1226,9 @@ */ #define PROPORTIONAL_FONT_RATIO 1.0 +/** + * Spend 28 bytes of SRAM to optimize the GCode parser + */ +#define FASTER_GCODE_PARSER + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h index c4341165f..33515e271 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h @@ -1221,4 +1221,9 @@ */ #define PROPORTIONAL_FONT_RATIO 1.0 +/** + * Spend 28 bytes of SRAM to optimize the GCode parser + */ +#define FASTER_GCODE_PARSER + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h index 2a7371020..65fb22c3c 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h @@ -1226,4 +1226,9 @@ */ #define PROPORTIONAL_FONT_RATIO 1.5 +/** + * Spend 28 bytes of SRAM to optimize the GCode parser + */ +#define FASTER_GCODE_PARSER + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/makibox/Configuration_adv.h b/Marlin/example_configurations/makibox/Configuration_adv.h index 50843a39a..49e41368d 100644 --- a/Marlin/example_configurations/makibox/Configuration_adv.h +++ b/Marlin/example_configurations/makibox/Configuration_adv.h @@ -1219,4 +1219,9 @@ */ #define PROPORTIONAL_FONT_RATIO 1.0 +/** + * Spend 28 bytes of SRAM to optimize the GCode parser + */ +#define FASTER_GCODE_PARSER + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h index 19c17e29f..a5441c127 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h @@ -1219,4 +1219,9 @@ */ #define PROPORTIONAL_FONT_RATIO 1.0 +/** + * Spend 28 bytes of SRAM to optimize the GCode parser + */ +#define FASTER_GCODE_PARSER + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/wt150/Configuration_adv.h b/Marlin/example_configurations/wt150/Configuration_adv.h index 9baf16688..ab2b4cb73 100644 --- a/Marlin/example_configurations/wt150/Configuration_adv.h +++ b/Marlin/example_configurations/wt150/Configuration_adv.h @@ -1222,4 +1222,9 @@ */ #define PROPORTIONAL_FONT_RATIO 1.0 +/** + * Spend 28 bytes of SRAM to optimize the GCode parser + */ +#define FASTER_GCODE_PARSER + #endif // CONFIGURATION_ADV_H From f4028fe088e43c3471fde69fdb23ce1631dc472a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 20 May 2017 03:03:08 -0500 Subject: [PATCH 142/189] New GCode Parser - Implementation --- Marlin/Conditionals_post.h | 3 + Marlin/G26_Mesh_Validation_Tool.cpp | 58 +- Marlin/M100_Free_Mem_Chk.cpp | 13 +- Marlin/Marlin.h | 18 +- Marlin/Marlin_main.cpp | 996 ++++++++++++---------------- Marlin/configuration_store.cpp | 21 +- Marlin/gcode.cpp | 279 ++++++++ Marlin/gcode.h | 285 ++++++++ Marlin/hex_print_routines.cpp | 6 +- Marlin/hex_print_routines.h | 5 +- Marlin/macros.h | 4 +- Marlin/planner.cpp | 9 +- Marlin/ubl_G29.cpp | 146 ++-- 13 files changed, 1110 insertions(+), 733 deletions(-) create mode 100644 Marlin/gcode.cpp create mode 100644 Marlin/gcode.h diff --git a/Marlin/Conditionals_post.h b/Marlin/Conditionals_post.h index c40289ea5..a4ae28ff3 100644 --- a/Marlin/Conditionals_post.h +++ b/Marlin/Conditionals_post.h @@ -838,4 +838,7 @@ // Shorthand #define GRID_MAX_POINTS ((GRID_MAX_POINTS_X) * (GRID_MAX_POINTS_Y)) + // Add commands that need sub-codes to this list + #define USE_GCODE_SUBCODES ENABLED(G38_PROBE_TARGET) + #endif // CONDITIONALS_POST_H diff --git a/Marlin/G26_Mesh_Validation_Tool.cpp b/Marlin/G26_Mesh_Validation_Tool.cpp index 0bae98391..a17adda10 100644 --- a/Marlin/G26_Mesh_Validation_Tool.cpp +++ b/Marlin/G26_Mesh_Validation_Tool.cpp @@ -34,6 +34,7 @@ #include "stepper.h" #include "temperature.h" #include "ultralcd.h" + #include "gcode.h" #define EXTRUSION_MULTIPLIER 1.0 #define RETRACTION_MULTIPLIER 1.0 @@ -130,11 +131,7 @@ void set_destination_to_current(); void set_current_to_destination(); void prepare_move_to_destination(); - float code_value_float(); - float code_value_linear_units(); - float code_value_axis_units(const AxisEnum axis); - bool code_value_bool(); - bool code_has_value(); + void lcd_setstatuspgm(const char* const message, const uint8_t level); void sync_plan_position_e(); void chirp_at_user(); @@ -625,29 +622,29 @@ g26_hotend_temp = HOTEND_TEMP; g26_prime_flag = 0; - g26_ooze_amount = code_seen('O') && code_has_value() ? code_value_linear_units() : OOZE_AMOUNT; - g26_keep_heaters_on = code_seen('K') && code_value_bool(); - g26_continue_with_closest = code_seen('C') && code_value_bool(); + g26_ooze_amount = parser.seen('O') && parser.has_value() ? parser.value_linear_units() : OOZE_AMOUNT; + g26_keep_heaters_on = parser.seen('K') && parser.value_bool(); + g26_continue_with_closest = parser.seen('C') && parser.value_bool(); - if (code_seen('B')) { - g26_bed_temp = code_value_temp_abs(); + if (parser.seen('B')) { + g26_bed_temp = parser.value_celsius(); if (!WITHIN(g26_bed_temp, 15, 140)) { SERIAL_PROTOCOLLNPGM("?Specified bed temperature not plausible."); return UBL_ERR; } } - if (code_seen('L')) { - g26_layer_height = code_value_linear_units(); + if (parser.seen('L')) { + g26_layer_height = parser.value_linear_units(); if (!WITHIN(g26_layer_height, 0.0, 2.0)) { SERIAL_PROTOCOLLNPGM("?Specified layer height not plausible."); return UBL_ERR; } } - if (code_seen('Q')) { - if (code_has_value()) { - g26_retraction_multiplier = code_value_float(); + if (parser.seen('Q')) { + if (parser.has_value()) { + g26_retraction_multiplier = parser.value_float(); if (!WITHIN(g26_retraction_multiplier, 0.05, 15.0)) { SERIAL_PROTOCOLLNPGM("?Specified Retraction Multiplier not plausible."); return UBL_ERR; @@ -659,20 +656,20 @@ } } - if (code_seen('S')) { - g26_nozzle = code_value_float(); + if (parser.seen('S')) { + g26_nozzle = parser.value_float(); if (!WITHIN(g26_nozzle, 0.1, 1.0)) { SERIAL_PROTOCOLLNPGM("?Specified nozzle size not plausible."); return UBL_ERR; } } - if (code_seen('P')) { - if (!code_has_value()) + if (parser.seen('P')) { + if (!parser.has_value()) g26_prime_flag = -1; else { g26_prime_flag++; - g26_prime_length = code_value_linear_units(); + g26_prime_length = parser.value_linear_units(); if (!WITHIN(g26_prime_length, 0.0, 25.0)) { SERIAL_PROTOCOLLNPGM("?Specified prime length not plausible."); return UBL_ERR; @@ -680,8 +677,8 @@ } } - if (code_seen('F')) { - g26_filament_diameter = code_value_linear_units(); + if (parser.seen('F')) { + g26_filament_diameter = parser.value_linear_units(); if (!WITHIN(g26_filament_diameter, 1.0, 4.0)) { SERIAL_PROTOCOLLNPGM("?Specified filament size not plausible."); return UBL_ERR; @@ -693,27 +690,28 @@ g26_extrusion_multiplier *= g26_filament_diameter * sq(g26_nozzle) / sq(0.3); // Scale up by nozzle size - if (code_seen('H')) { - g26_hotend_temp = code_value_temp_abs(); + if (parser.seen('H')) { + g26_hotend_temp = parser.value_celsius(); if (!WITHIN(g26_hotend_temp, 165, 280)) { SERIAL_PROTOCOLLNPGM("?Specified nozzle temperature not plausible."); return UBL_ERR; } } - if (code_seen('U')) { + if (parser.seen('U')) { randomSeed(millis()); - random_deviation = code_has_value() ? code_value_float() : 50.0; + // This setting will persist for the next G26 + random_deviation = parser.has_value() ? parser.value_float() : 50.0; } - g26_repeats = code_seen('R') ? (code_has_value() ? code_value_int() : GRID_MAX_POINTS+1) : GRID_MAX_POINTS+1; + g26_repeats = parser.seen('R') ? (parser.has_value() ? parser.value_int() : GRID_MAX_POINTS + 1) : GRID_MAX_POINTS + 1; if (g26_repeats < 1) { SERIAL_PROTOCOLLNPGM("?(R)epeat value not plausible; must be at least 1."); return UBL_ERR; } - g26_x_pos = code_seen('X') ? code_value_linear_units() : current_position[X_AXIS]; - g26_y_pos = code_seen('Y') ? code_value_linear_units() : current_position[Y_AXIS]; + g26_x_pos = parser.seen('X') ? parser.value_linear_units() : current_position[X_AXIS]; + g26_y_pos = parser.seen('Y') ? parser.value_linear_units() : current_position[Y_AXIS]; if (!position_is_reachable_xy(g26_x_pos, g26_y_pos)) { SERIAL_PROTOCOLLNPGM("?Specified X,Y coordinate out of bounds."); return UBL_ERR; @@ -722,7 +720,7 @@ /** * Wait until all parameters are verified before altering the state! */ - state.active = !code_seen('D'); + state.active = !parser.seen('D'); return UBL_OK; } diff --git a/Marlin/M100_Free_Mem_Chk.cpp b/Marlin/M100_Free_Mem_Chk.cpp index 6b5edebff..cfc001de2 100644 --- a/Marlin/M100_Free_Mem_Chk.cpp +++ b/Marlin/M100_Free_Mem_Chk.cpp @@ -61,6 +61,7 @@ extern size_t __heap_start, __heap_end, __flp; extern char __bss_end; #include "Marlin.h" +#include "gcode.h" #include "hex_print_routines.h" // @@ -188,7 +189,7 @@ void free_memory_pool_report(char * const ptr, const int16_t size) { * This is useful to check the correctness of the M100 D and the M100 F commands. */ void corrupt_free_memory(char *ptr, const uint16_t size) { - if (code_seen('C')) { + if (parser.seen('C')) { ptr += 8; const uint16_t near_top = top_of_stack() - ptr - 250, // -250 to avoid interrupt activity that's altered the stack. j = near_top / (size + 1); @@ -247,23 +248,23 @@ void gcode_M100() { // Always init on the first invocation of M100 static bool m100_not_initialized = true; - if (m100_not_initialized || code_seen('I')) { + if (m100_not_initialized || parser.seen('I')) { m100_not_initialized = false; init_free_memory(ptr, sp - ptr); } #if ENABLED(M100_FREE_MEMORY_DUMPER) - if (code_seen('D')) + if (parser.seen('D')) return dump_free_memory(ptr, sp); #endif - if (code_seen('F')) + if (parser.seen('F')) return free_memory_pool_report(ptr, sp - ptr); #if ENABLED(M100_FREE_MEMORY_CORRUPTOR) - if (code_seen('C')) - return corrupt_free_memory(ptr, code_value_int()); + if (parser.seen('C')) + return corrupt_free_memory(ptr, parser.value_int()); #endif } diff --git a/Marlin/Marlin.h b/Marlin/Marlin.h index 37f539320..aecd89b32 100644 --- a/Marlin/Marlin.h +++ b/Marlin/Marlin.h @@ -287,22 +287,6 @@ extern float soft_endstop_min[XYZ], soft_endstop_max[XYZ]; void update_software_endstops(const AxisEnum axis); #endif -// GCode support for external objects -bool code_seen(char); -int code_value_int(); -int16_t code_value_temp_abs(); -int16_t code_value_temp_diff(); - -#if ENABLED(INCH_MODE_SUPPORT) - float code_value_linear_units(); - float code_value_axis_units(const AxisEnum axis); - float code_value_per_axis_unit(const AxisEnum axis); -#else - #define code_value_linear_units() code_value_float() - #define code_value_axis_units(A) code_value_float() - #define code_value_per_axis_unit(A) code_value_float() -#endif - #if IS_KINEMATIC extern float delta[ABC]; void inverse_kinematics(const float logical[XYZ]); @@ -490,4 +474,4 @@ FORCE_INLINE bool position_is_reachable_xy(const float &lx, const float &ly) { return position_is_reachable_raw_xy(RAW_X_POSITION(lx), RAW_Y_POSITION(ly)); } -#endif //MARLIN_H +#endif // MARLIN_H diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 2e5d08e76..6547cc152 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -242,6 +242,7 @@ #include "nozzle.h" #include "duration_t.h" #include "types.h" +#include "gcode.h" #if HAS_ABL #include "vector_3.h" @@ -373,14 +374,6 @@ static uint8_t cmd_queue_index_r = 0, // Ring buffer read position static char command_queue[BUFSIZE][MAX_CMD_SIZE]; #endif -/** - * Current GCode Command - * When a GCode handler is running, these will be set - */ -static char *current_command, // The command currently being executed - *current_command_args, // The address where arguments begin - *seen_pointer; // Set by code_seen(), used by the code_value functions - /** * Next Injected Command pointer. NULL if no commands are being injected. * Used by Marlin internally to ensure that commands initiated from within @@ -388,10 +381,6 @@ static char *current_command, // The command currently being executed */ static const char *injected_commands_P = NULL; -#if ENABLED(INCH_MODE_SUPPORT) - float linear_unit_factor = 1.0, volumetric_unit_factor = 1.0; -#endif - #if ENABLED(TEMPERATURE_UNITS_SUPPORT) TempUnit input_temp_units = TEMPUNIT_C; #endif @@ -408,7 +397,8 @@ float constexpr homing_feedrate_mm_s[] = { #endif MMM_TO_MMS(HOMING_FEEDRATE_Z), 0 }; -float feedrate_mm_s = MMM_TO_MMS(1500.0), saved_feedrate_mm_s; +float feedrate_mm_s = MMM_TO_MMS(1500.0); +static float saved_feedrate_mm_s; int feedrate_percentage = 100, saved_feedrate_percentage, flow_percentage[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(100); @@ -1056,8 +1046,8 @@ inline void get_serial_commands() { char* command = serial_line_buffer; while (*command == ' ') command++; // skip any leading spaces - char* npos = (*command == 'N') ? command : NULL; // Require the N parameter to start the line - char* apos = strchr(command, '*'); + char *npos = (*command == 'N') ? command : NULL, // Require the N parameter to start the line + *apos = strchr(command, '*'); if (npos) { @@ -1249,125 +1239,21 @@ void get_available_commands() { #endif } -inline bool code_has_value() { - int i = 1; - char c = seen_pointer[i]; - while (c == ' ') c = seen_pointer[++i]; - if (c == '-' || c == '+') c = seen_pointer[++i]; - if (c == '.') c = seen_pointer[++i]; - return NUMERIC(c); -} - -inline float code_value_float() { - char* e = strchr(seen_pointer, 'E'); - if (!e) return strtod(seen_pointer + 1, NULL); - *e = 0; - float ret = strtod(seen_pointer + 1, NULL); - *e = 'E'; - return ret; -} - -inline unsigned long code_value_ulong() { return strtoul(seen_pointer + 1, NULL, 10); } - -inline long code_value_long() { return strtol(seen_pointer + 1, NULL, 10); } - -inline int code_value_int() { return (int)strtol(seen_pointer + 1, NULL, 10); } - -inline uint16_t code_value_ushort() { return (uint16_t)strtoul(seen_pointer + 1, NULL, 10); } - -inline uint8_t code_value_byte() { return (uint8_t)(constrain(strtol(seen_pointer + 1, NULL, 10), 0, 255)); } - -inline bool code_value_bool() { return !code_has_value() || code_value_byte() > 0; } - -#if ENABLED(INCH_MODE_SUPPORT) - inline void set_input_linear_units(LinearUnit units) { - switch (units) { - case LINEARUNIT_INCH: - linear_unit_factor = 25.4; - break; - case LINEARUNIT_MM: - default: - linear_unit_factor = 1.0; - break; - } - volumetric_unit_factor = pow(linear_unit_factor, 3.0); - } - - inline float axis_unit_factor(const AxisEnum axis) { - return (axis >= E_AXIS && volumetric_enabled ? volumetric_unit_factor : linear_unit_factor); - } - - inline float code_value_linear_units() { return code_value_float() * linear_unit_factor; } - inline float code_value_axis_units(const AxisEnum axis) { return code_value_float() * axis_unit_factor(axis); } - inline float code_value_per_axis_unit(const AxisEnum axis) { return code_value_float() / axis_unit_factor(axis); } -#endif - -#if ENABLED(TEMPERATURE_UNITS_SUPPORT) - inline void set_input_temp_units(TempUnit units) { input_temp_units = units; } - - float to_temp_units(const float &c) { - switch (input_temp_units) { - case TEMPUNIT_F: - return c * 0.5555555556 + 32.0; - case TEMPUNIT_K: - return c + 273.15; - case TEMPUNIT_C: - default: - return c; - } - } - - int16_t code_value_temp_abs() { - const float c = code_value_float(); - switch (input_temp_units) { - case TEMPUNIT_F: - return (int16_t)((c - 32.0) * 0.5555555556); - case TEMPUNIT_K: - return (int16_t)(c - 273.15); - case TEMPUNIT_C: - default: - return (int16_t)(c); - } - } - - int16_t code_value_temp_diff() { - switch (input_temp_units) { - case TEMPUNIT_F: - return code_value_float() * 0.5555555556; - case TEMPUNIT_C: - case TEMPUNIT_K: - default: - return code_value_float(); - } - } -#else - int16_t code_value_temp_abs() { return code_value_int(); } - int16_t code_value_temp_diff() { return code_value_int(); } -#endif - -FORCE_INLINE millis_t code_value_millis() { return code_value_ulong(); } -inline millis_t code_value_millis_from_seconds() { return code_value_float() * 1000; } - -bool code_seen(char code) { - seen_pointer = strchr(current_command_args, code); - return (seen_pointer != NULL); // Return TRUE if the code-letter was found -} - /** * Set target_extruder from the T parameter or the active_extruder * * Returns TRUE if the target is invalid */ bool get_target_extruder_from_command(int code) { - if (code_seen('T')) { - if (code_value_byte() >= EXTRUDERS) { + if (parser.seen('T')) { + if (parser.value_byte() >= EXTRUDERS) { SERIAL_ECHO_START; SERIAL_CHAR('M'); SERIAL_ECHO(code); - SERIAL_ECHOLNPAIR(" " MSG_INVALID_EXTRUDER " ", code_value_byte()); + SERIAL_ECHOLNPAIR(" " MSG_INVALID_EXTRUDER " ", parser.value_byte()); return true; } - target_extruder = code_value_byte(); + target_extruder = parser.value_byte(); } else target_extruder = active_extruder; @@ -3141,9 +3027,9 @@ static void homeaxis(const AxisEnum axis) { const char* mixing_codes = "ABCDHI"; byte mix_bits = 0; for (uint8_t i = 0; i < MIXING_STEPPERS; i++) { - if (code_seen(mixing_codes[i])) { + if (parser.seen(mixing_codes[i])) { SBI(mix_bits, i); - float v = code_value_float(); + float v = parser.value_float(); NOLESS(v, 0.0); mixing_factor[i] = RECIPROCAL(v); } @@ -3175,14 +3061,14 @@ static void homeaxis(const AxisEnum axis) { */ void gcode_get_destination() { LOOP_XYZE(i) { - if (code_seen(axis_codes[i])) - destination[i] = code_value_axis_units((AxisEnum)i) + (axis_relative_modes[i] || relative_mode ? current_position[i] : 0); + if (parser.seen(axis_codes[i])) + destination[i] = parser.value_axis_units((AxisEnum)i) + (axis_relative_modes[i] || relative_mode ? current_position[i] : 0); else destination[i] = current_position[i]; } - if (code_seen('F') && code_value_linear_units() > 0.0) - feedrate_mm_s = MMM_TO_MMS(code_value_linear_units()); + if (parser.seen('F') && parser.value_linear_units() > 0.0) + feedrate_mm_s = MMM_TO_MMS(parser.value_feedrate()); #if ENABLED(PRINTCOUNTER) if (!DEBUGGING(DRYRUN)) @@ -3195,13 +3081,6 @@ void gcode_get_destination() { #endif } -void unknown_command_error() { - SERIAL_ECHO_START; - SERIAL_ECHOPAIR(MSG_UNKNOWN_COMMAND, current_command); - SERIAL_CHAR('"'); - SERIAL_EOL; -} - #if ENABLED(HOST_KEEPALIVE_FEATURE) /** @@ -3253,7 +3132,7 @@ inline void gcode_G0_G1( #if ENABLED(FWRETRACT) - if (autoretract_enabled && !(code_seen('X') || code_seen('Y') || code_seen('Z')) && code_seen('E')) { + if (autoretract_enabled && !(parser.seen('X') || parser.seen('Y') || parser.seen('Z')) && parser.seen('E')) { const float echange = destination[E_AXIS] - current_position[E_AXIS]; // Is this move an attempt to retract or recover? if ((echange < -MIN_RETRACT && !retracted[active_extruder]) || (echange > MIN_RETRACT && retracted[active_extruder])) { @@ -3264,7 +3143,7 @@ inline void gcode_G0_G1( } } - #endif //FWRETRACT + #endif // FWRETRACT #if IS_SCARA fast_move ? prepare_uninterpolated_move_to_destination() : prepare_move_to_destination(); @@ -3313,8 +3192,8 @@ inline void gcode_G0_G1( #endif float arc_offset[2] = { 0.0, 0.0 }; - if (code_seen('R')) { - const float r = code_value_linear_units(), + if (parser.seen('R')) { + const float r = parser.value_linear_units(), x1 = current_position[X_AXIS], y1 = current_position[Y_AXIS], x2 = destination[X_AXIS], y2 = destination[Y_AXIS]; if (r && (x2 != x1 || y2 != y1)) { @@ -3330,8 +3209,8 @@ inline void gcode_G0_G1( } } else { - if (code_seen('I')) arc_offset[X_AXIS] = code_value_linear_units(); - if (code_seen('J')) arc_offset[Y_AXIS] = code_value_linear_units(); + if (parser.seen('I')) arc_offset[X_AXIS] = parser.value_linear_units(); + if (parser.seen('J')) arc_offset[Y_AXIS] = parser.value_linear_units(); } if (arc_offset[0] || arc_offset[1]) { @@ -3354,8 +3233,8 @@ inline void gcode_G0_G1( inline void gcode_G4() { millis_t dwell_ms = 0; - if (code_seen('P')) dwell_ms = code_value_millis(); // milliseconds to wait - if (code_seen('S')) dwell_ms = code_value_millis_from_seconds(); // seconds to wait + if (parser.seen('P')) dwell_ms = parser.value_millis(); // milliseconds to wait + if (parser.seen('S')) dwell_ms = parser.value_millis_from_seconds(); // seconds to wait stepper.synchronize(); refresh_cmd_timeout(); @@ -3384,10 +3263,10 @@ inline void gcode_G4() { gcode_get_destination(); const float offset[] = { - code_seen('I') ? code_value_linear_units() : 0.0, - code_seen('J') ? code_value_linear_units() : 0.0, - code_seen('P') ? code_value_linear_units() : 0.0, - code_seen('Q') ? code_value_linear_units() : 0.0 + parser.seen('I') ? parser.value_linear_units() : 0.0, + parser.seen('J') ? parser.value_linear_units() : 0.0, + parser.seen('P') ? parser.value_linear_units() : 0.0, + parser.seen('Q') ? parser.value_linear_units() : 0.0 }; plan_cubic_move(offset); @@ -3405,7 +3284,7 @@ inline void gcode_G4() { inline void gcode_G10_G11(bool doRetract=false) { #if EXTRUDERS > 1 if (doRetract) { - retracted_swap[active_extruder] = (code_seen('S') && code_value_bool()); // checks for swap retract argument + retracted_swap[active_extruder] = (parser.seen('S') && parser.value_bool()); // checks for swap retract argument } #endif retract(doRetract @@ -3425,10 +3304,10 @@ inline void gcode_G4() { // Don't allow nozzle cleaning without homing first if (axis_unhomed_error()) return; - const uint8_t pattern = code_seen('P') ? code_value_ushort() : 0, - strokes = code_seen('S') ? code_value_ushort() : NOZZLE_CLEAN_STROKES, - objects = code_seen('T') ? code_value_ushort() : NOZZLE_CLEAN_TRIANGLES; - const float radius = code_seen('R') ? code_value_float() : NOZZLE_CLEAN_CIRCLE_RADIUS; + const uint8_t pattern = parser.seen('P') ? parser.value_ushort() : 0, + strokes = parser.seen('S') ? parser.value_ushort() : NOZZLE_CLEAN_STROKES, + objects = parser.seen('T') ? parser.value_ushort() : NOZZLE_CLEAN_TRIANGLES; + const float radius = parser.seen('R') ? parser.value_float() : NOZZLE_CLEAN_CIRCLE_RADIUS; Nozzle::clean(pattern, strokes, radius, objects); } @@ -3438,12 +3317,12 @@ inline void gcode_G4() { /** * G20: Set input mode to inches */ - inline void gcode_G20() { set_input_linear_units(LINEARUNIT_INCH); } + inline void gcode_G20() { parser.set_input_linear_units(LINEARUNIT_INCH); } /** * G21: Set input mode to millimeters */ - inline void gcode_G21() { set_input_linear_units(LINEARUNIT_MM); } + inline void gcode_G21() { parser.set_input_linear_units(LINEARUNIT_MM); } #endif #if ENABLED(NOZZLE_PARK_FEATURE) @@ -3453,7 +3332,7 @@ inline void gcode_G4() { inline void gcode_G27() { // Don't allow nozzle parking without homing first if (axis_unhomed_error()) return; - Nozzle::park(code_seen('P') ? code_value_ushort() : 0); + Nozzle::park(parser.seen('P') ? parser.value_ushort() : 0); } #endif // NOZZLE_PARK_FEATURE @@ -3770,9 +3649,9 @@ inline void gcode_G28(const bool always_home_all) { #else // NOT DELTA - const bool homeX = always_home_all || code_seen('X'), - homeY = always_home_all || code_seen('Y'), - homeZ = always_home_all || code_seen('Z'), + const bool homeX = always_home_all || parser.seen('X'), + homeY = always_home_all || parser.seen('Y'), + homeZ = always_home_all || parser.seen('Z'), home_all = (!homeX && !homeY && !homeZ) || (homeX && homeY && homeZ); set_destination_to_current(); @@ -4001,7 +3880,7 @@ void home_all_axes() { gcode_G28(true); } static bool enable_soft_endstops; #endif - const MeshLevelingState state = code_seen('S') ? (MeshLevelingState)code_value_byte() : MeshReport; + const MeshLevelingState state = parser.seen('S') ? (MeshLevelingState)parser.value_byte() : MeshReport; if (!WITHIN(state, 0, 5)) { SERIAL_PROTOCOLLNPGM("S out of range (0-5)."); return; @@ -4073,8 +3952,8 @@ void home_all_axes() { gcode_G28(true); } break; case MeshSet: - if (code_seen('X')) { - px = code_value_int() - 1; + if (parser.seen('X')) { + px = parser.value_int() - 1; if (!WITHIN(px, 0, GRID_MAX_POINTS_X - 1)) { SERIAL_PROTOCOLLNPGM("X out of range (1-" STRINGIFY(GRID_MAX_POINTS_X) ")."); return; @@ -4085,8 +3964,8 @@ void home_all_axes() { gcode_G28(true); } return; } - if (code_seen('Y')) { - py = code_value_int() - 1; + if (parser.seen('Y')) { + py = parser.value_int() - 1; if (!WITHIN(py, 0, GRID_MAX_POINTS_Y - 1)) { SERIAL_PROTOCOLLNPGM("Y out of range (1-" STRINGIFY(GRID_MAX_POINTS_Y) ")."); return; @@ -4097,8 +3976,8 @@ void home_all_axes() { gcode_G28(true); } return; } - if (code_seen('Z')) { - mbl.z_values[px][py] = code_value_linear_units(); + if (parser.seen('Z')) { + mbl.z_values[px][py] = parser.value_linear_units(); } else { SERIAL_CHAR('Z'); echo_not_entered(); @@ -4107,8 +3986,8 @@ void home_all_axes() { gcode_G28(true); } break; case MeshSetZOffset: - if (code_seen('Z')) { - mbl.z_offset = code_value_linear_units(); + if (parser.seen('Z')) { + mbl.z_offset = parser.value_linear_units(); } else { SERIAL_CHAR('Z'); echo_not_entered(); @@ -4213,7 +4092,7 @@ void home_all_axes() { gcode_G28(true); } // G29 Q is also available if debugging #if ENABLED(DEBUG_LEVELING_FEATURE) - const bool query = code_seen('Q'); + const bool query = parser.seen('Q'); const uint8_t old_debug_flags = marlin_debug_flags; if (query) marlin_debug_flags |= DEBUG_LEVELING; if (DEBUGGING(LEVELING)) { @@ -4227,7 +4106,7 @@ void home_all_axes() { gcode_G28(true); } #endif #if ENABLED(DEBUG_LEVELING_FEATURE) && DISABLED(PROBE_MANUALLY) - const bool faux = code_seen('C') && code_value_bool(); + const bool faux = parser.seen('C') && parser.value_bool(); #else bool constexpr faux = false; #endif @@ -4318,24 +4197,24 @@ void home_all_axes() { gcode_G28(true); } #if ENABLED(AUTO_BED_LEVELING_BILINEAR) - if (code_seen('W')) { + if (parser.seen('W')) { if (!bilinear_grid_spacing[X_AXIS]) { SERIAL_ERROR_START; SERIAL_ERRORLNPGM("No bilinear grid"); return; } - const float z = code_seen('Z') && code_has_value() ? code_value_float() : 99999; + const float z = parser.seen('Z') && parser.has_value() ? parser.value_float() : 99999; if (!WITHIN(z, -10, 10)) { SERIAL_ERROR_START; SERIAL_ERRORLNPGM("Bad Z value"); return; } - const float x = code_seen('X') && code_has_value() ? code_value_float() : 99999, - y = code_seen('Y') && code_has_value() ? code_value_float() : 99999; - int8_t i = code_seen('I') && code_has_value() ? code_value_byte() : -1, - j = code_seen('J') && code_has_value() ? code_value_byte() : -1; + const float x = parser.seen('X') && parser.has_value() ? parser.value_float() : 99999, + y = parser.seen('Y') && parser.has_value() ? parser.value_float() : 99999; + int8_t i = parser.seen('I') && parser.has_value() ? parser.value_byte() : -1, + j = parser.seen('J') && parser.has_value() ? parser.value_byte() : -1; if (x < 99998 && y < 99998) { // Get nearest i / j from x / y @@ -4353,37 +4232,37 @@ void home_all_axes() { gcode_G28(true); } set_bed_leveling_enabled(abl_should_enable); } return; - } // code_seen('W') + } // parser.seen('W') #endif #if HAS_LEVELING // Jettison bed leveling data - if (code_seen('J')) { + if (parser.seen('J')) { reset_bed_level(); return; } #endif - verbose_level = code_seen('V') && code_has_value() ? code_value_int() : 0; + verbose_level = parser.seen('V') && parser.has_value() ? parser.value_int() : 0; if (!WITHIN(verbose_level, 0, 4)) { SERIAL_PROTOCOLLNPGM("?(V)erbose level is implausible (0-4)."); return; } - dryrun = code_seen('D') && code_value_bool(); + dryrun = parser.seen('D') && parser.value_bool(); #if ENABLED(AUTO_BED_LEVELING_LINEAR) - do_topography_map = verbose_level > 2 || code_seen('T'); + do_topography_map = verbose_level > 2 || parser.seen('T'); // X and Y specify points in each direction, overriding the default // These values may be saved with the completed mesh - abl_grid_points_x = code_seen('X') ? code_value_int() : GRID_MAX_POINTS_X; - abl_grid_points_y = code_seen('Y') ? code_value_int() : GRID_MAX_POINTS_Y; - if (code_seen('P')) abl_grid_points_x = abl_grid_points_y = code_value_int(); + abl_grid_points_x = parser.seen('X') ? parser.value_int() : GRID_MAX_POINTS_X; + abl_grid_points_y = parser.seen('Y') ? parser.value_int() : GRID_MAX_POINTS_Y; + if (parser.seen('P')) abl_grid_points_x = abl_grid_points_y = parser.value_int(); if (abl_grid_points_x < 2 || abl_grid_points_y < 2) { SERIAL_PROTOCOLLNPGM("?Number of probe points is implausible (2 minimum)."); @@ -4394,18 +4273,18 @@ void home_all_axes() { gcode_G28(true); } #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) - zoffset = code_seen('Z') ? code_value_linear_units() : 0; + zoffset = parser.seen('Z') ? parser.value_linear_units() : 0; #endif #if ABL_GRID - xy_probe_feedrate_mm_s = MMM_TO_MMS(code_seen('S') ? code_value_linear_units() : XY_PROBE_SPEED); + xy_probe_feedrate_mm_s = MMM_TO_MMS(parser.seen('S') ? parser.value_linear_units() : XY_PROBE_SPEED); - left_probe_bed_position = code_seen('L') ? (int)code_value_linear_units() : LOGICAL_X_POSITION(LEFT_PROBE_BED_POSITION); - right_probe_bed_position = code_seen('R') ? (int)code_value_linear_units() : LOGICAL_X_POSITION(RIGHT_PROBE_BED_POSITION); - front_probe_bed_position = code_seen('F') ? (int)code_value_linear_units() : LOGICAL_Y_POSITION(FRONT_PROBE_BED_POSITION); - back_probe_bed_position = code_seen('B') ? (int)code_value_linear_units() : LOGICAL_Y_POSITION(BACK_PROBE_BED_POSITION); + left_probe_bed_position = parser.seen('L') ? (int)parser.value_linear_units() : LOGICAL_X_POSITION(LEFT_PROBE_BED_POSITION); + right_probe_bed_position = parser.seen('R') ? (int)parser.value_linear_units() : LOGICAL_X_POSITION(RIGHT_PROBE_BED_POSITION); + front_probe_bed_position = parser.seen('F') ? (int)parser.value_linear_units() : LOGICAL_Y_POSITION(FRONT_PROBE_BED_POSITION); + back_probe_bed_position = parser.seen('B') ? (int)parser.value_linear_units() : LOGICAL_Y_POSITION(BACK_PROBE_BED_POSITION); const bool left_out_l = left_probe_bed_position < LOGICAL_X_POSITION(MIN_PROBE_X), left_out = left_out_l || left_probe_bed_position > right_probe_bed_position - (MIN_PROBE_EDGE), @@ -4519,7 +4398,7 @@ void home_all_axes() { gcode_G28(true); } #if ENABLED(PROBE_MANUALLY) // Abort current G29 procedure, go back to ABLStart - if (code_seen('A') && g29_in_progress) { + if (parser.seen('A') && g29_in_progress) { SERIAL_PROTOCOLLNPGM("Manual G29 aborted"); #if HAS_SOFTWARE_ENDSTOPS soft_endstops_enabled = enable_soft_endstops; @@ -4529,7 +4408,7 @@ void home_all_axes() { gcode_G28(true); } } // Query G29 status - if (code_seen('Q')) { + if (parser.seen('Q')) { if (!g29_in_progress) SERIAL_PROTOCOLLNPGM("Manual G29 idle"); else { @@ -4538,7 +4417,7 @@ void home_all_axes() { gcode_G28(true); } } } - if (code_seen('A') || code_seen('Q')) return; + if (parser.seen('A') || parser.seen('Q')) return; // Fall through to probe the first point g29_in_progress = true; @@ -4674,7 +4553,7 @@ void home_all_axes() { gcode_G28(true); } #else // !PROBE_MANUALLY - bool stow_probe_after_each = code_seen('E'); + const bool stow_probe_after_each = parser.seen('E'); #if ABL_GRID @@ -5015,8 +4894,8 @@ void home_all_axes() { gcode_G28(true); } * S0 Leave the probe deployed */ inline void gcode_G30() { - const float xpos = code_seen('X') ? code_value_linear_units() : current_position[X_AXIS] + X_PROBE_OFFSET_FROM_EXTRUDER, - ypos = code_seen('Y') ? code_value_linear_units() : current_position[Y_AXIS] + Y_PROBE_OFFSET_FROM_EXTRUDER; + const float xpos = parser.seen('X') ? parser.value_linear_units() : current_position[X_AXIS] + X_PROBE_OFFSET_FROM_EXTRUDER, + ypos = parser.seen('Y') ? parser.value_linear_units() : current_position[Y_AXIS] + Y_PROBE_OFFSET_FROM_EXTRUDER; if (!position_is_reachable_by_probe_xy(xpos, ypos)) return; @@ -5027,7 +4906,7 @@ void home_all_axes() { gcode_G28(true); } setup_for_endstop_or_probe_move(); - const float measured_z = probe_pt(xpos, ypos, !code_seen('S') || code_value_bool(), 1); + const float measured_z = probe_pt(xpos, ypos, !parser.seen('S') || parser.value_bool(), 1); if (!isnan(measured_z)) { SERIAL_PROTOCOLPAIR("Bed X: ", FIXFLOAT(xpos)); @@ -5080,25 +4959,25 @@ void home_all_axes() { gcode_G28(true); } */ inline void gcode_G33() { - const int8_t probe_points = code_seen('P') ? code_value_int() : DELTA_CALIBRATION_DEFAULT_POINTS; + const int8_t probe_points = parser.seen('P') ? parser.value_int() : DELTA_CALIBRATION_DEFAULT_POINTS; if (!WITHIN(probe_points, 1, 7)) { SERIAL_PROTOCOLLNPGM("?(P)oints is implausible (1 to 7)."); return; } - const int8_t verbose_level = code_seen('V') ? code_value_byte() : 1; + const int8_t verbose_level = parser.seen('V') ? parser.value_byte() : 1; if (!WITHIN(verbose_level, 0, 2)) { SERIAL_PROTOCOLLNPGM("?(V)erbose level is implausible (0-2)."); return; } - const float calibration_precision = code_seen('C') ? code_value_float() : 0.0; + const float calibration_precision = parser.seen('C') ? parser.value_float() : 0.0; if (calibration_precision < 0) { SERIAL_PROTOCOLLNPGM("?(C)alibration precision is implausible (>0)."); return; } - const bool towers_set = !code_seen('T'), + const bool towers_set = !parser.seen('T'), _1p_calibration = probe_points == 1, _4p_calibration = probe_points == 2, _4p_towers_points = _4p_calibration && towers_set, @@ -5537,7 +5416,7 @@ void home_all_axes() { gcode_G28(true); } // If any axis has enough movement, do the move LOOP_XYZ(i) if (fabs(destination[i] - current_position[i]) >= G38_MINIMUM_MOVE) { - if (!code_seen('F')) feedrate_mm_s = homing_feedrate_mm_s[i]; + if (!parser.seen('F')) feedrate_mm_s = homing_feedrate_mm_s[i]; // If G38.2 fails throw an error if (!G38_run_probe() && is_38_2) { SERIAL_ERROR_START; @@ -5558,10 +5437,10 @@ void home_all_axes() { gcode_G28(true); } */ inline void gcode_G42() { if (IsRunning()) { - const bool hasI = code_seen('I'); - const int8_t ix = code_has_value() ? code_value_int() : 0; - const bool hasJ = code_seen('J'); - const int8_t iy = code_has_value() ? code_value_int() : 0; + const bool hasI = parser.seen('I'); + const int8_t ix = parser.has_value() ? parser.value_int() : 0; + const bool hasJ = parser.seen('J'); + const int8_t iy = parser.has_value() ? parser.value_int() : 0; if ((hasI && !WITHIN(ix, 0, GRID_MAX_POINTS_X - 1)) || (hasJ && !WITHIN(iy, 0, GRID_MAX_POINTS_Y - 1))) { SERIAL_ECHOLNPGM(MSG_ERR_MESH_XY); @@ -5582,13 +5461,13 @@ void home_all_axes() { gcode_G28(true); } set_destination_to_current(); if (hasI) destination[X_AXIS] = LOGICAL_X_POSITION(_GET_MESH_X(ix)); if (hasJ) destination[Y_AXIS] = LOGICAL_Y_POSITION(_GET_MESH_Y(iy)); - if (code_seen('P') && code_value_bool()) { + if (parser.seen('P') && parser.value_bool()) { if (hasI) destination[X_AXIS] -= X_PROBE_OFFSET_FROM_EXTRUDER; if (hasJ) destination[Y_AXIS] -= Y_PROBE_OFFSET_FROM_EXTRUDER; } - if (code_seen('F') && code_value_linear_units() > 0.0) - feedrate_mm_s = MMM_TO_MMS(code_value_linear_units()); + if (parser.seen('F') && parser.value_linear_units() > 0.0) + feedrate_mm_s = MMM_TO_MMS(parser.value_linear_units()); // SCARA kinematic has "safe" XY raw moves #if IS_SCARA @@ -5606,20 +5485,20 @@ void home_all_axes() { gcode_G28(true); } */ inline void gcode_G92() { bool didXYZ = false, - didE = code_seen('E'); + didE = parser.seen('E'); if (!didE) stepper.synchronize(); LOOP_XYZE(i) { - if (code_seen(axis_codes[i])) { + if (parser.seen(axis_codes[i])) { #if IS_SCARA - current_position[i] = code_value_axis_units((AxisEnum)i); + current_position[i] = parser.value_axis_units((AxisEnum)i); if (i != E_AXIS) didXYZ = true; #else #if HAS_POSITION_SHIFT const float p = current_position[i]; #endif - float v = code_value_axis_units((AxisEnum)i); + float v = parser.value_axis_units((AxisEnum)i); current_position[i] = v; @@ -5648,22 +5527,22 @@ inline void gcode_G92() { * M1: Conditional stop - Wait for user button press on LCD */ inline void gcode_M0_M1() { - const char * const args = current_command_args; + const char * const args = parser.string_arg; - millis_t codenum = 0; + millis_t ms = 0; bool hasP = false, hasS = false; - if (code_seen('P')) { - codenum = code_value_millis(); // milliseconds to wait - hasP = codenum > 0; + if (parser.seen('P')) { + ms = parser.value_millis(); // milliseconds to wait + hasP = ms > 0; } - if (code_seen('S')) { - codenum = code_value_millis_from_seconds(); // seconds to wait - hasS = codenum > 0; + if (parser.seen('S')) { + ms = parser.value_millis_from_seconds(); // seconds to wait + hasS = ms > 0; } #if ENABLED(ULTIPANEL) - if (!hasP && !hasS && *args != '\0') + if (!hasP && !hasS && args && *args) lcd_setstatus(args, true); else { LCD_MESSAGEPGM(MSG_USERWAIT); @@ -5674,7 +5553,7 @@ inline void gcode_G92() { #else - if (!hasP && !hasS && *args != '\0') { + if (!hasP && !hasS && args && *args) { SERIAL_ECHO_START; SERIAL_ECHOLN(args); } @@ -5687,9 +5566,9 @@ inline void gcode_G92() { stepper.synchronize(); refresh_cmd_timeout(); - if (codenum > 0) { - codenum += previous_cmd_ms; // wait until this time for a click - while (PENDING(millis(), codenum) && wait_for_user) idle(); + if (ms > 0) { + ms += previous_cmd_ms; // wait until this time for a click + while (PENDING(millis(), ms) && wait_for_user) idle(); } else { #if ENABLED(ULTIPANEL) @@ -5759,7 +5638,7 @@ inline void gcode_G92() { */ inline void ocr_val_mode() { - uint8_t spindle_laser_power = code_value_byte(); + uint8_t spindle_laser_power = parser.value_byte(); WRITE(SPINDLE_LASER_ENABLE_PIN, SPINDLE_LASER_ENABLE_INVERT); // turn spindle on (active low) if (SPINDLE_LASER_PWM_INVERT) spindle_laser_power = 255 - spindle_laser_power; analogWrite(SPINDLE_LASER_PWM_PIN, spindle_laser_power); @@ -5786,9 +5665,9 @@ inline void gcode_G92() { * Then needed to AND the uint16_t result with 0x00FF to make sure we only wrote the byte of interest. */ #if ENABLED(SPINDLE_LASER_PWM) - if (code_seen('O')) ocr_val_mode(); + if (parser.seen('O')) ocr_val_mode(); else { - const float spindle_laser_power = code_seen('S') ? code_value_float() : 0; + const float spindle_laser_power = parser.seen('S') ? parser.value_float() : 0; if (spindle_laser_power == 0) { WRITE(SPINDLE_LASER_ENABLE_PIN, !SPINDLE_LASER_ENABLE_INVERT); // turn spindle off (active low) delay_for_power_down(); @@ -5895,7 +5774,7 @@ inline void gcode_M17() { /** * M23: Open a file */ - inline void gcode_M23() { card.openFile(current_command_args, true); } + inline void gcode_M23() { card.openFile(parser.string_arg, true); } /** * M24: Start or Resume SD Print @@ -5925,8 +5804,8 @@ inline void gcode_M17() { * M26: Set SD Card file index */ inline void gcode_M26() { - if (card.cardOK && code_seen('S')) - card.setIndex(code_value_long()); + if (card.cardOK && parser.seen('S')) + card.setIndex(parser.value_long()); } /** @@ -5937,7 +5816,7 @@ inline void gcode_M17() { /** * M28: Start SD Write */ - inline void gcode_M28() { card.openFile(current_command_args, false); } + inline void gcode_M28() { card.openFile(parser.string_arg, false); } /** * M29: Stop SD Write @@ -5953,7 +5832,7 @@ inline void gcode_M17() { inline void gcode_M30() { if (card.cardOK) { card.closefile(); - card.removeFile(current_command_args); + card.removeFile(parser.string_arg); } } @@ -5977,23 +5856,18 @@ inline void gcode_M31() { /** * M32: Select file and start SD Print */ - inline void gcode_M32() { // Why is M32 allowed to flout the sacred GCode standard? + inline void gcode_M32() { if (card.sdprinting) stepper.synchronize(); - char* namestartpos = strchr(current_command_args, '!'); // Find ! to indicate filename string start. - if (!namestartpos) - namestartpos = current_command_args; // Default name position, 4 letters after the M - else - namestartpos++; //to skip the '!' - - bool call_procedure = code_seen('P') && (seen_pointer < namestartpos); + char* namestartpos = parser.string_arg; + bool call_procedure = parser.seen('P'); if (card.cardOK) { card.openFile(namestartpos, true, call_procedure); - if (code_seen('S') && seen_pointer < namestartpos) // "S" (must occur _before_ the filename!) - card.setIndex(code_value_long()); + if (parser.seen('S')) + card.setIndex(parser.value_long()); card.startFileprint(); @@ -6017,7 +5891,7 @@ inline void gcode_M31() { * /Miscellaneous/Armchair/Armchair.gcode */ inline void gcode_M33() { - card.printLongPath(current_command_args); + card.printLongPath(parser.string_arg); } #endif @@ -6027,12 +5901,12 @@ inline void gcode_M31() { * M34: Set SD Card Sorting Options */ inline void gcode_M34() { - if (code_seen('S')) card.setSortOn(code_value_bool()); - if (code_seen('F')) { - int v = code_value_long(); + if (parser.seen('S')) card.setSortOn(parser.value_bool()); + if (parser.seen('F')) { + int v = parser.value_long(); card.setSortFolders(v < 0 ? -1 : v > 0 ? 1 : 0); } - //if (code_seen('R')) card.setSortReverse(code_value_bool()); + //if (parser.seen('R')) card.setSortReverse(parser.value_bool()); } #endif // SDCARD_SORT_ALPHA && SDSORT_GCODE @@ -6040,7 +5914,7 @@ inline void gcode_M31() { * M928: Start SD Write */ inline void gcode_M928() { - card.openLogFile(current_command_args); + card.openLogFile(parser.string_arg); } #endif // SDSUPPORT @@ -6062,12 +5936,12 @@ static bool pin_is_protected(uint8_t pin) { * S Pin status from 0 - 255 */ inline void gcode_M42() { - if (!code_seen('S')) return; + if (!parser.seen('S')) return; - int pin_status = code_value_int(); + int pin_status = parser.value_int(); if (!WITHIN(pin_status, 0, 255)) return; - int pin_number = code_seen('P') ? code_value_int() : LED_PIN; + int pin_number = parser.seen('P') ? parser.value_int() : LED_PIN; if (pin_number < 0) return; if (pin_is_protected(pin_number)) { @@ -6100,11 +5974,11 @@ inline void gcode_M42() { #include "pinsDebug.h" inline void toggle_pins() { - const bool I_flag = code_seen('I') && code_value_bool(); - const int repeat = code_seen('R') ? code_value_int() : 1, - start = code_seen('S') ? code_value_int() : 0, - end = code_seen('E') ? code_value_int() : NUM_DIGITAL_PINS - 1, - wait = code_seen('W') ? code_value_int() : 500; + const bool I_flag = parser.seen('I') && parser.value_bool(); + const int repeat = parser.seen('R') ? parser.value_int() : 1, + start = parser.seen('S') ? parser.value_int() : 0, + end = parser.seen('E') ? parser.value_int() : NUM_DIGITAL_PINS - 1, + wait = parser.seen('W') ? parser.value_int() : 500; for (uint8_t pin = start; pin <= end; pin++) { if (!I_flag && pin_is_protected(pin)) { @@ -6142,7 +6016,7 @@ inline void gcode_M42() { #else - const uint8_t probe_index = code_seen('P') ? code_value_byte() : Z_ENDSTOP_SERVO_NR; + const uint8_t probe_index = parser.seen('P') ? parser.value_byte() : Z_ENDSTOP_SERVO_NR; SERIAL_PROTOCOLLNPGM("Servo probe test"); SERIAL_PROTOCOLLNPAIR(". using index: ", probe_index); @@ -6284,35 +6158,35 @@ inline void gcode_M42() { */ inline void gcode_M43() { - if (code_seen('T')) { // must be first ot else it's "S" and "E" parameters will execute endstop or servo test + if (parser.seen('T')) { // must be first ot else it's "S" and "E" parameters will execute endstop or servo test toggle_pins(); return; } // Enable or disable endstop monitoring - if (code_seen('E')) { - endstop_monitor_flag = code_value_bool(); + if (parser.seen('E')) { + endstop_monitor_flag = parser.value_bool(); SERIAL_PROTOCOLPGM("endstop monitor "); SERIAL_PROTOCOL(endstop_monitor_flag ? "en" : "dis"); SERIAL_PROTOCOLLNPGM("abled"); return; } - if (code_seen('S')) { + if (parser.seen('S')) { servo_probe_test(); return; } // Get the range of pins to test or watch - const uint8_t first_pin = code_seen('P') ? code_value_byte() : 0, - last_pin = code_seen('P') ? first_pin : NUM_DIGITAL_PINS - 1; + const uint8_t first_pin = parser.seen('P') ? parser.value_byte() : 0, + last_pin = parser.seen('P') ? first_pin : NUM_DIGITAL_PINS - 1; if (first_pin > last_pin) return; - const bool ignore_protection = code_seen('I') && code_value_bool(); + const bool ignore_protection = parser.seen('I') && parser.value_bool(); // Watch until click, M108, or reset - if (code_seen('W') && code_value_bool()) { + if (parser.seen('W') && parser.value_bool()) { SERIAL_PROTOCOLLNPGM("Watching pins"); byte pin_state[last_pin - first_pin + 1]; for (int8_t pin = first_pin; pin <= last_pin; pin++) { @@ -6390,7 +6264,7 @@ inline void gcode_M42() { if (axis_unhomed_error()) return; - const int8_t verbose_level = code_seen('V') ? code_value_byte() : 1; + const int8_t verbose_level = parser.seen('V') ? parser.value_byte() : 1; if (!WITHIN(verbose_level, 0, 4)) { SERIAL_PROTOCOLLNPGM("?(V)erbose level is implausible (0-4)."); return; @@ -6399,19 +6273,19 @@ inline void gcode_M42() { if (verbose_level > 0) SERIAL_PROTOCOLLNPGM("M48 Z-Probe Repeatability Test"); - int8_t n_samples = code_seen('P') ? code_value_byte() : 10; + int8_t n_samples = parser.seen('P') ? parser.value_byte() : 10; if (!WITHIN(n_samples, 4, 50)) { SERIAL_PROTOCOLLNPGM("?Sample size not plausible (4-50)."); return; } + const bool stow_probe_after_each = parser.seen('E'); + float X_current = current_position[X_AXIS], Y_current = current_position[Y_AXIS]; - bool stow_probe_after_each = code_seen('E'); - - const float X_probe_location = code_seen('X') ? code_value_linear_units() : X_current + X_PROBE_OFFSET_FROM_EXTRUDER, - Y_probe_location = code_seen('Y') ? code_value_linear_units() : Y_current + Y_PROBE_OFFSET_FROM_EXTRUDER; + const float X_probe_location = parser.seen('X') ? parser.value_linear_units() : X_current + X_PROBE_OFFSET_FROM_EXTRUDER, + Y_probe_location = parser.seen('Y') ? parser.value_linear_units() : Y_current + Y_PROBE_OFFSET_FROM_EXTRUDER; #if DISABLED(DELTA) if (!WITHIN(X_probe_location, LOGICAL_X_POSITION(MIN_PROBE_X), LOGICAL_X_POSITION(MAX_PROBE_X))) { @@ -6429,15 +6303,15 @@ inline void gcode_M42() { } #endif - bool seen_L = code_seen('L'); - uint8_t n_legs = seen_L ? code_value_byte() : 0; + bool seen_L = parser.seen('L'); + uint8_t n_legs = seen_L ? parser.value_byte() : 0; if (n_legs > 15) { SERIAL_PROTOCOLLNPGM("?Number of legs in movement not plausible (0-15)."); return; } if (n_legs == 1) n_legs = 2; - bool schizoid_flag = code_seen('S'); + bool schizoid_flag = parser.seen('S'); if (schizoid_flag && !seen_L) n_legs = 7; /** @@ -6653,7 +6527,7 @@ inline void gcode_M77() { print_job_timer.stop(); } */ inline void gcode_M78() { // "M78 S78" will reset the statistics - if (code_seen('S') && code_value_int() == 78) + if (parser.seen('S') && parser.value_int() == 78) print_job_timer.initStats(); else print_job_timer.showStats(); @@ -6671,8 +6545,8 @@ inline void gcode_M104() { if (target_extruder != active_extruder) return; #endif - if (code_seen('S')) { - const int16_t temp = code_value_temp_abs(); + if (parser.seen('S')) { + const int16_t temp = parser.value_celsius(); thermalManager.setTargetHotend(temp, target_extruder); #if ENABLED(DUAL_X_CARRIAGE) @@ -6687,13 +6561,13 @@ inline void gcode_M104() { * standby mode, for instance in a dual extruder setup, without affecting * the running print timer. */ - if (code_value_temp_abs() <= (EXTRUDE_MINTEMP) / 2) { + if (parser.value_celsius() <= (EXTRUDE_MINTEMP) / 2) { print_job_timer.stop(); LCD_MESSAGEPGM(WELCOME_MSG); } #endif - if (code_value_temp_abs() > thermalManager.degHotend(target_extruder)) + if (parser.value_celsius() > thermalManager.degHotend(target_extruder)) lcd_status_printf_P(0, PSTR("E%i %s"), target_extruder + 1, MSG_HEATING); } @@ -6780,8 +6654,8 @@ inline void gcode_M105() { * M155: Set temperature auto-report interval. M155 S */ inline void gcode_M155() { - if (code_seen('S')) { - auto_report_temp_interval = code_value_byte(); + if (parser.seen('S')) { + auto_report_temp_interval = parser.value_byte(); NOMORE(auto_report_temp_interval, 60); next_temp_report_ms = millis() + 1000UL * auto_report_temp_interval; } @@ -6806,8 +6680,8 @@ inline void gcode_M105() { * P Fan index, if more than one fan */ inline void gcode_M106() { - uint16_t s = code_seen('S') ? code_value_ushort() : 255, - p = code_seen('P') ? code_value_ushort() : 0; + uint16_t s = parser.seen('S') ? parser.value_ushort() : 255, + p = parser.seen('P') ? parser.value_ushort() : 0; NOMORE(s, 255); if (p < FAN_COUNT) fanSpeeds[p] = s; } @@ -6816,7 +6690,7 @@ inline void gcode_M105() { * M107: Fan Off */ inline void gcode_M107() { - uint16_t p = code_seen('P') ? code_value_ushort() : 0; + uint16_t p = parser.seen('P') ? parser.value_ushort() : 0; if (p < FAN_COUNT) fanSpeeds[p] = 0; } @@ -6867,9 +6741,9 @@ inline void gcode_M109() { if (target_extruder != active_extruder) return; #endif - const bool no_wait_for_cooling = code_seen('S'); - if (no_wait_for_cooling || code_seen('R')) { - const int16_t temp = code_value_temp_abs(); + const bool no_wait_for_cooling = parser.seen('S'); + if (no_wait_for_cooling || parser.seen('R')) { + const int16_t temp = parser.value_celsius(); thermalManager.setTargetHotend(temp, target_extruder); #if ENABLED(DUAL_X_CARRIAGE) @@ -6883,7 +6757,7 @@ inline void gcode_M109() { * standby mode, (e.g., in a dual extruder setup) without affecting * the running print timer. */ - if (code_value_temp_abs() <= (EXTRUDE_MINTEMP) / 2) { + if (parser.value_celsius() <= (EXTRUDE_MINTEMP) / 2) { print_job_timer.stop(); LCD_MESSAGEPGM(WELCOME_MSG); } @@ -7020,12 +6894,11 @@ inline void gcode_M109() { if (DEBUGGING(DRYRUN)) return; LCD_MESSAGEPGM(MSG_BED_HEATING); - const bool no_wait_for_cooling = code_seen('S'); - if (no_wait_for_cooling || code_seen('R')) { - thermalManager.setTargetBed(code_value_temp_abs()); - + const bool no_wait_for_cooling = parser.seen('S'); + if (no_wait_for_cooling || parser.seen('R')) { + thermalManager.setTargetBed(parser.value_celsius()); #if ENABLED(PRINTJOB_TIMER_AUTOSTART) - if (code_value_temp_abs() > BED_MINTEMP) + if (parser.value_celsius() > BED_MINTEMP) print_job_timer.start(); #endif } @@ -7133,14 +7006,14 @@ inline void gcode_M109() { * M110: Set Current Line Number */ inline void gcode_M110() { - if (code_seen('N')) gcode_LastN = code_value_long(); + if (parser.seen('N')) gcode_LastN = parser.value_long(); } /** * M111: Set the debug level */ inline void gcode_M111() { - marlin_debug_flags = code_seen('S') ? code_value_byte() : (uint8_t)DEBUG_NONE; + marlin_debug_flags = parser.seen('S') ? parser.value_byte() : (uint8_t)DEBUG_NONE; const static char str_debug_1[] PROGMEM = MSG_DEBUG_ECHO; const static char str_debug_2[] PROGMEM = MSG_DEBUG_INFO; @@ -7152,9 +7025,9 @@ inline void gcode_M111() { #endif const static char* const debug_strings[] PROGMEM = { - str_debug_1, str_debug_2, str_debug_4, str_debug_8, str_debug_16, + str_debug_1, str_debug_2, str_debug_4, str_debug_8, str_debug_16 #if ENABLED(DEBUG_LEVELING_FEATURE) - str_debug_32 + , str_debug_32 #endif }; @@ -7183,8 +7056,8 @@ inline void gcode_M111() { * S Optional. Set the keepalive interval. */ inline void gcode_M113() { - if (code_seen('S')) { - host_keepalive_interval = code_value_byte(); + if (parser.seen('S')) { + host_keepalive_interval = parser.value_byte(); NOMORE(host_keepalive_interval, 60); } else { @@ -7201,7 +7074,7 @@ inline void gcode_M111() { /** * M126: Heater 1 valve open */ - inline void gcode_M126() { baricuda_valve_pressure = code_seen('S') ? code_value_byte() : 255; } + inline void gcode_M126() { baricuda_valve_pressure = parser.seen('S') ? parser.value_byte() : 255; } /** * M127: Heater 1 valve close */ @@ -7212,7 +7085,7 @@ inline void gcode_M111() { /** * M128: Heater 2 valve open */ - inline void gcode_M128() { baricuda_e_to_p_pressure = code_seen('S') ? code_value_byte() : 255; } + inline void gcode_M128() { baricuda_e_to_p_pressure = parser.seen('S') ? parser.value_byte() : 255; } /** * M129: Heater 2 valve close */ @@ -7226,7 +7099,7 @@ inline void gcode_M111() { */ inline void gcode_M140() { if (DEBUGGING(DRYRUN)) return; - if (code_seen('S')) thermalManager.setTargetBed(code_value_temp_abs()); + if (parser.seen('S')) thermalManager.setTargetBed(parser.value_celsius()); } #if ENABLED(ULTIPANEL) @@ -7240,24 +7113,24 @@ inline void gcode_M140() { * F */ inline void gcode_M145() { - uint8_t material = code_seen('S') ? (uint8_t)code_value_int() : 0; + uint8_t material = parser.seen('S') ? (uint8_t)parser.value_int() : 0; if (material >= COUNT(lcd_preheat_hotend_temp)) { SERIAL_ERROR_START; SERIAL_ERRORLNPGM(MSG_ERR_MATERIAL_INDEX); } else { int v; - if (code_seen('H')) { - v = code_value_int(); + if (parser.seen('H')) { + v = parser.value_int(); lcd_preheat_hotend_temp[material] = constrain(v, EXTRUDE_MINTEMP, HEATER_0_MAXTEMP - 15); } - if (code_seen('F')) { - v = code_value_int(); + if (parser.seen('F')) { + v = parser.value_int(); lcd_preheat_fan_speed[material] = constrain(v, 0, 255); } #if TEMP_SENSOR_BED != 0 - if (code_seen('B')) { - v = code_value_int(); + if (parser.seen('B')) { + v = parser.value_int(); lcd_preheat_bed_temp[material] = constrain(v, BED_MINTEMP, BED_MAXTEMP - 15); } #endif @@ -7271,9 +7144,9 @@ inline void gcode_M140() { * M149: Set temperature units */ inline void gcode_M149() { - if (code_seen('C')) set_input_temp_units(TEMPUNIT_C); - else if (code_seen('K')) set_input_temp_units(TEMPUNIT_K); - else if (code_seen('F')) set_input_temp_units(TEMPUNIT_F); + if (parser.seen('C')) parser.set_input_temp_units(TEMPUNIT_C); + else if (parser.seen('K')) parser.set_input_temp_units(TEMPUNIT_K); + else if (parser.seen('F')) parser.set_input_temp_units(TEMPUNIT_F); } #endif @@ -7286,7 +7159,7 @@ inline void gcode_M140() { inline void gcode_M80() { // S: Report the current power supply state and exit - if (code_seen('S')) { + if (parser.seen('S')) { serialprintPGM(powersupply_on ? PSTR("PS:1\n") : PSTR("PS:0\n")); return; } @@ -7362,21 +7235,21 @@ inline void gcode_M83() { axis_relative_modes[E_AXIS] = true; } * M18, M84: Disable stepper motors */ inline void gcode_M18_M84() { - if (code_seen('S')) { - stepper_inactive_time = code_value_millis_from_seconds(); + if (parser.seen('S')) { + stepper_inactive_time = parser.value_millis_from_seconds(); } else { - bool all_axis = !((code_seen('X')) || (code_seen('Y')) || (code_seen('Z')) || (code_seen('E'))); + bool all_axis = !((parser.seen('X')) || (parser.seen('Y')) || (parser.seen('Z')) || (parser.seen('E'))); if (all_axis) { stepper.finish_and_disable(); } else { stepper.synchronize(); - if (code_seen('X')) disable_X(); - if (code_seen('Y')) disable_Y(); - if (code_seen('Z')) disable_Z(); + if (parser.seen('X')) disable_X(); + if (parser.seen('Y')) disable_Y(); + if (parser.seen('Z')) disable_Z(); #if ((E0_ENABLE_PIN != X_ENABLE_PIN) && (E1_ENABLE_PIN != Y_ENABLE_PIN)) // Only enable on boards that have seperate ENABLE_PINS - if (code_seen('E')) disable_e_steppers(); + if (parser.seen('E')) disable_e_steppers(); #endif } } @@ -7386,7 +7259,7 @@ inline void gcode_M18_M84() { * M85: Set inactivity shutdown timer with parameter S. To disable set zero (default) */ inline void gcode_M85() { - if (code_seen('S')) max_inactive_time = code_value_millis_from_seconds(); + if (parser.seen('S')) max_inactive_time = parser.value_millis_from_seconds(); } /** @@ -7411,9 +7284,9 @@ inline void gcode_M92() { GET_TARGET_EXTRUDER(92); LOOP_XYZE(i) { - if (code_seen(axis_codes[i])) { + if (parser.seen(axis_codes[i])) { if (i == E_AXIS) { - const float value = code_value_per_axis_unit((AxisEnum)(E_AXIS + TARGET_EXTRUDER)); + const float value = parser.value_per_axis_unit((AxisEnum)(E_AXIS + TARGET_EXTRUDER)); if (value < 20.0) { float factor = planner.axis_steps_per_mm[E_AXIS + TARGET_EXTRUDER] / value; // increase e constants if M92 E14 is given for netfab. planner.max_jerk[E_AXIS] *= factor; @@ -7423,7 +7296,7 @@ inline void gcode_M92() { planner.axis_steps_per_mm[E_AXIS + TARGET_EXTRUDER] = value; } else { - planner.axis_steps_per_mm[i] = code_value_per_axis_unit((AxisEnum)i); + planner.axis_steps_per_mm[i] = parser.value_per_axis_unit((AxisEnum)i); } } } @@ -7531,7 +7404,7 @@ inline void gcode_M115() { * M117: Set LCD Status Message */ inline void gcode_M117() { - lcd_setstatus(current_command_args); + lcd_setstatus(parser.string_arg); } /** @@ -7592,7 +7465,7 @@ inline void gcode_M121() { endstops.enable_globally(false); } set_destination_to_current(); // Initial retract before move to filament change position - destination[E_AXIS] += code_seen('L') ? code_value_axis_units(E_AXIS) : 0 + destination[E_AXIS] += parser.seen('L') ? parser.value_axis_units(E_AXIS) : 0 #if defined(FILAMENT_CHANGE_RETRACT_LENGTH) && FILAMENT_CHANGE_RETRACT_LENGTH > 0 - (FILAMENT_CHANGE_RETRACT_LENGTH) #endif @@ -7600,7 +7473,7 @@ inline void gcode_M121() { endstops.enable_globally(false); } RUNPLAN(FILAMENT_CHANGE_RETRACT_FEEDRATE); // Lift Z axis - const float z_lift = code_seen('Z') ? code_value_linear_units() : + const float z_lift = parser.seen('Z') ? parser.value_linear_units() : #if defined(FILAMENT_CHANGE_Z_ADD) && FILAMENT_CHANGE_Z_ADD > 0 FILAMENT_CHANGE_Z_ADD #else @@ -7614,12 +7487,12 @@ inline void gcode_M121() { endstops.enable_globally(false); } } // Move XY axes to filament change position or given position - destination[X_AXIS] = code_seen('X') ? code_value_linear_units() : 0 + destination[X_AXIS] = parser.seen('X') ? parser.value_linear_units() : 0 #ifdef FILAMENT_CHANGE_X_POS + FILAMENT_CHANGE_X_POS #endif ; - destination[Y_AXIS] = code_seen('Y') ? code_value_linear_units() : 0 + destination[Y_AXIS] = parser.seen('Y') ? parser.value_linear_units() : 0 #ifdef FILAMENT_CHANGE_Y_POS + FILAMENT_CHANGE_Y_POS #endif @@ -7627,8 +7500,8 @@ inline void gcode_M121() { endstops.enable_globally(false); } #if HOTENDS > 1 && DISABLED(DUAL_X_CARRIAGE) if (active_extruder > 0) { - if (!code_seen('X')) destination[X_AXIS] += hotend_offset[X_AXIS][active_extruder]; - if (!code_seen('Y')) destination[Y_AXIS] += hotend_offset[Y_AXIS][active_extruder]; + if (!parser.seen('X')) destination[X_AXIS] += hotend_offset[X_AXIS][active_extruder]; + if (!parser.seen('Y')) destination[Y_AXIS] += hotend_offset[Y_AXIS][active_extruder]; } #endif @@ -7672,11 +7545,11 @@ inline void gcode_M121() { endstops.enable_globally(false); } */ inline void gcode_M150() { set_led_color( - code_seen('R') ? (code_has_value() ? code_value_byte() : 255) : 0, - code_seen('U') ? (code_has_value() ? code_value_byte() : 255) : 0, - code_seen('B') ? (code_has_value() ? code_value_byte() : 255) : 0 + 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 #if ENABLED(RGBW_LED) - , code_seen('W') ? (code_has_value() ? code_value_byte() : 255) : 0 + , parser.seen('W') ? (parser.has_value() ? parser.value_byte() : 255) : 0 #endif ); } @@ -7693,13 +7566,13 @@ inline void gcode_M200() { if (get_target_extruder_from_command(200)) return; - if (code_seen('D')) { + if (parser.seen('D')) { // setting any extruder filament size disables volumetric on the assumption that // slicers either generate in extruder values as cubic mm or as as filament feeds // for all extruders - volumetric_enabled = (code_value_linear_units() != 0.0); + volumetric_enabled = (parser.value_linear_units() != 0.0); if (volumetric_enabled) { - filament_size[target_extruder] = code_value_linear_units(); + filament_size[target_extruder] = parser.value_linear_units(); // make sure all extruders have some sane value for the filament size for (uint8_t i = 0; i < COUNT(filament_size); i++) if (! filament_size[i]) filament_size[i] = DEFAULT_NOMINAL_FILAMENT_DIA; @@ -7718,9 +7591,9 @@ inline void gcode_M201() { GET_TARGET_EXTRUDER(201); LOOP_XYZE(i) { - if (code_seen(axis_codes[i])) { + if (parser.seen(axis_codes[i])) { const uint8_t a = i + (i == E_AXIS ? TARGET_EXTRUDER : 0); - planner.max_acceleration_mm_per_s2[a] = code_value_axis_units((AxisEnum)a); + planner.max_acceleration_mm_per_s2[a] = parser.value_axis_units((AxisEnum)a); } } // steps per sq second need to be updated to agree with the units per sq second (as they are what is used in the planner) @@ -7730,7 +7603,7 @@ inline void gcode_M201() { #if 0 // Not used for Sprinter/grbl gen6 inline void gcode_M202() { LOOP_XYZE(i) { - if (code_seen(axis_codes[i])) axis_travel_steps_per_sqr_second[i] = code_value_axis_units((AxisEnum)i) * planner.axis_steps_per_mm[i]; + if (parser.seen(axis_codes[i])) axis_travel_steps_per_sqr_second[i] = parser.value_axis_units((AxisEnum)i) * planner.axis_steps_per_mm[i]; } } #endif @@ -7746,9 +7619,9 @@ inline void gcode_M203() { GET_TARGET_EXTRUDER(203); LOOP_XYZE(i) - if (code_seen(axis_codes[i])) { + if (parser.seen(axis_codes[i])) { const uint8_t a = i + (i == E_AXIS ? TARGET_EXTRUDER : 0); - planner.max_feedrate_mm_s[a] = code_value_axis_units((AxisEnum)a); + planner.max_feedrate_mm_s[a] = parser.value_axis_units((AxisEnum)a); } } @@ -7762,20 +7635,20 @@ inline void gcode_M203() { * Also sets minimum segment time in ms (B20000) to prevent buffer under-runs and M20 minimum feedrate */ inline void gcode_M204() { - if (code_seen('S')) { // Kept for legacy compatibility. Should NOT BE USED for new developments. - planner.travel_acceleration = planner.acceleration = code_value_linear_units(); + if (parser.seen('S')) { // Kept for legacy compatibility. Should NOT BE USED for new developments. + planner.travel_acceleration = planner.acceleration = parser.value_linear_units(); SERIAL_ECHOLNPAIR("Setting Print and Travel Acceleration: ", planner.acceleration); } - if (code_seen('P')) { - planner.acceleration = code_value_linear_units(); + if (parser.seen('P')) { + planner.acceleration = parser.value_linear_units(); SERIAL_ECHOLNPAIR("Setting Print Acceleration: ", planner.acceleration); } - if (code_seen('R')) { - planner.retract_acceleration = code_value_linear_units(); + if (parser.seen('R')) { + planner.retract_acceleration = parser.value_linear_units(); SERIAL_ECHOLNPAIR("Setting Retract Acceleration: ", planner.retract_acceleration); } - if (code_seen('T')) { - planner.travel_acceleration = code_value_linear_units(); + if (parser.seen('T')) { + planner.travel_acceleration = parser.value_linear_units(); SERIAL_ECHOLNPAIR("Setting Travel Acceleration: ", planner.travel_acceleration); } } @@ -7792,13 +7665,13 @@ inline void gcode_M204() { * E = Max E Jerk (units/sec^2) */ inline void gcode_M205() { - if (code_seen('S')) planner.min_feedrate_mm_s = code_value_linear_units(); - if (code_seen('T')) planner.min_travel_feedrate_mm_s = code_value_linear_units(); - if (code_seen('B')) planner.min_segment_time = code_value_millis(); - if (code_seen('X')) planner.max_jerk[X_AXIS] = code_value_linear_units(); - if (code_seen('Y')) planner.max_jerk[Y_AXIS] = code_value_linear_units(); - if (code_seen('Z')) planner.max_jerk[Z_AXIS] = code_value_linear_units(); - if (code_seen('E')) planner.max_jerk[E_AXIS] = code_value_linear_units(); + if (parser.seen('S')) planner.min_feedrate_mm_s = parser.value_linear_units(); + if (parser.seen('T')) planner.min_travel_feedrate_mm_s = parser.value_linear_units(); + if (parser.seen('B')) planner.min_segment_time = parser.value_millis(); + if (parser.seen('X')) planner.max_jerk[X_AXIS] = parser.value_linear_units(); + if (parser.seen('Y')) planner.max_jerk[Y_AXIS] = parser.value_linear_units(); + if (parser.seen('Z')) planner.max_jerk[Z_AXIS] = parser.value_linear_units(); + if (parser.seen('E')) planner.max_jerk[E_AXIS] = parser.value_linear_units(); } #if HAS_M206_COMMAND @@ -7808,12 +7681,12 @@ inline void gcode_M205() { */ inline void gcode_M206() { LOOP_XYZ(i) - if (code_seen(axis_codes[i])) - set_home_offset((AxisEnum)i, code_value_linear_units()); + if (parser.seen(axis_codes[i])) + set_home_offset((AxisEnum)i, parser.value_linear_units()); #if ENABLED(MORGAN_SCARA) - if (code_seen('T')) set_home_offset(A_AXIS, code_value_linear_units()); // Theta - if (code_seen('P')) set_home_offset(B_AXIS, code_value_linear_units()); // Psi + if (parser.seen('T')) set_home_offset(A_AXIS, parser.value_linear_units()); // Theta + if (parser.seen('P')) set_home_offset(B_AXIS, parser.value_linear_units()); // Psi #endif SYNC_PLAN_POSITION_KINEMATIC(); @@ -7836,20 +7709,20 @@ inline void gcode_M205() { * Z = Rotate A and B by this angle */ inline void gcode_M665() { - if (code_seen('H')) { - home_offset[Z_AXIS] = code_value_linear_units() - DELTA_HEIGHT; - current_position[Z_AXIS] += code_value_linear_units() - DELTA_HEIGHT - home_offset[Z_AXIS]; + if (parser.seen('H')) { + home_offset[Z_AXIS] = parser.value_linear_units() - DELTA_HEIGHT; + current_position[Z_AXIS] += parser.value_linear_units() - DELTA_HEIGHT - home_offset[Z_AXIS]; update_software_endstops(Z_AXIS); } - if (code_seen('L')) delta_diagonal_rod = code_value_linear_units(); - if (code_seen('R')) delta_radius = code_value_linear_units(); - if (code_seen('S')) delta_segments_per_second = code_value_float(); - if (code_seen('B')) delta_calibration_radius = code_value_float(); - if (code_seen('X')) delta_tower_angle_trim[A_AXIS] = code_value_float(); - if (code_seen('Y')) delta_tower_angle_trim[B_AXIS] = code_value_float(); - if (code_seen('Z')) { // rotate all 3 axis for Z = 0 - delta_tower_angle_trim[A_AXIS] -= code_value_float(); - delta_tower_angle_trim[B_AXIS] -= code_value_float(); + if (parser.seen('L')) delta_diagonal_rod = parser.value_linear_units(); + if (parser.seen('R')) delta_radius = parser.value_linear_units(); + if (parser.seen('S')) delta_segments_per_second = parser.value_float(); + if (parser.seen('B')) delta_calibration_radius = parser.value_float(); + if (parser.seen('X')) delta_tower_angle_trim[A_AXIS] = parser.value_float(); + if (parser.seen('Y')) delta_tower_angle_trim[B_AXIS] = parser.value_float(); + if (parser.seen('Z')) { // rotate all 3 axis for Z = 0 + delta_tower_angle_trim[A_AXIS] -= parser.value_float(); + delta_tower_angle_trim[B_AXIS] -= parser.value_float(); } recalc_delta_settings(delta_radius, delta_diagonal_rod); } @@ -7863,8 +7736,8 @@ inline void gcode_M205() { } #endif LOOP_XYZ(i) { - if (code_seen(axis_codes[i])) { - endstop_adj[i] = code_value_linear_units(); + if (parser.seen(axis_codes[i])) { + endstop_adj[i] = parser.value_linear_units(); #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) { SERIAL_ECHOPAIR("endstop_adj[", axis_codes[i]); @@ -7890,7 +7763,7 @@ inline void gcode_M205() { * M666: For Z Dual Endstop setup, set z axis offset to the z2 axis. */ inline void gcode_M666() { - if (code_seen('Z')) z_endstop_adj = code_value_linear_units(); + if (parser.seen('Z')) z_endstop_adj = parser.value_linear_units(); SERIAL_ECHOLNPAIR("Z Endstop Adjustment set to (mm):", z_endstop_adj); } @@ -7907,11 +7780,11 @@ inline void gcode_M205() { * Z[units] retract_zlift */ inline void gcode_M207() { - if (code_seen('S')) retract_length = code_value_axis_units(E_AXIS); - if (code_seen('F')) retract_feedrate_mm_s = MMM_TO_MMS(code_value_axis_units(E_AXIS)); - if (code_seen('Z')) retract_zlift = code_value_linear_units(); + if (parser.seen('S')) retract_length = parser.value_axis_units(E_AXIS); + if (parser.seen('F')) retract_feedrate_mm_s = MMM_TO_MMS(parser.value_axis_units(E_AXIS)); + if (parser.seen('Z')) retract_zlift = parser.value_linear_units(); #if EXTRUDERS > 1 - if (code_seen('W')) retract_length_swap = code_value_axis_units(E_AXIS); + if (parser.seen('W')) retract_length_swap = parser.value_axis_units(E_AXIS); #endif } @@ -7923,10 +7796,10 @@ inline void gcode_M205() { * F[units/min] retract_recover_feedrate_mm_s */ inline void gcode_M208() { - if (code_seen('S')) retract_recover_length = code_value_axis_units(E_AXIS); - if (code_seen('F')) retract_recover_feedrate_mm_s = MMM_TO_MMS(code_value_axis_units(E_AXIS)); + if (parser.seen('S')) retract_recover_length = parser.value_axis_units(E_AXIS); + if (parser.seen('F')) retract_recover_feedrate_mm_s = MMM_TO_MMS(parser.value_axis_units(E_AXIS)); #if EXTRUDERS > 1 - if (code_seen('W')) retract_recover_length_swap = code_value_axis_units(E_AXIS); + if (parser.seen('W')) retract_recover_length_swap = parser.value_axis_units(E_AXIS); #endif } @@ -7936,8 +7809,8 @@ inline void gcode_M205() { * moves will be classified as retraction. */ inline void gcode_M209() { - if (code_seen('S')) { - autoretract_enabled = code_value_bool(); + if (parser.seen('S')) { + autoretract_enabled = parser.value_bool(); for (int i = 0; i < EXTRUDERS; i++) retracted[i] = false; } } @@ -7952,7 +7825,7 @@ inline void gcode_M205() { inline void gcode_M211() { SERIAL_ECHO_START; #if HAS_SOFTWARE_ENDSTOPS - if (code_seen('S')) soft_endstops_enabled = code_value_bool(); + if (parser.seen('S')) soft_endstops_enabled = parser.value_bool(); SERIAL_ECHOPGM(MSG_SOFT_ENDSTOPS); serialprintPGM(soft_endstops_enabled ? PSTR(MSG_ON) : PSTR(MSG_OFF)); #else @@ -7982,11 +7855,11 @@ inline void gcode_M211() { inline void gcode_M218() { if (get_target_extruder_from_command(218) || target_extruder == 0) return; - if (code_seen('X')) hotend_offset[X_AXIS][target_extruder] = code_value_linear_units(); - if (code_seen('Y')) hotend_offset[Y_AXIS][target_extruder] = code_value_linear_units(); + if (parser.seen('X')) hotend_offset[X_AXIS][target_extruder] = parser.value_linear_units(); + if (parser.seen('Y')) hotend_offset[Y_AXIS][target_extruder] = parser.value_linear_units(); #if ENABLED(DUAL_X_CARRIAGE) || ENABLED(SWITCHING_NOZZLE) - if (code_seen('Z')) hotend_offset[Z_AXIS][target_extruder] = code_value_linear_units(); + if (parser.seen('Z')) hotend_offset[Z_AXIS][target_extruder] = parser.value_linear_units(); #endif SERIAL_ECHO_START; @@ -8010,7 +7883,7 @@ inline void gcode_M211() { * M220: Set speed percentage factor, aka "Feed Rate" (M220 S95) */ inline void gcode_M220() { - if (code_seen('S')) feedrate_percentage = code_value_int(); + if (parser.seen('S')) feedrate_percentage = parser.value_int(); } /** @@ -8018,17 +7891,17 @@ inline void gcode_M220() { */ inline void gcode_M221() { if (get_target_extruder_from_command(221)) return; - if (code_seen('S')) - flow_percentage[target_extruder] = code_value_int(); + if (parser.seen('S')) + flow_percentage[target_extruder] = parser.value_int(); } /** * M226: Wait until the specified pin reaches the state required (M226 P S) */ inline void gcode_M226() { - if (code_seen('P')) { - int pin_number = code_value_int(), - pin_state = code_seen('S') ? code_value_int() : -1; // required pin state - default is inverted + if (parser.seen('P')) { + int pin_number = parser.value_int(), + pin_state = parser.seen('S') ? parser.value_int() : -1; // required pin state - default is inverted if (pin_state >= -1 && pin_state <= 1 && pin_number > -1 && !pin_is_protected(pin_number)) { @@ -8052,7 +7925,7 @@ inline void gcode_M226() { while (digitalRead(pin_number) != target) idle(); } // pin_state -1 0 1 && pin_number > -1 - } // code_seen('P') + } // parser.seen('P') } #if ENABLED(EXPERIMENTAL_I2CBUS) @@ -8075,16 +7948,16 @@ inline void gcode_M226() { */ inline void gcode_M260() { // Set the target address - if (code_seen('A')) i2c.address(code_value_byte()); + if (parser.seen('A')) i2c.address(parser.value_byte()); // Add a new byte to the buffer - if (code_seen('B')) i2c.addbyte(code_value_byte()); + if (parser.seen('B')) i2c.addbyte(parser.value_byte()); // Flush the buffer to the bus - if (code_seen('S')) i2c.send(); + if (parser.seen('S')) i2c.send(); // Reset and rewind the buffer - else if (code_seen('R')) i2c.reset(); + else if (parser.seen('R')) i2c.reset(); } /** @@ -8093,9 +7966,9 @@ inline void gcode_M226() { * Usage: M261 A B */ inline void gcode_M261() { - if (code_seen('A')) i2c.address(code_value_byte()); + if (parser.seen('A')) i2c.address(parser.value_byte()); - uint8_t bytes = code_seen('B') ? code_value_byte() : 1; + uint8_t bytes = parser.seen('B') ? parser.value_byte() : 1; if (i2c.addr && bytes && bytes <= TWIBUS_BUFFER_SIZE) { i2c.relay(bytes); @@ -8114,11 +7987,11 @@ inline void gcode_M226() { * M280: Get or set servo position. P [S] */ inline void gcode_M280() { - if (!code_seen('P')) return; - int servo_index = code_value_int(); + if (!parser.seen('P')) return; + int servo_index = parser.value_int(); if (WITHIN(servo_index, 0, NUM_SERVOS - 1)) { - if (code_seen('S')) - MOVE_SERVO(servo_index, code_value_int()); + if (parser.seen('S')) + MOVE_SERVO(servo_index, parser.value_int()); else { SERIAL_ECHO_START; SERIAL_ECHOPAIR(" Servo ", servo_index); @@ -8140,8 +8013,8 @@ inline void gcode_M226() { * M300: Play beep sound S P */ inline void gcode_M300() { - uint16_t const frequency = code_seen('S') ? code_value_ushort() : 260; - uint16_t duration = code_seen('P') ? code_value_ushort() : 1000; + uint16_t const frequency = parser.seen('S') ? parser.value_ushort() : 260; + uint16_t duration = parser.seen('P') ? parser.value_ushort() : 1000; // Limits the tone duration to 0-5 seconds. NOMORE(duration, 5000); @@ -8169,15 +8042,15 @@ inline void gcode_M226() { // multi-extruder PID patch: M301 updates or prints a single extruder's PID values // default behaviour (omitting E parameter) is to update for extruder 0 only - int e = code_seen('E') ? code_value_int() : 0; // extruder being updated + int e = parser.seen('E') ? parser.value_int() : 0; // extruder being updated if (e < HOTENDS) { // catch bad input value - if (code_seen('P')) PID_PARAM(Kp, e) = code_value_float(); - if (code_seen('I')) PID_PARAM(Ki, e) = scalePID_i(code_value_float()); - if (code_seen('D')) PID_PARAM(Kd, e) = scalePID_d(code_value_float()); + if (parser.seen('P')) PID_PARAM(Kp, e) = parser.value_float(); + if (parser.seen('I')) PID_PARAM(Ki, e) = scalePID_i(parser.value_float()); + if (parser.seen('D')) PID_PARAM(Kd, e) = scalePID_d(parser.value_float()); #if ENABLED(PID_EXTRUSION_SCALING) - if (code_seen('C')) PID_PARAM(Kc, e) = code_value_float(); - if (code_seen('L')) lpq_len = code_value_float(); + if (parser.seen('C')) PID_PARAM(Kc, e) = parser.value_float(); + if (parser.seen('L')) lpq_len = parser.value_float(); NOMORE(lpq_len, LPQ_MAX_LEN); #endif @@ -8206,9 +8079,9 @@ inline void gcode_M226() { #if ENABLED(PIDTEMPBED) inline void gcode_M304() { - if (code_seen('P')) thermalManager.bedKp = code_value_float(); - if (code_seen('I')) thermalManager.bedKi = scalePID_i(code_value_float()); - if (code_seen('D')) thermalManager.bedKd = scalePID_d(code_value_float()); + if (parser.seen('P')) thermalManager.bedKp = parser.value_float(); + if (parser.seen('I')) thermalManager.bedKi = scalePID_i(parser.value_float()); + if (parser.seen('D')) thermalManager.bedKd = scalePID_d(parser.value_float()); thermalManager.updatePID(); @@ -8262,7 +8135,7 @@ inline void gcode_M226() { * M250: Read and optionally set the LCD contrast */ inline void gcode_M250() { - if (code_seen('C')) set_lcd_contrast(code_value_int()); + if (parser.seen('C')) set_lcd_contrast(parser.value_int()); SERIAL_PROTOCOLPGM("lcd contrast value: "); SERIAL_PROTOCOL(lcd_contrast); SERIAL_EOL; @@ -8288,14 +8161,14 @@ inline void gcode_M226() { * M302 S170 P1 ; set min extrude temp to 170 but leave disabled */ inline void gcode_M302() { - bool seen_S = code_seen('S'); + bool seen_S = parser.seen('S'); if (seen_S) { - thermalManager.extrude_min_temp = code_value_temp_abs(); + thermalManager.extrude_min_temp = parser.value_celsius(); thermalManager.allow_cold_extrude = (thermalManager.extrude_min_temp == 0); } - if (code_seen('P')) - thermalManager.allow_cold_extrude = (thermalManager.extrude_min_temp == 0) || code_value_bool(); + if (parser.seen('P')) + thermalManager.allow_cold_extrude = (thermalManager.extrude_min_temp == 0) || parser.value_bool(); else if (!seen_S) { // Report current state SERIAL_ECHO_START; @@ -8317,11 +8190,11 @@ inline void gcode_M226() { */ inline void gcode_M303() { #if HAS_PID_HEATING - const int e = code_seen('E') ? code_value_int() : 0, - c = code_seen('C') ? code_value_int() : 5; - const bool u = code_seen('U') && code_value_bool(); + const int e = parser.seen('E') ? parser.value_int() : 0, + c = parser.seen('C') ? parser.value_int() : 5; + const bool u = parser.seen('U') && parser.value_bool(); - int16_t temp = code_seen('S') ? code_value_temp_abs() : (e < 0 ? 70 : 150); + int16_t temp = parser.seen('S') ? parser.value_celsius() : (e < 0 ? 70 : 150); if (WITHIN(e, 0, HOTENDS - 1)) target_extruder = e; @@ -8482,8 +8355,8 @@ inline void gcode_M400() { stepper.synchronize(); } * M404: Display or set (in current units) the nominal filament width (3mm, 1.75mm ) W<3.0> */ inline void gcode_M404() { - if (code_seen('W')) { - filament_width_nominal = code_value_linear_units(); + if (parser.seen('W')) { + filament_width_nominal = parser.value_linear_units(); } else { SERIAL_PROTOCOLPGM("Filament dia (nominal mm):"); @@ -8496,8 +8369,8 @@ inline void gcode_M400() { stepper.synchronize(); } */ inline void gcode_M405() { // This is technically a linear measurement, but since it's quantized to centimeters and is a different unit than - // everything else, it uses code_value_int() instead of code_value_linear_units(). - if (code_seen('D')) meas_delay_cm = code_value_int(); + // everything else, it uses parser.value_int() instead of parser.value_linear_units(). + if (parser.seen('D')) meas_delay_cm = parser.value_int(); NOMORE(meas_delay_cm, MAX_MEASUREMENT_DELAY); if (filwidth_delay_index[1] == -1) { // Initialize the ring buffer if not done since startup @@ -8555,8 +8428,8 @@ void quickstop_stepper() { #if ENABLED(AUTO_BED_LEVELING_UBL) // L to load a mesh from the EEPROM - if (code_seen('L')) { - const int8_t storage_slot = code_has_value() ? code_value_int() : ubl.state.storage_slot; + if (parser.seen('L')) { + const int8_t storage_slot = parser.has_value() ? parser.value_int() : ubl.state.storage_slot; const int16_t a = settings.calc_num_meshes(); if (!a) { @@ -8576,7 +8449,7 @@ void quickstop_stepper() { #endif // AUTO_BED_LEVELING_UBL // V to print the matrix or mesh - if (code_seen('V')) { + if (parser.seen('V')) { #if ABL_PLANAR planner.bed_level_matrix.debug(PSTR("Bed Level Correction Matrix:")); #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) @@ -8596,7 +8469,7 @@ void quickstop_stepper() { #if ENABLED(AUTO_BED_LEVELING_UBL) // L to load a mesh from the EEPROM - if (code_seen('L') || code_seen('V')) { + if (parser.seen('L') || parser.seen('V')) { ubl.display_map(0); // Currently only supports one map type SERIAL_ECHOLNPAIR("UBL_MESH_VALID = ", UBL_MESH_VALID); SERIAL_ECHOLNPAIR("ubl.state.storage_slot = ", ubl.state.storage_slot); @@ -8604,13 +8477,13 @@ void quickstop_stepper() { #endif bool to_enable = false; - if (code_seen('S')) { - to_enable = code_value_bool(); + if (parser.seen('S')) { + to_enable = parser.value_bool(); set_bed_leveling_enabled(to_enable); } #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - if (code_seen('Z')) set_z_fade_height(code_value_linear_units()); + if (parser.seen('Z')) set_z_fade_height(parser.value_linear_units()); #endif const bool new_status = @@ -8645,11 +8518,11 @@ void quickstop_stepper() { * M421 I J Q */ inline void gcode_M421() { - const bool hasX = code_seen('X'), hasI = code_seen('I'); - const int8_t ix = hasI ? code_value_int() : hasX ? mbl.probe_index_x(RAW_X_POSITION(code_value_linear_units())) : -1; - const bool hasY = code_seen('Y'), hasJ = code_seen('J'); - const int8_t iy = hasJ ? code_value_int() : hasY ? mbl.probe_index_y(RAW_Y_POSITION(code_value_linear_units())) : -1; - const bool hasZ = code_seen('Z'), hasQ = !hasZ && code_seen('Q'); + const bool hasX = parser.seen('X'), hasI = parser.seen('I'); + const int8_t ix = hasI ? parser.value_int() : hasX ? mbl.probe_index_x(RAW_X_POSITION(parser.value_linear_units())) : -1; + const bool hasY = parser.seen('Y'), hasJ = parser.seen('J'); + const int8_t iy = hasJ ? parser.value_int() : hasY ? mbl.probe_index_y(RAW_Y_POSITION(parser.value_linear_units())) : -1; + const bool hasZ = parser.seen('Z'), hasQ = !hasZ && parser.seen('Q'); if (int(hasI && hasJ) + int(hasX && hasY) != 1 || !(hasZ || hasQ)) { SERIAL_ERROR_START; @@ -8660,7 +8533,7 @@ void quickstop_stepper() { SERIAL_ERRORLNPGM(MSG_ERR_MESH_XY); } else - mbl.set_z(ix, iy, code_value_linear_units() + (hasQ ? mbl.z_values[ix][iy] : 0)); + mbl.set_z(ix, iy, parser.value_linear_units() + (hasQ ? mbl.z_values[ix][iy] : 0)); } #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) @@ -8673,11 +8546,11 @@ void quickstop_stepper() { * M421 I J Q */ inline void gcode_M421() { - const bool hasI = code_seen('I'); - const int8_t ix = hasI ? code_value_int() : -1; - const bool hasJ = code_seen('J'); - const int8_t iy = hasJ ? code_value_int() : -1; - const bool hasZ = code_seen('Z'), hasQ = !hasZ && code_seen('Q'); + const bool hasI = parser.seen('I'); + const int8_t ix = hasI ? parser.value_int() : -1; + const bool hasJ = parser.seen('J'); + const int8_t iy = hasJ ? parser.value_int() : -1; + const bool hasZ = parser.seen('Z'), hasQ = !hasZ && parser.seen('Q'); if (!hasI || !hasJ || !(hasZ || hasQ)) { SERIAL_ERROR_START; @@ -8688,7 +8561,7 @@ void quickstop_stepper() { SERIAL_ERRORLNPGM(MSG_ERR_MESH_XY); } else { - z_values[ix][iy] = code_value_linear_units() + (hasQ ? z_values[ix][iy] : 0); + z_values[ix][iy] = parser.value_linear_units() + (hasQ ? z_values[ix][iy] : 0); #if ENABLED(ABL_BILINEAR_SUBDIVISION) bed_level_virt_interpolate(); #endif @@ -8707,12 +8580,11 @@ void quickstop_stepper() { * M421 C Q */ inline void gcode_M421() { - const bool hasC = code_seen('C'); - const bool hasI = code_seen('I'); - int8_t ix = hasI ? code_value_int() : -1; - const bool hasJ = code_seen('J'); - int8_t iy = hasJ ? code_value_int() : -1; - const bool hasZ = code_seen('Z'), hasQ = !hasZ && code_seen('Q'); + const bool hasC = parser.seen('C'), hasI = parser.seen('I'); + int8_t ix = hasI ? parser.value_int() : -1; + const bool hasJ = parser.seen('J'); + int8_t iy = hasJ ? parser.value_int() : -1; + const bool hasZ = parser.seen('Z'), hasQ = !hasZ && parser.seen('Q'); if (hasC) { const mesh_index_pair location = ubl.find_closest_mesh_point_of_type(REAL, current_position[X_AXIS], current_position[Y_AXIS], USE_NOZZLE_AS_REFERENCE, NULL, false); @@ -8729,7 +8601,7 @@ void quickstop_stepper() { SERIAL_ERRORLNPGM(MSG_ERR_MESH_XY); } else - ubl.z_values[ix][iy] = code_value_linear_units() + (hasQ ? ubl.z_values[ix][iy] : 0); + ubl.z_values[ix][iy] = parser.value_linear_units() + (hasQ ? ubl.z_values[ix][iy] : 0); } #endif // AUTO_BED_LEVELING_UBL @@ -8803,7 +8675,7 @@ inline void gcode_M502() { * M503: print settings currently in memory */ inline void gcode_M503() { - (void)settings.report(code_seen('S') && !code_value_bool()); + (void)settings.report(parser.seen('S') && !parser.value_bool()); } #if ENABLED(ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED) @@ -8812,7 +8684,7 @@ inline void gcode_M503() { * M540: Set whether SD card print should abort on endstop hit (M540 S<0|1>) */ inline void gcode_M540() { - if (code_seen('S')) stepper.abort_on_endstop_hit = code_value_bool(); + if (parser.seen('S')) stepper.abort_on_endstop_hit = parser.value_bool(); } #endif // ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED @@ -8858,8 +8730,8 @@ inline void gcode_M503() { inline void gcode_M851() { SERIAL_ECHO_START; SERIAL_ECHOPGM(MSG_ZPROBE_ZOFFSET " "); - if (code_seen('Z')) { - const float value = code_value_linear_units(); + if (parser.seen('Z')) { + const float value = parser.value_linear_units(); if (WITHIN(value, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX)) { zprobe_zoffset = value; refresh_zprobe_zoffset(); @@ -8933,7 +8805,7 @@ inline void gcode_M503() { set_destination_to_current(); // Initial retract before move to filament change position - destination[E_AXIS] += code_seen('E') ? code_value_axis_units(E_AXIS) : 0 + destination[E_AXIS] += parser.seen('E') ? parser.value_axis_units(E_AXIS) : 0 #if defined(FILAMENT_CHANGE_RETRACT_LENGTH) && FILAMENT_CHANGE_RETRACT_LENGTH > 0 - (FILAMENT_CHANGE_RETRACT_LENGTH) #endif @@ -8942,7 +8814,7 @@ inline void gcode_M503() { RUNPLAN(FILAMENT_CHANGE_RETRACT_FEEDRATE); // Lift Z axis - float z_lift = code_seen('Z') ? code_value_linear_units() : + float z_lift = parser.seen('Z') ? parser.value_linear_units() : #if defined(FILAMENT_CHANGE_Z_ADD) && FILAMENT_CHANGE_Z_ADD > 0 FILAMENT_CHANGE_Z_ADD #else @@ -8957,12 +8829,12 @@ inline void gcode_M503() { } // Move XY axes to filament exchange position - if (code_seen('X')) destination[X_AXIS] = code_value_linear_units(); + if (parser.seen('X')) destination[X_AXIS] = parser.value_linear_units(); #ifdef FILAMENT_CHANGE_X_POS else destination[X_AXIS] = FILAMENT_CHANGE_X_POS; #endif - if (code_seen('Y')) destination[Y_AXIS] = code_value_linear_units(); + if (parser.seen('Y')) destination[Y_AXIS] = parser.value_linear_units(); #ifdef FILAMENT_CHANGE_Y_POS else destination[Y_AXIS] = FILAMENT_CHANGE_Y_POS; #endif @@ -8974,7 +8846,7 @@ inline void gcode_M503() { idle(); // Unload filament - destination[E_AXIS] += code_seen('L') ? code_value_axis_units(E_AXIS) : 0 + destination[E_AXIS] += parser.seen('L') ? parser.value_axis_units(E_AXIS) : 0 #if FILAMENT_CHANGE_UNLOAD_LENGTH > 0 - (FILAMENT_CHANGE_UNLOAD_LENGTH) #endif @@ -9062,7 +8934,7 @@ inline void gcode_M503() { lcd_filament_change_show_message(FILAMENT_CHANGE_MESSAGE_LOAD); // Load filament - destination[E_AXIS] += code_seen('L') ? -code_value_axis_units(E_AXIS) : 0 + destination[E_AXIS] += parser.seen('L') ? -parser.value_axis_units(E_AXIS) : 0 #if FILAMENT_CHANGE_LOAD_LENGTH > 0 + FILAMENT_CHANGE_LOAD_LENGTH #endif @@ -9145,14 +9017,14 @@ inline void gcode_M503() { */ inline void gcode_M605() { stepper.synchronize(); - if (code_seen('S')) dual_x_carriage_mode = (DualXMode)code_value_byte(); + if (parser.seen('S')) dual_x_carriage_mode = (DualXMode)parser.value_byte(); switch (dual_x_carriage_mode) { case DXC_FULL_CONTROL_MODE: case DXC_AUTO_PARK_MODE: break; case DXC_DUPLICATION_MODE: - if (code_seen('X')) duplicate_extruder_x_offset = max(code_value_linear_units(), X2_MIN_POS - x_home_pos(0)); - if (code_seen('R')) duplicate_extruder_temp_offset = code_value_temp_diff(); + if (parser.seen('X')) duplicate_extruder_x_offset = max(parser.value_linear_units(), X2_MIN_POS - x_home_pos(0)); + if (parser.seen('R')) duplicate_extruder_temp_offset = parser.value_celsius_diff(); SERIAL_ECHO_START; SERIAL_ECHOPGM(MSG_HOTEND_OFFSET); SERIAL_CHAR(' '); @@ -9177,7 +9049,7 @@ inline void gcode_M503() { inline void gcode_M605() { stepper.synchronize(); - extruder_duplication_enabled = code_seen('S') && code_value_int() == (int)DXC_DUPLICATION_MODE; + extruder_duplication_enabled = parser.seen('S') && parser.value_int() == (int)DXC_DUPLICATION_MODE; SERIAL_ECHO_START; SERIAL_ECHOLNPAIR(MSG_DUPLICATION_MODE, extruder_duplication_enabled ? MSG_ON : MSG_OFF); } @@ -9195,14 +9067,14 @@ inline void gcode_M503() { inline void gcode_M900() { stepper.synchronize(); - const float newK = code_seen('K') ? code_value_float() : -1; + const float newK = parser.seen('K') ? parser.value_float() : -1; if (newK >= 0) planner.extruder_advance_k = newK; - float newR = code_seen('R') ? code_value_float() : -1; + float newR = parser.seen('R') ? parser.value_float() : -1; if (newR < 0) { - const float newD = code_seen('D') ? code_value_float() : -1, - newW = code_seen('W') ? code_value_float() : -1, - newH = code_seen('H') ? code_value_float() : -1; + const float newD = parser.seen('D') ? parser.value_float() : -1, + newW = parser.seen('W') ? parser.value_float() : -1, + newH = parser.seen('H') ? parser.value_float() : -1; if (newD >= 0 && newW >= 0 && newH >= 0) newR = newD ? (newW * newH) / (sq(newD * 0.5) * M_PI) : 0; } @@ -9271,7 +9143,7 @@ inline void gcode_M503() { inline void gcode_M906() { uint16_t values[XYZE]; LOOP_XYZE(i) - values[i] = code_seen(axis_codes[i]) ? code_value_int() : 0; + values[i] = parser.seen(axis_codes[i]) ? parser.value_int() : 0; #if ENABLED(X_IS_TMC2130) if (values[X_AXIS]) tmc2130_set_current(stepperX, 'X', values[X_AXIS]); @@ -9291,7 +9163,7 @@ inline void gcode_M503() { #endif #if ENABLED(AUTOMATIC_CURRENT_CONTROL) - if (code_seen('S')) auto_current_control = code_value_bool(); + if (parser.seen('S')) auto_current_control = parser.value_bool(); #endif } @@ -9300,7 +9172,7 @@ inline void gcode_M503() { * The flag is held by the library and persist until manually cleared by M912 */ inline void gcode_M911() { - const bool reportX = code_seen('X'), reportY = code_seen('Y'), reportZ = code_seen('Z'), reportE = code_seen('E'), + const bool reportX = parser.seen('X'), reportY = parser.seen('Y'), reportZ = parser.seen('Z'), reportE = parser.seen('E'), reportAll = (!reportX && !reportY && !reportZ && !reportE) || (reportX && reportY && reportZ && reportE); #if ENABLED(X_IS_TMC2130) if (reportX || reportAll) tmc2130_report_otpw(stepperX, 'X'); @@ -9320,7 +9192,7 @@ inline void gcode_M503() { * M912: Clear TMC2130 stepper driver overtemperature pre-warn flag held by the library */ inline void gcode_M912() { - const bool clearX = code_seen('X'), clearY = code_seen('Y'), clearZ = code_seen('Z'), clearE = code_seen('E'), + const bool clearX = parser.seen('X'), clearY = parser.seen('Y'), clearZ = parser.seen('Z'), clearE = parser.seen('E'), clearAll = (!clearX && !clearY && !clearZ && !clearE) || (clearX && clearY && clearZ && clearE); #if ENABLED(X_IS_TMC2130) if (clearX || clearAll) tmc2130_clear_otpw(stepperX, 'X'); @@ -9343,7 +9215,7 @@ inline void gcode_M503() { inline void gcode_M913() { uint16_t values[XYZE]; LOOP_XYZE(i) - values[i] = code_seen(axis_codes[i]) ? code_value_int() : 0; + values[i] = parser.seen(axis_codes[i]) ? parser.value_int() : 0; #if ENABLED(X_IS_TMC2130) if (values[X_AXIS]) tmc2130_set_pwmthrs(stepperX, 'X', values[X_AXIS], planner.axis_steps_per_mm[X_AXIS]); @@ -9370,11 +9242,11 @@ inline void gcode_M503() { #if ENABLED(SENSORLESS_HOMING) inline void gcode_M914() { #if ENABLED(X_IS_TMC2130) - if (code_seen(axis_codes[X_AXIS])) tmc2130_set_sgt(stepperX, 'X', code_value_int()); + if (parser.seen(axis_codes[X_AXIS])) tmc2130_set_sgt(stepperX, 'X', parser.value_int()); else tmc2130_get_sgt(stepperX, 'X'); #endif #if ENABLED(Y_IS_TMC2130) - if (code_seen(axis_codes[Y_AXIS])) tmc2130_set_sgt(stepperY, 'Y', code_value_int()); + if (parser.seen(axis_codes[Y_AXIS])) tmc2130_set_sgt(stepperY, 'Y', parser.value_int()); else tmc2130_get_sgt(stepperY, 'Y'); #endif } @@ -9387,32 +9259,32 @@ inline void gcode_M503() { */ inline void gcode_M907() { #if HAS_DIGIPOTSS - LOOP_XYZE(i) if (code_seen(axis_codes[i])) stepper.digipot_current(i, code_value_int()); - if (code_seen('B')) stepper.digipot_current(4, code_value_int()); - if (code_seen('S')) for (uint8_t i = 0; i <= 4; i++) stepper.digipot_current(i, code_value_int()); + LOOP_XYZE(i) if (parser.seen(axis_codes[i])) stepper.digipot_current(i, parser.value_int()); + if (parser.seen('B')) stepper.digipot_current(4, parser.value_int()); + if (parser.seen('S')) for (uint8_t i = 0; i <= 4; i++) stepper.digipot_current(i, parser.value_int()); #elif HAS_MOTOR_CURRENT_PWM #if PIN_EXISTS(MOTOR_CURRENT_PWM_XY) - if (code_seen('X')) stepper.digipot_current(0, code_value_int()); + if (parser.seen('X')) stepper.digipot_current(0, parser.value_int()); #endif #if PIN_EXISTS(MOTOR_CURRENT_PWM_Z) - if (code_seen('Z')) stepper.digipot_current(1, code_value_int()); + if (parser.seen('Z')) stepper.digipot_current(1, parser.value_int()); #endif #if PIN_EXISTS(MOTOR_CURRENT_PWM_E) - if (code_seen('E')) stepper.digipot_current(2, code_value_int()); + if (parser.seen('E')) stepper.digipot_current(2, parser.value_int()); #endif #endif #if ENABLED(DIGIPOT_I2C) // this one uses actual amps in floating point - LOOP_XYZE(i) if (code_seen(axis_codes[i])) digipot_i2c_set_current(i, code_value_float()); + LOOP_XYZE(i) if (parser.seen(axis_codes[i])) digipot_i2c_set_current(i, parser.value_float()); // for each additional extruder (named B,C,D,E..., channels 4,5,6,7...) - for (uint8_t i = NUM_AXIS; i < DIGIPOT_I2C_NUM_CHANNELS; i++) if (code_seen('B' + i - (NUM_AXIS))) digipot_i2c_set_current(i, code_value_float()); + for (uint8_t i = NUM_AXIS; i < DIGIPOT_I2C_NUM_CHANNELS; i++) if (parser.seen('B' + i - (NUM_AXIS))) digipot_i2c_set_current(i, parser.value_float()); #endif #if ENABLED(DAC_STEPPER_CURRENT) - if (code_seen('S')) { - const float dac_percent = code_value_float(); + if (parser.seen('S')) { + const float dac_percent = parser.value_float(); for (uint8_t i = 0; i <= 4; i++) dac_current_percent(i, dac_percent); } - LOOP_XYZE(i) if (code_seen(axis_codes[i])) dac_current_percent(i, code_value_float()); + LOOP_XYZE(i) if (parser.seen(axis_codes[i])) dac_current_percent(i, parser.value_float()); #endif } @@ -9424,14 +9296,14 @@ inline void gcode_M907() { inline void gcode_M908() { #if HAS_DIGIPOTSS stepper.digitalPotWrite( - code_seen('P') ? code_value_int() : 0, - code_seen('S') ? code_value_int() : 0 + parser.seen('P') ? parser.value_int() : 0, + parser.seen('S') ? parser.value_int() : 0 ); #endif #ifdef DAC_STEPPER_CURRENT dac_current_raw( - code_seen('P') ? code_value_byte() : -1, - code_seen('S') ? code_value_ushort() : 0 + parser.seen('P') ? parser.value_byte() : -1, + parser.seen('S') ? parser.value_ushort() : 0 ); #endif } @@ -9450,9 +9322,9 @@ inline void gcode_M907() { // M350 Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers. inline void gcode_M350() { - if (code_seen('S')) for (int i = 0; i <= 4; i++) stepper.microstep_mode(i, code_value_byte()); - LOOP_XYZE(i) if (code_seen(axis_codes[i])) stepper.microstep_mode(i, code_value_byte()); - if (code_seen('B')) stepper.microstep_mode(4, code_value_byte()); + if (parser.seen('S')) for (int i = 0; i <= 4; i++) stepper.microstep_mode(i, parser.value_byte()); + LOOP_XYZE(i) if (parser.seen(axis_codes[i])) stepper.microstep_mode(i, parser.value_byte()); + if (parser.seen('B')) stepper.microstep_mode(4, parser.value_byte()); stepper.microstep_readings(); } @@ -9461,14 +9333,14 @@ inline void gcode_M907() { * S# determines MS1 or MS2, X# sets the pin high/low. */ inline void gcode_M351() { - if (code_seen('S')) switch (code_value_byte()) { + if (parser.seen('S')) switch (parser.value_byte()) { case 1: - LOOP_XYZE(i) if (code_seen(axis_codes[i])) stepper.microstep_ms(i, code_value_byte(), -1); - if (code_seen('B')) stepper.microstep_ms(4, code_value_byte(), -1); + LOOP_XYZE(i) if (parser.seen(axis_codes[i])) stepper.microstep_ms(i, parser.value_byte(), -1); + if (parser.seen('B')) stepper.microstep_ms(4, parser.value_byte(), -1); break; case 2: - LOOP_XYZE(i) if (code_seen(axis_codes[i])) stepper.microstep_ms(i, -1, code_value_byte()); - if (code_seen('B')) stepper.microstep_ms(4, -1, code_value_byte()); + LOOP_XYZE(i) if (parser.seen(axis_codes[i])) stepper.microstep_ms(i, -1, parser.value_byte()); + if (parser.seen('B')) stepper.microstep_ms(4, -1, parser.value_byte()); break; } stepper.microstep_readings(); @@ -9495,8 +9367,8 @@ inline void gcode_M907() { */ inline void gcode_M355() { #if HAS_CASE_LIGHT - if (code_seen('P')) case_light_brightness = code_value_byte(); - if (code_seen('S')) case_light_on = code_value_bool(); + if (parser.seen('P')) case_light_brightness = parser.value_byte(); + if (parser.seen('S')) case_light_on = parser.value_bool(); update_case_light(); SERIAL_ECHO_START; SERIAL_ECHOPGM("Case lights "); @@ -9518,9 +9390,9 @@ inline void gcode_M355() { * */ inline void gcode_M163() { - const int mix_index = code_seen('S') ? code_value_int() : 0; + const int mix_index = parser.seen('S') ? parser.value_int() : 0; if (mix_index < MIXING_STEPPERS) { - float mix_value = code_seen('P') ? code_value_float() : 0.0; + float mix_value = parser.seen('P') ? parser.value_float() : 0.0; NOLESS(mix_value, 0.0); mixing_factor[mix_index] = RECIPROCAL(mix_value); } @@ -9535,7 +9407,7 @@ inline void gcode_M355() { * */ inline void gcode_M164() { - const int tool_index = code_seen('S') ? code_value_int() : 0; + const int tool_index = parser.seen('S') ? parser.value_int() : 0; if (tool_index < MIXING_VIRTUAL_TOOLS) { normalize_mix(); for (uint8_t i = 0; i < MIXING_STEPPERS; i++) @@ -9578,7 +9450,7 @@ inline void gcode_M999() { Running = true; lcd_reset_alert_level(); - if (code_seen('S') && code_value_bool()) return; + if (parser.seen('S') && parser.value_bool()) return; // gcode_LastN = Stopped_gcode_LastN; FlushSerialRequestResend(); @@ -9953,8 +9825,8 @@ inline void gcode_T(uint8_t tmp_extruder) { tool_change( tmp_extruder, - code_seen('F') ? MMM_TO_MMS(code_value_linear_units()) : 0.0, - (tmp_extruder == active_extruder) || (code_seen('S') && code_value_bool()) + parser.seen('F') ? MMM_TO_MMS(parser.value_linear_units()) : 0.0, + (tmp_extruder == active_extruder) || (parser.seen('S') && parser.value_bool()) ); #endif @@ -9972,7 +9844,7 @@ inline void gcode_T(uint8_t tmp_extruder) { * This is called from the main loop() */ void process_next_command() { - current_command = command_queue[cmd_queue_index_r]; + char * const current_command = command_queue[cmd_queue_index_r]; if (DEBUGGING(ECHO)) { SERIAL_ECHO_START; @@ -9983,70 +9855,20 @@ void process_next_command() { #endif } - // Sanitize the current command: - // - Skip leading spaces - // - Bypass N[-0-9][0-9]*[ ]* - // - Overwrite * with nul to mark the end - while (*current_command == ' ') ++current_command; - if (*current_command == 'N' && NUMERIC_SIGNED(current_command[1])) { - current_command += 2; // skip N[-0-9] - while (NUMERIC(*current_command)) ++current_command; // skip [0-9]* - while (*current_command == ' ') ++current_command; // skip [ ]* - } - char* starpos = strchr(current_command, '*'); // * should always be the last parameter - if (starpos) while (*starpos == ' ' || *starpos == '*') *starpos-- = '\0'; // nullify '*' and ' ' - - char *cmd_ptr = current_command; - - // Get the command code, which must be G, M, or T - char command_code = *cmd_ptr++; - - // Skip spaces to get the numeric part - while (*cmd_ptr == ' ') cmd_ptr++; - - // Allow for decimal point in command - #if ENABLED(G38_PROBE_TARGET) - uint8_t subcode = 0; - #endif - - uint16_t codenum = 0; // define ahead of goto - - // Bail early if there's no code - bool code_is_good = NUMERIC(*cmd_ptr); - if (!code_is_good) goto ExitUnknownCommand; - - // Get and skip the code number - do { - codenum = (codenum * 10) + (*cmd_ptr - '0'); - cmd_ptr++; - } while (NUMERIC(*cmd_ptr)); - - // Allow for decimal point in command - #if ENABLED(G38_PROBE_TARGET) - if (*cmd_ptr == '.') { - cmd_ptr++; - while (NUMERIC(*cmd_ptr)) - subcode = (subcode * 10) + (*cmd_ptr++ - '0'); - } - #endif - - // Skip all spaces to get to the first argument, or nul - while (*cmd_ptr == ' ') cmd_ptr++; - - // The command's arguments (if any) start here, for sure! - current_command_args = cmd_ptr; - KEEPALIVE_STATE(IN_HANDLER); + // Parse the next command in the queue + parser.parse(current_command); + // Handle a known G, M, or T - switch (command_code) { - case 'G': switch (codenum) { + switch (parser.command_letter) { + case 'G': switch (parser.codenum) { // G0, G1 case 0: case 1: #if IS_SCARA - gcode_G0_G1(codenum == 0); + gcode_G0_G1(parser.codenum == 0); #else gcode_G0_G1(); #endif @@ -10056,7 +9878,7 @@ void process_next_command() { #if ENABLED(ARC_SUPPORT) && DISABLED(SCARA) case 2: // G2 - CW ARC case 3: // G3 - CCW ARC - gcode_G2_G3(codenum == 2); + gcode_G2_G3(parser.codenum == 2); break; #endif @@ -10075,7 +9897,7 @@ void process_next_command() { #if ENABLED(FWRETRACT) case 10: // G10: retract case 11: // G11: retract_recover - gcode_G10_G11(codenum == 10); + gcode_G10_G11(parser.codenum == 10); break; #endif // FWRETRACT @@ -10170,10 +9992,15 @@ void process_next_command() { break; #endif + #if ENABLED(DEBUG_GCODE_PARSER) + case 800: + parser.debug(); // GCode Parser Test for G + break; + #endif } break; - case 'M': switch (codenum) { + case 'M': switch (parser.codenum) { #if HAS_RESUME_CONTINUE case 0: // M0: Unconditional stop - Wait for user button press on LCD case 1: // M1: Conditional stop - Wait for user button press on LCD @@ -10764,6 +10591,12 @@ void process_next_command() { gcode_M355(); break; + #if ENABLED(DEBUG_GCODE_PARSER) + case 800: + parser.debug(); // GCode Parser Test for M + break; + #endif + case 999: // M999: Restart after being Stopped gcode_M999(); break; @@ -10771,19 +10604,14 @@ void process_next_command() { break; case 'T': - gcode_T(codenum); + gcode_T(parser.codenum); break; - default: code_is_good = false; + default: parser.unknown_command_error(); } KEEPALIVE_STATE(NOT_BUSY); -ExitUnknownCommand: - - // Still unknown command? Throw an error - if (!code_is_good) unknown_command_error(); - ok_to_send(); } @@ -12163,7 +11991,7 @@ void manage_inactivity(bool ignore_stepper_queue/*=false*/) { if (max_inactive_time && ELAPSED(ms, previous_cmd_ms + max_inactive_time)) { SERIAL_ERROR_START; - SERIAL_ECHOLNPAIR(MSG_KILL_INACTIVE_TIME, current_command); + SERIAL_ECHOLNPAIR(MSG_KILL_INACTIVE_TIME, parser.command_ptr); kill(PSTR(MSG_KILLED)); } diff --git a/Marlin/configuration_store.cpp b/Marlin/configuration_store.cpp index 85780fbc3..f23ee7770 100644 --- a/Marlin/configuration_store.cpp +++ b/Marlin/configuration_store.cpp @@ -178,6 +178,10 @@ MarlinSettings settings; #include "temperature.h" #include "ultralcd.h" +#if ENABLED(INCH_MODE_SUPPORT) || (ENABLED(ULTIPANEL) && ENABLED(TEMPERATURE_UNITS_SUPPORT)) + #include "gcode.h" +#endif + #if ENABLED(MESH_BED_LEVELING) #include "mesh_bed_leveling.h" #endif @@ -1331,13 +1335,12 @@ void MarlinSettings::reset() { */ CONFIG_ECHO_START; #if ENABLED(INCH_MODE_SUPPORT) - extern float linear_unit_factor, volumetric_unit_factor; - #define LINEAR_UNIT(N) ((N) / linear_unit_factor) - #define VOLUMETRIC_UNIT(N) ((N) / (volumetric_enabled ? volumetric_unit_factor : linear_unit_factor)) + #define LINEAR_UNIT(N) ((N) / parser.linear_unit_factor) + #define VOLUMETRIC_UNIT(N) ((N) / (volumetric_enabled ? parser.volumetric_unit_factor : parser.linear_unit_factor)) SERIAL_ECHOPGM(" G2"); - SERIAL_CHAR(linear_unit_factor == 1.0 ? '1' : '0'); + SERIAL_CHAR(parser.linear_unit_factor == 1.0 ? '1' : '0'); SERIAL_ECHOPGM(" ; Units in "); - serialprintPGM(linear_unit_factor == 1.0 ? PSTR("mm\n") : PSTR("inches\n")); + serialprintPGM(parser.linear_unit_factor == 1.0 ? PSTR("mm\n") : PSTR("inches\n")); #else #define LINEAR_UNIT(N) N #define VOLUMETRIC_UNIT(N) N @@ -1351,13 +1354,11 @@ void MarlinSettings::reset() { CONFIG_ECHO_START; #if ENABLED(TEMPERATURE_UNITS_SUPPORT) - extern TempUnit input_temp_units; - extern float to_temp_units(const float &f); - #define TEMP_UNIT(N) to_temp_units(N) + #define TEMP_UNIT(N) parser.to_temp_units(N) SERIAL_ECHOPGM(" M149 "); - SERIAL_CHAR(input_temp_units == TEMPUNIT_K ? 'K' : input_temp_units == TEMPUNIT_F ? 'F' : 'C'); + SERIAL_CHAR(parser.temp_units_code()); SERIAL_ECHOPGM(" ; Units in "); - serialprintPGM(input_temp_units == TEMPUNIT_K ? PSTR("Kelvin\n") : input_temp_units == TEMPUNIT_F ? PSTR("Fahrenheit\n") : PSTR("Celsius\n")); + serialprintPGM(parser.temp_units_name()); #else #define TEMP_UNIT(N) N SERIAL_ECHOLNPGM(" M149 C ; Units in Celsius\n"); diff --git a/Marlin/gcode.cpp b/Marlin/gcode.cpp new file mode 100644 index 000000000..caceb09bd --- /dev/null +++ b/Marlin/gcode.cpp @@ -0,0 +1,279 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (C) 2016 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 . + * + */ + +/** + * gcode.cpp - Parser for a GCode line, providing a parameter interface. + */ + +#include "gcode.h" + +#include "Marlin.h" +#include "language.h" + +// Must be declared for allocation and to satisfy the linker +// Zero values need no initialization. + +#if ENABLED(INCH_MODE_SUPPORT) + float GCodeParser::linear_unit_factor, GCodeParser::volumetric_unit_factor; +#endif + +#if ENABLED(TEMPERATURE_UNITS_SUPPORT) + TempUnit GCodeParser::input_temp_units; +#endif + +char *GCodeParser::command_ptr, + *GCodeParser::string_arg, + *GCodeParser::value_ptr; +char GCodeParser::command_letter; +int GCodeParser::codenum; +#if USE_GCODE_SUBCODES + int GCodeParser::subcode; +#endif + +#if ENABLED(FASTER_GCODE_PARSER) + // Optimized Parameters + byte GCodeParser::codebits[4]; // found bits + uint8_t GCodeParser::param[26]; // parameter offsets from command_ptr +#else + char *GCodeParser::command_args; // start of parameters +#endif + +// Create a global instance of the GCode parser singleton +GCodeParser parser; + +/** + * Clear all code-seen (and value pointers) + * + * Since each param is set/cleared on seen codes, + * this may be optimized by commenting out ZERO(param) + */ +void GCodeParser::reset() { + string_arg = NULL; // No whole line argument + command_letter = '?'; // No command letter + codenum = 0; // No command code + #if USE_GCODE_SUBCODES + subcode = 0; // No command sub-code + #endif + #if ENABLED(FASTER_GCODE_PARSER) + ZERO(codebits); // No codes yet + //ZERO(param); // No parameters (should be safe to comment out this line) + #endif +} + +// Populate all fields by parsing a single line of GCode +// 58 bytes of SRAM are used to speed up seen/value +void GCodeParser::parse(char *p) { + + reset(); // No codes to report + + // Skip spaces + while (*p == ' ') ++p; + + // Skip N[-0-9] if included in the command line + if (*p == 'N' && NUMERIC_SIGNED(p[1])) { + #if ENABLED(FASTER_GCODE_PARSER) + //set('N', p + 1); // (optional) Set the 'N' parameter value + #endif + p += 2; // skip N[-0-9] + while (NUMERIC(*p)) ++p; // skip [0-9]* + while (*p == ' ') ++p; // skip [ ]* + } + + // *p now points to the current command, which should be G, M, or T + command_ptr = p; + + // Get the command letter, which must be G, M, or T + const char letter = *p++; + + // Nullify asterisk and trailing whitespace + char *starpos = strchr(p, '*'); + if (starpos) { + --starpos; // * + while (*starpos == ' ') --starpos; // spaces... + starpos[1] = '\0'; + } + + // Bail if the letter is not G, M, or T + switch (letter) { case 'G': case 'M': case 'T': break; default: return; } + + // Skip spaces to get the numeric part + while (*p == ' ') p++; + + // Bail if there's no command code number + if (!NUMERIC(*p)) return; + + // Save the command letter at this point + // A '?' signifies an unknown command + command_letter = letter; + + // Get the code number - integer digits only + codenum = 0; + do { + codenum *= 10, codenum += *p++ - '0'; + } while (NUMERIC(*p)); + + // Allow for decimal point in command + #if USE_GCODE_SUBCODES + if (*p == '.') { + p++; + while (NUMERIC(*p)) + subcode *= 10, subcode += *p++ - '0'; + } + #endif + + // Skip all spaces to get to the first argument, or nul + while (*p == ' ') p++; + + // The command parameters (if any) start here, for sure! + + #if DISABLED(FASTER_GCODE_PARSER) + command_args = p; // Scan for parameters in seen() + #endif + + // Only use string_arg for these M codes + if (letter == 'M') switch (codenum) { case 23: case 28: case 30: case 117: case 928: string_arg = p; return; default: break; } + + #if ENABLED(DEBUG_GCODE_PARSER) + const bool debug = codenum == 800; + #endif + + /** + * Find all parameters, set flags and pointers for fast parsing + * + * Most codes ignore 'string_arg', but those that want a string will get the right pointer. + * The following loop assigns the first "parameter" having no numeric value to 'string_arg'. + * This allows M0/M1 with expire time to work: "M0 S5 You Win!" + */ + string_arg = NULL; + while (char code = *p++) { // Get the next parameter. A NUL ends the loop + + // Special handling for M32 [P] !/path/to/file.g# + // The path must be the last parameter + if (code == '!' && letter == 'M' && codenum == 32) { + string_arg = p; // Name starts after '!' + char * const lb = strchr(p, '#'); // Already seen '#' as SD char (to pause buffering) + if (lb) *lb = '\0'; // Safe to mark the end of the filename + return; + } + + // Arguments MUST be uppercase for fast GCode parsing + #if ENABLED(FASTER_GCODE_PARSER) + #define PARAM_TEST WITHIN(code, 'A', 'Z') + #else + #define PARAM_TEST true + #endif + + if (PARAM_TEST) { + + const bool has_num = DECIMAL_SIGNED(*p); // The parameter has a number [-+0-9.] + + #if ENABLED(DEBUG_GCODE_PARSER) + if (debug) { + SERIAL_ECHOPAIR("Got letter ", code); // DEBUG + SERIAL_ECHOPAIR(" at index ", (int)(p - command_ptr - 1)); // DEBUG + if (has_num) SERIAL_ECHOPGM(" (has_num)"); + } + #endif + + if (!has_num && !string_arg) { // No value? First time, keep as string_arg + string_arg = p - 1; + #if ENABLED(DEBUG_GCODE_PARSER) + if (debug) SERIAL_ECHOPAIR(" string_arg: ", hex_address((void*)string_arg)); // DEBUG + #endif + } + + #if ENABLED(DEBUG_GCODE_PARSER) + if (debug) SERIAL_EOL; + #endif + + #if ENABLED(FASTER_GCODE_PARSER) + set(code, has_num ? p : NULL // Set parameter exists and pointer (NULL for no number) + #if ENABLED(DEBUG_GCODE_PARSER) + , debug + #endif + ); + #endif + } + else if (!string_arg) { // Not A-Z? First time, keep as the string_arg + string_arg = p - 1; + #if ENABLED(DEBUG_GCODE_PARSER) + if (debug) SERIAL_ECHOPAIR(" string_arg: ", hex_address((void*)string_arg)); // DEBUG + #endif + } + + while (*p && *p != ' ') p++; // Skip over the parameter + while (*p == ' ') p++; // Skip over all spaces + } +} + +void GCodeParser::unknown_command_error() { + SERIAL_ECHO_START; + SERIAL_ECHOPAIR(MSG_UNKNOWN_COMMAND, command_ptr); + SERIAL_CHAR('"'); + SERIAL_EOL; +} + +#if ENABLED(DEBUG_GCODE_PARSER) + + void GCodeParser::debug() { + SERIAL_ECHOPAIR("Command: ", command_ptr); + SERIAL_ECHOPAIR(" (", command_letter); + SERIAL_ECHO(codenum); + SERIAL_ECHOLNPGM(")"); + #if ENABLED(FASTER_GCODE_PARSER) + SERIAL_ECHO(" args: \""); + for (char c = 'A'; c <= 'Z'; ++c) + if (seen(c)) { SERIAL_CHAR(c); SERIAL_CHAR(' '); } + #else + SERIAL_ECHOPAIR(" args: \"", command_args); + #endif + SERIAL_ECHOPGM("\""); + if (string_arg) { + SERIAL_ECHOPGM(" string: \""); + SERIAL_ECHO(string_arg); + SERIAL_CHAR('"'); + } + SERIAL_ECHOPGM("\n\n"); + for (char c = 'A'; c <= 'Z'; ++c) { + if (seen(c)) { + SERIAL_ECHOPAIR("Code '", c); SERIAL_ECHOPGM("':"); + if (has_value()) { + SERIAL_ECHOPAIR("\n float: ", value_float()); + SERIAL_ECHOPAIR("\n long: ", value_long()); + SERIAL_ECHOPAIR("\n ulong: ", value_ulong()); + SERIAL_ECHOPAIR("\n millis: ", value_millis()); + SERIAL_ECHOPAIR("\n sec-ms: ", value_millis_from_seconds()); + SERIAL_ECHOPAIR("\n int: ", value_int()); + SERIAL_ECHOPAIR("\n ushort: ", value_ushort()); + SERIAL_ECHOPAIR("\n byte: ", (int)value_byte()); + SERIAL_ECHOPAIR("\n bool: ", (int)value_bool()); + SERIAL_ECHOPAIR("\n linear: ", value_linear_units()); + SERIAL_ECHOPAIR("\n celsius: ", value_celsius()); + } + else + SERIAL_ECHOPGM(" (no value)"); + SERIAL_ECHOPGM("\n\n"); + } + } + } + +#endif // DEBUG_GCODE_PARSER diff --git a/Marlin/gcode.h b/Marlin/gcode.h new file mode 100644 index 000000000..8348f5646 --- /dev/null +++ b/Marlin/gcode.h @@ -0,0 +1,285 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (C) 2016 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 . + * + */ + +/** + * gcode.h - Parser for a GCode line, providing a parameter interface. + * Codes like M149 control the way the GCode parser behaves, + * so settings for these codes are located in this class. + */ + +#ifndef GCODE_H +#define GCODE_H + +#include "enum.h" +#include "types.h" +#include "MarlinConfig.h" + +//#define DEBUG_GCODE_PARSER + +#if ENABLED(DEBUG_GCODE_PARSER) + #include "hex_print_routines.h" + #include "serial.h" +#endif + +#if ENABLED(INCH_MODE_SUPPORT) + extern bool volumetric_enabled; +#endif + +/** + * GCode parser + * + * - Parse a single gcode line for its letter, code, subcode, and parameters + * - FASTER_GCODE_PARSER: + * - Flags existing params (1 bit each) + * - Stores value offsets (1 byte each) + * - Provide accessors for parameters: + * - Parameter exists + * - Parameter has value + * - Parameter value in different units and types + */ +class GCodeParser { + +private: + static char *value_ptr; // Set by seen, used to fetch the value + + #if ENABLED(FASTER_GCODE_PARSER) + static byte codebits[4]; // Parameters pre-scanned + static uint8_t param[26]; // For A-Z, offsets into command args + #else + static char *command_args; // Args start here, for slow scan + #endif + +public: + + // Global states for GCode-level units features + + #if ENABLED(INCH_MODE_SUPPORT) + static float linear_unit_factor, volumetric_unit_factor; + #endif + + #if ENABLED(TEMPERATURE_UNITS_SUPPORT) + static TempUnit input_temp_units; + #endif + + // Command line state + static char *command_ptr, // The command, so it can be echoed + *string_arg; // string of command line + + static char command_letter; // G, M, or T + static int codenum; // 123 + #if USE_GCODE_SUBCODES + static int subcode; // .1 + #endif + + #if ENABLED(DEBUG_GCODE_PARSER) + void debug(); + #endif + + // Reset is done before parsing + static void reset(); + + #if ENABLED(FASTER_GCODE_PARSER) + + // Set the flag and pointer for a parameter + static void set(const char c, char * const ptr + #if ENABLED(DEBUG_GCODE_PARSER) + , const bool debug=false + #endif + ) { + const uint8_t ind = c - 'A'; + if (ind >= COUNT(param)) return; // Only A-Z + SBI(codebits[ind >> 3], ind & 0x7); // parameter exists + param[ind] = ptr ? ptr - command_ptr : 0; // parameter offset or 0 + #if ENABLED(DEBUG_GCODE_PARSER) + if (debug) { + SERIAL_ECHOPAIR("Set bit ", (int)(ind & 0x7)); + SERIAL_ECHOPAIR(" of index ", (int)(ind >> 3)); + SERIAL_ECHOLNPAIR(" | param = ", hex_address((void*)param[ind])); + } + #endif + } + + // Code seen bit was set. If not found, value_ptr is unchanged. + // This allows "if (seen('A')||seen('B'))" to use the last-found value. + static bool seen(const char c) { + const uint8_t ind = c - 'A'; + if (ind >= COUNT(param)) return false; // Only A-Z + const bool b = TEST(codebits[ind >> 3], ind & 0x7); + if (b) value_ptr = command_ptr + param[ind]; + return b; + } + + #else + + // Code is found in the string. If not found, value_ptr is unchanged. + // This allows "if (seen('A')||seen('B'))" to use the last-found value. + static bool seen(const char c) { + char *p = strchr(command_args, c); + const bool b = !!p; + if (b) value_ptr = DECIMAL_SIGNED(*p) ? p + 1 : NULL; + return b; + } + + #endif // FASTER_GCODE_PARSER + + // Populate all fields by parsing a single line of GCode + // This uses 54 bytes of SRAM to speed up seen/value + static void parse(char * p); + + // Code value pointer was set + FORCE_INLINE static bool has_value() { return value_ptr != NULL; } + + // Float removes 'E' to prevent scientific notation interpretation + inline static float value_float() { + if (value_ptr) { + char *e = value_ptr; + for (;;) { + const char c = *e; + if (c == '\0' || c == ' ') break; + if (c == 'E' || c == 'e') { + *e = '\0'; + const float ret = strtod(value_ptr, NULL); + *e = c; + return ret; + } + ++e; + } + return strtod(value_ptr, NULL); + } + return 0.0; + } + + // Code value as a long or ulong + inline static long value_long() { return value_ptr ? strtol(value_ptr, NULL, 10) : 0L; } + inline unsigned static long value_ulong() { return value_ptr ? strtoul(value_ptr, NULL, 10) : 0UL; } + + // Code value for use as time + FORCE_INLINE static millis_t value_millis() { return value_ulong(); } + FORCE_INLINE static millis_t value_millis_from_seconds() { return value_float() * 1000UL; } + + // Reduce to fewer bits + FORCE_INLINE static int value_int() { return (int)value_long(); } + FORCE_INLINE uint16_t value_ushort() { return (uint16_t)value_long(); } + inline static uint8_t value_byte() { return (uint8_t)(constrain(value_long(), 0, 255)); } + + // Bool is true with no value or non-zero + inline static bool value_bool() { return !has_value() || value_byte(); } + + // Units modes: Inches, Fahrenheit, Kelvin + + #if ENABLED(INCH_MODE_SUPPORT) + + inline static void set_input_linear_units(LinearUnit units) { + switch (units) { + case LINEARUNIT_INCH: + linear_unit_factor = 25.4; + break; + case LINEARUNIT_MM: + default: + linear_unit_factor = 1.0; + break; + } + volumetric_unit_factor = pow(linear_unit_factor, 3.0); + } + + inline static float axis_unit_factor(const AxisEnum axis) { + return (axis >= E_AXIS && volumetric_enabled ? volumetric_unit_factor : linear_unit_factor); + } + + inline static float value_linear_units() { return value_float() * linear_unit_factor; } + inline static float value_axis_units(const AxisEnum axis) { return value_float() * axis_unit_factor(axis); } + inline static float value_per_axis_unit(const AxisEnum axis) { return value_float() / axis_unit_factor(axis); } + + #else + + FORCE_INLINE static float value_linear_units() { return value_float(); } + FORCE_INLINE static float value_axis_units(const AxisEnum a) { UNUSED(a); return value_float(); } + FORCE_INLINE static float value_per_axis_unit(const AxisEnum a) { UNUSED(a); return value_float(); } + + #endif + + #if ENABLED(TEMPERATURE_UNITS_SUPPORT) + + inline static void set_input_temp_units(TempUnit units) { input_temp_units = units; } + + #if ENABLED(ULTIPANEL) && DISABLED(DISABLE_M503) + + FORCE_INLINE static char temp_units_code() { + return input_temp_units == TEMPUNIT_K ? 'K' : input_temp_units == TEMPUNIT_F ? 'F' : 'C'; + } + FORCE_INLINE static char* temp_units_name() { + return input_temp_units == TEMPUNIT_K ? PSTR("Kelvin") : input_temp_units == TEMPUNIT_F ? PSTR("Fahrenheit") : PSTR("Celsius") + } + inline static float to_temp_units(const float &f) { + switch (input_temp_units) { + case TEMPUNIT_F: + return f * 0.5555555556 + 32.0; + case TEMPUNIT_K: + return f + 273.15; + case TEMPUNIT_C: + default: + return f; + } + } + + #endif // ULTIPANEL && !DISABLE_M503 + + inline static float value_celsius() { + const float f = value_float(); + switch (input_temp_units) { + case TEMPUNIT_F: + return (f - 32.0) * 0.5555555556; + case TEMPUNIT_K: + return f - 273.15; + case TEMPUNIT_C: + default: + return f; + } + } + + inline static float value_celsius_diff() { + switch (input_temp_units) { + case TEMPUNIT_F: + return value_float() * 0.5555555556; + case TEMPUNIT_C: + case TEMPUNIT_K: + default: + return value_float(); + } + } + + #else + + FORCE_INLINE static float value_celsius() { return value_float(); } + FORCE_INLINE static float value_celsius_diff() { return value_float(); } + + #endif + + FORCE_INLINE static float value_feedrate() { return value_linear_units(); } + + void unknown_command_error(); + +}; + +extern GCodeParser parser; + +#endif // GCODE_H diff --git a/Marlin/hex_print_routines.cpp b/Marlin/hex_print_routines.cpp index 39e5b4cd7..65b97fc18 100644 --- a/Marlin/hex_print_routines.cpp +++ b/Marlin/hex_print_routines.cpp @@ -20,7 +20,9 @@ * */ #include "Marlin.h" -#if ENABLED(AUTO_BED_LEVELING_UBL) || ENABLED(M100_FREE_MEMORY_WATCHER) +#include "gcode.h" + +#if ENABLED(AUTO_BED_LEVELING_UBL) || ENABLED(M100_FREE_MEMORY_WATCHER) || ENABLED(DEBUG_GCODE_PARSER) #include "hex_print_routines.h" @@ -50,4 +52,4 @@ void print_hex_byte(const uint8_t b) { SERIAL_ECHO(hex_byte(b)); } void print_hex_word(const uint16_t w) { SERIAL_ECHO(hex_word(w)); } void print_hex_address(const void * const w) { SERIAL_ECHO(hex_address(w)); } -#endif // AUTO_BED_LEVELING_UBL || M100_FREE_MEMORY_WATCHER +#endif // AUTO_BED_LEVELING_UBL || M100_FREE_MEMORY_WATCHER || DEBUG_GCODE_PARSER diff --git a/Marlin/hex_print_routines.h b/Marlin/hex_print_routines.h index ea4073331..1ca61e311 100644 --- a/Marlin/hex_print_routines.h +++ b/Marlin/hex_print_routines.h @@ -24,8 +24,9 @@ #define HEX_PRINT_ROUTINES_H #include "MarlinConfig.h" +#include "gcode.h" -#if ENABLED(AUTO_BED_LEVELING_UBL) || ENABLED(M100_FREE_MEMORY_WATCHER) +#if ENABLED(AUTO_BED_LEVELING_UBL) || ENABLED(M100_FREE_MEMORY_WATCHER) || ENABLED(DEBUG_GCODE_PARSER) // // Utility functions to create and print hex strings as nybble, byte, and word. @@ -43,5 +44,5 @@ void print_hex_byte(const uint8_t b); void print_hex_word(const uint16_t w); void print_hex_address(const void * const w); -#endif // AUTO_BED_LEVELING_UBL || M100_FREE_MEMORY_WATCHER +#endif // AUTO_BED_LEVELING_UBL || M100_FREE_MEMORY_WATCHER || DEBUG_GCODE_PARSER #endif // HEX_PRINT_ROUTINES_H diff --git a/Marlin/macros.h b/Marlin/macros.h index e7283f867..0fb057441 100644 --- a/Marlin/macros.h +++ b/Marlin/macros.h @@ -124,7 +124,9 @@ #define WITHIN(V,L,H) ((V) >= (L) && (V) <= (H)) #define NUMERIC(a) WITHIN(a, '0', '9') -#define NUMERIC_SIGNED(a) (NUMERIC(a) || (a) == '-') +#define DECIMAL(a) (NUMERIC(a) || a == '.') +#define NUMERIC_SIGNED(a) (NUMERIC(a) || (a) == '-' || (a) == '+') +#define DECIMAL_SIGNED(a) (DECIMAL(a) || (a) == '-' || (a) == '+') #define COUNT(a) (sizeof(a)/sizeof(*a)) #define ZERO(a) memset(a,0,sizeof(a)) #define COPY(a,b) memcpy(a,b,min(sizeof(a),sizeof(b))) diff --git a/Marlin/planner.cpp b/Marlin/planner.cpp index 155a4717f..44b1a36f4 100644 --- a/Marlin/planner.cpp +++ b/Marlin/planner.cpp @@ -64,6 +64,7 @@ #include "ultralcd.h" #include "language.h" #include "ubl.h" +#include "gcode.h" #include "Marlin.h" @@ -1549,10 +1550,10 @@ void Planner::refresh_positioning() { #if ENABLED(AUTOTEMP) void Planner::autotemp_M104_M109() { - autotemp_enabled = code_seen('F'); - if (autotemp_enabled) autotemp_factor = code_value_temp_diff(); - if (code_seen('S')) autotemp_min = code_value_temp_abs(); - if (code_seen('B')) autotemp_max = code_value_temp_abs(); + autotemp_enabled = parser.seen('F'); + if (autotemp_enabled) autotemp_factor = parser.value_celsius_diff(); + if (parser.seen('S')) autotemp_min = parser.value_celsius(); + if (parser.seen('B')) autotemp_max = parser.value_celsius(); } #endif diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 381ab28ab..c9abfbd5c 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -30,6 +30,7 @@ #include "configuration_store.h" #include "ultralcd.h" #include "stepper.h" + #include "gcode.h" #include #include "least_squares_fit.h" @@ -47,10 +48,6 @@ float lcd_z_offset_edit(); extern float meshedit_done; extern long babysteps_done; - extern float code_value_float(); - extern uint8_t code_value_byte(); - extern bool code_value_bool(); - extern bool code_has_value(); extern float probe_pt(const float &x, const float &y, bool, int); extern bool set_probe_deployed(bool); @@ -322,26 +319,20 @@ return; } - // Check for commands that require the printer to be homed. + // Check for commands that require the printer to be homed if (axis_unhomed_error()) { - if (code_seen('J')) + const int8_t p_val = parser.seen('P') && parser.has_value() ? parser.value_int() : -1; + if (p_val == 1 || p_val == 2 || p_val == 4 || parser.seen('J')) home_all_axes(); - else if (code_seen('P')) { - if (code_has_value()) { - const int p_val = code_value_int(); - if (p_val == 1 || p_val == 2 || p_val == 4) - home_all_axes(); - } - } } if (g29_parameter_parsing()) return; // abort if parsing the simple parameters causes a problem, - // Invalidate Mesh Points. This command is a little bit asymetrical because + // Invalidate Mesh Points. This command is a little bit asymmetrical because // it directly specifies the repetition count and does not use the 'R' parameter. - if (code_seen('I')) { + if (parser.seen('I')) { uint8_t cnt = 0; - g29_repetition_cnt = code_has_value() ? code_value_int() : 1; + g29_repetition_cnt = parser.has_value() ? parser.value_int() : 1; while (g29_repetition_cnt--) { if (cnt > 20) { cnt = 0; idle(); } const mesh_index_pair location = find_closest_mesh_point_of_type(REAL, g29_x_pos, g29_y_pos, USE_NOZZLE_AS_REFERENCE, NULL, false); @@ -355,10 +346,10 @@ SERIAL_PROTOCOLLNPGM("Locations invalidated.\n"); } - if (code_seen('Q')) { - const int test_pattern = code_has_value() ? code_value_int() : -99; + if (parser.seen('Q')) { + const int test_pattern = parser.has_value() ? parser.value_int() : -99; if (!WITHIN(test_pattern, -1, 2)) { - SERIAL_PROTOCOLLNPGM("Invalid test_pattern value. (0-2)\n"); + SERIAL_PROTOCOLLNPGM("Invalid test_pattern value. (-1 to 2)\n"); return; } SERIAL_PROTOCOLLNPGM("Loading test_pattern values.\n"); @@ -385,15 +376,15 @@ // Allow the user to specify the height because 10mm is a little extreme in some cases. for (uint8_t x = (GRID_MAX_POINTS_X) / 3; x < 2 * (GRID_MAX_POINTS_X) / 3; x++) // Create a rectangular raised area in for (uint8_t y = (GRID_MAX_POINTS_Y) / 3; y < 2 * (GRID_MAX_POINTS_Y) / 3; y++) // the center of the bed - z_values[x][y] += code_seen('C') ? g29_constant : 9.99; + z_values[x][y] += parser.seen('C') ? g29_constant : 9.99; break; } } - if (code_seen('J')) { + if (parser.seen('J')) { if (g29_grid_size) { // if not 0 it is a normal n x n grid being probed save_ubl_active_state_and_disable(); - tilt_mesh_based_on_probed_grid(code_seen('T')); + tilt_mesh_based_on_probed_grid(parser.seen('T')); restore_ubl_active_state_and_leave(); } else { // grid_size == 0 : A 3-Point leveling has been requested @@ -425,7 +416,7 @@ } } - if (code_seen('P')) { + if (parser.seen('P')) { if (WITHIN(g29_phase_value, 0, 1) && state.storage_slot == -1) { state.storage_slot = 0; SERIAL_PROTOCOLLNPGM("Default storage slot 0 selected."); @@ -444,7 +435,7 @@ // // Invalidate Entire Mesh and Automatically Probe Mesh in areas that can be reached by the probe // - if (!code_seen('C')) { + if (!parser.seen('C')) { invalidate(); SERIAL_PROTOCOLLNPGM("Mesh invalidated. Probing mesh."); } @@ -455,7 +446,7 @@ SERIAL_PROTOCOLLNPGM(").\n"); } probe_entire_mesh(g29_x_pos + X_PROBE_OFFSET_FROM_EXTRUDER, g29_y_pos + Y_PROBE_OFFSET_FROM_EXTRUDER, - code_seen('T'), code_seen('E'), code_seen('U')); + parser.seen('T'), parser.seen('E'), parser.seen('U')); break; case 2: { @@ -481,30 +472,29 @@ #endif } - if (code_seen('C')) { + if (parser.seen('C')) { g29_x_pos = current_position[X_AXIS]; g29_y_pos = current_position[Y_AXIS]; } float height = Z_CLEARANCE_BETWEEN_PROBES; - if (code_seen('B')) { - g29_card_thickness = code_has_value() ? code_value_float() : measure_business_card_thickness(height); - + if (parser.seen('B')) { + g29_card_thickness = parser.has_value() ? parser.value_float() : measure_business_card_thickness(height); if (fabs(g29_card_thickness) > 1.5) { SERIAL_PROTOCOLLNPGM("?Error in Business Card measurement."); return; } } - if (code_seen('H') && code_has_value()) height = code_value_float(); + if (parser.seen('H') && parser.has_value()) height = parser.value_float(); if (!position_is_reachable_xy(g29_x_pos, g29_y_pos)) { - SERIAL_PROTOCOLLNPGM("(X,Y) outside printable radius."); + SERIAL_PROTOCOLLNPGM("XY outside printable radius."); return; } - manually_probe_remaining_mesh(g29_x_pos, g29_y_pos, height, g29_card_thickness, code_seen('T')); + manually_probe_remaining_mesh(g29_x_pos, g29_y_pos, height, g29_card_thickness, parser.seen('T')); SERIAL_PROTOCOLLNPGM("G29 P2 finished."); } break; @@ -531,7 +521,7 @@ } } } else { - const float cvf = code_value_float(); + const float cvf = parser.value_float(); switch((int)truncf(cvf * 10.0) - 30) { // 3.1 -> 1 #if ENABLED(UBL_G29_P31) case 1: { @@ -561,9 +551,7 @@ // // Fine Tune (i.e., Edit) the Mesh // - - fine_tune_mesh(g29_x_pos, g29_y_pos, code_seen('T')); - + fine_tune_mesh(g29_x_pos, g29_y_pos, parser.seen('T')); break; case 5: find_mean_mesh_height(); break; @@ -576,22 +564,22 @@ // Much of the 'What?' command can be eliminated. But until we are fully debugged, it is // good to have the extra information. Soon... we prune this to just a few items // - if (code_seen('W')) g29_what_command(); + if (parser.seen('W')) g29_what_command(); // // When we are fully debugged, this may go away. But there are some valid // use cases for the users. So we can wait and see what to do with it. // - if (code_seen('K')) // Kompare Current Mesh Data to Specified Stored Mesh + if (parser.seen('K')) // Kompare Current Mesh Data to Specified Stored Mesh g29_compare_current_mesh_to_stored_mesh(); // // Load a Mesh from the EEPROM // - if (code_seen('L')) { // Load Current Mesh Data - g29_storage_slot = code_has_value() ? code_value_int() : state.storage_slot; + if (parser.seen('L')) { // Load Current Mesh Data + g29_storage_slot = parser.has_value() ? parser.value_int() : state.storage_slot; int16_t a = settings.calc_num_meshes(); @@ -616,8 +604,8 @@ // Store a Mesh in the EEPROM // - if (code_seen('S')) { // Store (or Save) Current Mesh Data - g29_storage_slot = code_has_value() ? code_value_int() : state.storage_slot; + if (parser.seen('S')) { // Store (or Save) Current Mesh Data + g29_storage_slot = parser.has_value() ? parser.value_int() : state.storage_slot; if (g29_storage_slot == -1) { // Special case, we are going to 'Export' the mesh to the SERIAL_ECHOLNPGM("G29 I 999"); // host in a form it can be reconstructed on a different machine @@ -654,15 +642,17 @@ SERIAL_PROTOCOLLNPGM("Done."); } - if (code_seen('T')) - display_map(code_has_value() ? code_value_int() : 0); + if (parser.seen('T')) + display_map(parser.has_value() ? parser.value_int() : 0); - /* + /** * This code may not be needed... Prepare for its removal... * - if (code_seen('Z')) { - if (code_has_value()) - state.z_offset = code_value_float(); // do the simple case. Just lock in the specified value + */ + #if 0 + if (parser.seen('Z')) { + if (parser.has_value()) + state.z_offset = parser.value_float(); // do the simple case. Just lock in the specified value else { save_ubl_active_state_and_disable(); //float measured_z = probe_pt(g29_x_pos + X_PROBE_OFFSET_FROM_EXTRUDER, g29_y_pos + Y_PROBE_OFFSET_FROM_EXTRUDER, ProbeDeployAndStow, g29_verbose_level); @@ -712,7 +702,7 @@ restore_ubl_active_state_and_leave(); } } - */ + #endif LEAVE: @@ -1015,10 +1005,7 @@ if (do_ubl_mesh_map) display_map(g29_map_type); // show user where we're probing - if (code_seen('B')) - LCD_MESSAGEPGM("Place shim & measure"); // TODO: Make translatable string - else - LCD_MESSAGEPGM("Measure"); // TODO: Make translatable string + serialprintPGM(parser.seen('B') ? PSTR("Place shim & measure") : PSTR("Measure")); // TODO: Make translatable strings while (ubl_lcd_clicked()) delay(50); // wait for user to release encoder wheel delay(50); // debounce @@ -1073,13 +1060,13 @@ g29_constant = 0.0; g29_repetition_cnt = 0; - g29_x_flag = code_seen('X') && code_has_value(); - g29_x_pos = g29_x_flag ? code_value_float() : current_position[X_AXIS]; - g29_y_flag = code_seen('Y') && code_has_value(); - g29_y_pos = g29_y_flag ? code_value_float() : current_position[Y_AXIS]; + g29_x_flag = parser.seen('X') && parser.has_value(); + g29_x_pos = g29_x_flag ? parser.value_float() : current_position[X_AXIS]; + g29_y_flag = parser.seen('Y') && parser.has_value(); + g29_y_pos = g29_y_flag ? parser.value_float() : current_position[Y_AXIS]; - if (code_seen('R')) { - g29_repetition_cnt = code_has_value() ? code_value_int() : GRID_MAX_POINTS; + if (parser.seen('R')) { + g29_repetition_cnt = parser.has_value() ? parser.value_int() : GRID_MAX_POINTS; NOMORE(g29_repetition_cnt, GRID_MAX_POINTS); if (g29_repetition_cnt < 1) { SERIAL_PROTOCOLLNPGM("?(R)epetition count invalid (1+).\n"); @@ -1087,22 +1074,22 @@ } } - g29_verbose_level = code_seen('V') ? code_value_int() : 0; + g29_verbose_level = parser.seen('V') ? parser.value_int() : 0; if (!WITHIN(g29_verbose_level, 0, 4)) { SERIAL_PROTOCOLLNPGM("?(V)erbose level is implausible (0-4).\n"); err_flag = true; } - if (code_seen('P')) { - g29_phase_value = code_value_int(); + if (parser.seen('P')) { + g29_phase_value = parser.value_int(); if (!WITHIN(g29_phase_value, 0, 6)) { SERIAL_PROTOCOLLNPGM("?(P)hase value invalid (0-6).\n"); err_flag = true; } } - if (code_seen('J')) { - g29_grid_size = code_has_value() ? code_value_int() : 0; + if (parser.seen('J')) { + g29_grid_size = parser.has_value() ? parser.value_int() : 0; if (g29_grid_size && !WITHIN(g29_grid_size, 2, 9)) { SERIAL_PROTOCOLLNPGM("?Invalid grid size (J) specified (2-9).\n"); err_flag = true; @@ -1125,27 +1112,32 @@ if (err_flag) return UBL_ERR; - // Activate or deactivate UBL - if (code_seen('A')) { - if (code_seen('D')) { + /** + * Activate or deactivate UBL + * Note: UBL's G29 restores the state set here when done. + * Leveling is being enabled here with old data, possibly + * none. Error handling should disable for safety... + */ + if (parser.seen('A')) { + if (parser.seen('D')) { SERIAL_PROTOCOLLNPGM("?Can't activate and deactivate at the same time.\n"); return UBL_ERR; } state.active = true; report_state(); } - else if (code_seen('D')) { + else if (parser.seen('D')) { state.active = false; report_state(); } // Set global 'C' flag and its value - if ((g29_c_flag = code_seen('C'))) - g29_constant = code_value_float(); + if ((g29_c_flag = parser.seen('C'))) + g29_constant = parser.value_float(); #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - if (code_seen('F') && code_has_value()) { - const float fh = code_value_float(); + if (parser.seen('F') && parser.has_value()) { + const float fh = parser.value_float(); if (!WITHIN(fh, 0.0, 100.0)) { SERIAL_PROTOCOLLNPGM("?(F)ade height for Bed Level Correction not plausible.\n"); return UBL_ERR; @@ -1154,7 +1146,7 @@ } #endif - g29_map_type = code_seen('T') && code_has_value() ? code_value_int() : 0; + g29_map_type = parser.seen('T') && parser.has_value() ? parser.value_int() : 0; if (!WITHIN(g29_map_type, 0, 1)) { SERIAL_PROTOCOLLNPGM("Invalid map type.\n"); return UBL_ERR; @@ -1319,13 +1311,13 @@ return; } - if (!code_has_value()) { + if (!parser.has_value()) { SERIAL_PROTOCOLLNPGM("?Storage slot # required."); SERIAL_PROTOCOLLNPAIR("?Use 0 to ", a - 1); return; } - g29_storage_slot = code_value_int(); + g29_storage_slot = parser.value_int(); if (!WITHIN(g29_storage_slot, 0, a - 1)) { SERIAL_PROTOCOLLNPGM("?Invalid storage slot."); @@ -1416,7 +1408,7 @@ } void unified_bed_leveling::fine_tune_mesh(const float &lx, const float &ly, const bool do_ubl_mesh_map) { - if (!code_seen('R')) // fine_tune_mesh() is special. If no repetition count flag is specified + if (!parser.seen('R')) // fine_tune_mesh() is special. If no repetition count flag is specified g29_repetition_cnt = 1; // do exactly one mesh location. Otherwise use what the parser decided. mesh_index_pair location; @@ -1587,7 +1579,7 @@ const float x = float(x_min) + ix * dx; for (int8_t iy = 0; iy < g29_grid_size; iy++) { const float y = float(y_min) + dy * (zig_zag ? g29_grid_size - 1 - iy : iy); - float measured_z = probe_pt(LOGICAL_X_POSITION(x), LOGICAL_Y_POSITION(y), code_seen('E'), g29_verbose_level); // TODO: Needs error handling + float measured_z = probe_pt(LOGICAL_X_POSITION(x), LOGICAL_Y_POSITION(y), parser.seen('E'), g29_verbose_level); // TODO: Needs error handling #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) { SERIAL_CHAR('('); From 1d167a68740d56fd9755f75ab72fe3ec4ea5476c Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 23 May 2017 15:09:26 -0500 Subject: [PATCH 143/189] Some cleanup, fixes for ultralcd.cpp UBL code - Free up 30 bytes of SRAM in UBL LCD code - Fix BUILD_ABS_MESH temperature - Fix UBL indentation in ultralcd.cpp - UBL vars lowercase, "convert to positive" sensibly --- Marlin/language_en.h | 10 +- Marlin/ultralcd.cpp | 650 ++++++++++++++++++++++--------------------- 2 files changed, 340 insertions(+), 320 deletions(-) diff --git a/Marlin/language_en.h b/Marlin/language_en.h index fefc41082..ba8cb807d 100644 --- a/Marlin/language_en.h +++ b/Marlin/language_en.h @@ -170,18 +170,18 @@ #ifndef MSG_UBL_DEACTIVATE_MESH #define MSG_UBL_DEACTIVATE_MESH _UxGT("Deactivate UBL") #endif - #ifndef MSG_UBL_CUSTOM_BED_TEMP - #define MSG_UBL_CUSTOM_BED_TEMP _UxGT("Bed Temp") - #endif #ifndef MSG_UBL_SET_BED_TEMP #define MSG_UBL_SET_BED_TEMP _UxGT("Bed Temp") #endif - #ifndef MSG_UBL_CUSTOM_HOTEND_TEMP - #define MSG_UBL_CUSTOM_HOTEND_TEMP _UxGT("Hotend Temp") + #ifndef MSG_UBL_CUSTOM_BED_TEMP + #define MSG_UBL_CUSTOM_BED_TEMP MSG_UBL_SET_BED_TEMP #endif #ifndef MSG_UBL_SET_HOTEND_TEMP #define MSG_UBL_SET_HOTEND_TEMP _UxGT("Hotend Temp") #endif + #ifndef MSG_UBL_CUSTOM_HOTEND_TEMP + #define MSG_UBL_CUSTOM_HOTEND_TEMP MSG_UBL_SET_HOTEND_TEMP + #endif #ifndef MSG_UBL_EDIT_CUSTOM_MESH #define MSG_UBL_EDIT_CUSTOM_MESH _UxGT("Edit Custom Mesh") #endif diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 642bb16fd..ebe97ccd2 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -1663,346 +1663,366 @@ void kill_screen(const char* lcd_msg) { END_MENU(); } - #if ENABLED(AUTO_BED_LEVELING_UBL) - - void _lcd_ubl_level_bed(); - - int UBL_STORAGE_SLOT = 0, - CUSTOM_BED_TEMP = 50, - CUSTOM_HOTEND_TEMP = 190, - SIDE_POINTS = 3, - UBL_FILLIN_AMOUNT = 5, - UBL_HEIGHT_AMOUNT, - map_type; + #if ENABLED(AUTO_BED_LEVELING_UBL) - char UBL_LCD_GCODE [30]; + void _lcd_ubl_level_bed(); - /** - * UBL Build Custom Mesh Command - */ - void _lcd_ubl_build_custom_mesh() { - enqueue_and_echo_command("G28"); - #if (WATCH_THE_BED) - sprintf_P(UBL_LCD_GCODE, PSTR("M190 S%i"), CUSTOM_BED_TEMP); - enqueue_and_echo_command(UBL_LCD_GCODE); - #endif - sprintf_P(UBL_LCD_GCODE, PSTR("M109 S%i"), CUSTOM_HOTEND_TEMP); - enqueue_and_echo_command(UBL_LCD_GCODE); - enqueue_and_echo_command("G29 P1"); - } + static int ubl_storage_slot = 0, + custom_bed_temp = 50, + custom_hotend_temp = 190, + side_points = 3, + ubl_fillin_amount = 5, + ubl_height_amount, + map_type; - /** - * UBL Custom Mesh submenu - */ - void _lcd_ubl_custom_mesh() { - START_MENU(); - MENU_BACK(MSG_UBL_BUILD_MESH_MENU); - MENU_ITEM_EDIT(int3, MSG_UBL_CUSTOM_HOTEND_TEMP, &CUSTOM_HOTEND_TEMP, EXTRUDE_MINTEMP, (HEATER_0_MAXTEMP - 10)); - #if (WATCH_THE_BED) - MENU_ITEM_EDIT(int3, MSG_UBL_CUSTOM_BED_TEMP, &CUSTOM_BED_TEMP, BED_MINTEMP, (BED_MAXTEMP - 5)); - #endif - MENU_ITEM(function, MSG_UBL_BUILD_CUSTOM_MESH, _lcd_ubl_build_custom_mesh); - END_MENU(); - } + /** + * UBL Build Custom Mesh Command + */ + void _lcd_ubl_build_custom_mesh() { + char UBL_LCD_GCODE[20]; + enqueue_and_echo_commands_P(PSTR("G28")); + #if WATCH_THE_BED + sprintf_P(UBL_LCD_GCODE, PSTR("M190 S%i"), custom_bed_temp); + enqueue_and_echo_command(UBL_LCD_GCODE); + #endif + sprintf_P(UBL_LCD_GCODE, PSTR("M109 S%i"), custom_hotend_temp); + enqueue_and_echo_command(UBL_LCD_GCODE); + enqueue_and_echo_commands_P(PSTR("G29 P1")); + } - /** - * UBL Adjust Mesh Height Command - */ - void _lcd_ubl_adjust_height_cmd() { - if (UBL_HEIGHT_AMOUNT < 0) { - // Convert to positive for the `sprintf_P` string. - UBL_HEIGHT_AMOUNT = (UBL_HEIGHT_AMOUNT - (UBL_HEIGHT_AMOUNT * 2)); // Convert to positive - sprintf_P(UBL_LCD_GCODE, PSTR("G29 P6-.%i"), UBL_HEIGHT_AMOUNT); - // Convert back to negative to preserve the user setting. - UBL_HEIGHT_AMOUNT = (UBL_HEIGHT_AMOUNT - (UBL_HEIGHT_AMOUNT * 2)); // Convert back to negative + /** + * UBL Custom Mesh submenu + */ + void _lcd_ubl_custom_mesh() { + START_MENU(); + MENU_BACK(MSG_UBL_BUILD_MESH_MENU); + MENU_ITEM_EDIT(int3, MSG_UBL_CUSTOM_HOTEND_TEMP, &custom_hotend_temp, EXTRUDE_MINTEMP, (HEATER_0_MAXTEMP - 10)); + #if WATCH_THE_BED + MENU_ITEM_EDIT(int3, MSG_UBL_CUSTOM_BED_TEMP, &custom_bed_temp, BED_MINTEMP, (BED_MAXTEMP - 5)); + #endif + MENU_ITEM(function, MSG_UBL_BUILD_CUSTOM_MESH, _lcd_ubl_build_custom_mesh); + END_MENU(); } - else { - sprintf_P(UBL_LCD_GCODE, PSTR("G29 P6.%i"), UBL_HEIGHT_AMOUNT); + + /** + * UBL Adjust Mesh Height Command + */ + void _lcd_ubl_adjust_height_cmd() { + char UBL_LCD_GCODE[16]; + const int ind = ubl_height_amount < 0 ? 6 : 7; + strcpy_P(UBL_LCD_GCODE, PSTR("G29 P6-")); + sprintf_P(&UBL_LCD_GCODE[ind], PSTR(".%i"), abs(ubl_height_amount)); + enqueue_and_echo_command(UBL_LCD_GCODE); } - enqueue_and_echo_command(UBL_LCD_GCODE); - } - /** - * UBL Adjust Mesh Height submenu - */ - void _lcd_ubl_height_adjust_menu() { - START_MENU(); - MENU_BACK(MSG_UBL_EDIT_MESH_MENU); - MENU_ITEM_EDIT(int3, MSG_UBL_MESH_HEIGHT_AMOUNT, &UBL_HEIGHT_AMOUNT, -9, 9); - MENU_ITEM(function, MSG_UBL_MESH_HEIGHT_ADJUST, _lcd_ubl_adjust_height_cmd); - MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); - END_MENU(); - } + /** + * UBL Adjust Mesh Height submenu + */ + void _lcd_ubl_height_adjust_menu() { + START_MENU(); + MENU_BACK(MSG_UBL_EDIT_MESH_MENU); + MENU_ITEM_EDIT(int3, MSG_UBL_MESH_HEIGHT_AMOUNT, &ubl_height_amount, -9, 9); + MENU_ITEM(function, MSG_UBL_MESH_HEIGHT_ADJUST, _lcd_ubl_adjust_height_cmd); + MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); + END_MENU(); + } - /** - * UBL Edit Mesh submenu - */ - void _lcd_ubl_edit_mesh() { - START_MENU(); - MENU_BACK(MSG_UBL_TOOLS); - MENU_BACK(MSG_UBL_LEVEL_BED); - MENU_ITEM(gcode, MSG_UBL_FINE_TUNE_ALL, PSTR("G29 P4 R T")); - MENU_ITEM(gcode, MSG_UBL_FINE_TUNE_CLOSEST, PSTR("G29 P4 T")); - MENU_ITEM(submenu, MSG_UBL_MESH_HEIGHT_ADJUST, _lcd_ubl_height_adjust_menu); - MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); - END_MENU(); - } + /** + * UBL Edit Mesh submenu + */ + void _lcd_ubl_edit_mesh() { + START_MENU(); + MENU_BACK(MSG_UBL_TOOLS); + MENU_BACK(MSG_UBL_LEVEL_BED); + MENU_ITEM(gcode, MSG_UBL_FINE_TUNE_ALL, PSTR("G29 P4 R T")); + MENU_ITEM(gcode, MSG_UBL_FINE_TUNE_CLOSEST, PSTR("G29 P4 T")); + MENU_ITEM(submenu, MSG_UBL_MESH_HEIGHT_ADJUST, _lcd_ubl_height_adjust_menu); + MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); + END_MENU(); + } - /** - * UBL Validate Custom Mesh Command - */ - void _lcd_ubl_validate_custom_mesh() { - enqueue_and_echo_command("G28"); - #if (WATCH_THE_BED) - sprintf_P(UBL_LCD_GCODE, PSTR("G26 C B%i H%i P"), CUSTOM_BED_TEMP, CUSTOM_HOTEND_TEMP); - #else - sprintf_P(UBL_LCD_GCODE, PSTR("G26 C B0 H%i P"), CUSTOM_HOTEND_TEMP); - #endif - enqueue_and_echo_command(UBL_LCD_GCODE); - } + /** + * UBL Validate Custom Mesh Command + */ + void _lcd_ubl_validate_custom_mesh() { + char UBL_LCD_GCODE[24]; + const int temp = + #if WATCH_THE_BED + custom_bed_temp + #else + 0 + #endif + ; + sprintf_P(UBL_LCD_GCODE, PSTR("G28\nG26 C B%i H%i P"), temp, custom_hotend_temp); + enqueue_and_echo_command(UBL_LCD_GCODE); + } - /** - * UBL Validate Mesh submenu - */ - void _lcd_ubl_validate_mesh() { - START_MENU(); - MENU_BACK(MSG_UBL_TOOLS); - #if (WATCH_THE_BED) - MENU_ITEM(gcode, MSG_UBL_VALIDATE_PLA_MESH, PSTR("G28\nG26 C B" STRINGIFY(PREHEAT_1_TEMP_BED) - " H" STRINGIFY(PREHEAT_1_TEMP_HOTEND) " P")); - MENU_ITEM(gcode, MSG_UBL_VALIDATE_ABS_MESH, PSTR("G28\nG26 C B" STRINGIFY(PREHEAT_2_TEMP_BED) - " H" STRINGIFY(PREHEAT_2_TEMP_HOTEND) " P")); - #else - MENU_ITEM(gcode, MSG_UBL_VALIDATE_PLA_MESH, PSTR("G28\nG26 C B0 H" STRINGIFY(PREHEAT_1_TEMP_HOTEND) " P")); - MENU_ITEM(gcode, MSG_UBL_VALIDATE_ABS_MESH, PSTR("G28\nG26 C B0 H" STRINGIFY(PREHEAT_2_TEMP_HOTEND) " P")); - #endif - MENU_ITEM(function, MSG_UBL_VALIDATE_CUSTOM_MESH, _lcd_ubl_validate_custom_mesh); - MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); - END_MENU(); - } + /** + * UBL Validate Mesh submenu + */ + void _lcd_ubl_validate_mesh() { + START_MENU(); + MENU_BACK(MSG_UBL_TOOLS); + #if WATCH_THE_BED + MENU_ITEM(gcode, MSG_UBL_VALIDATE_PLA_MESH, PSTR("G28\nG26 C B" STRINGIFY(PREHEAT_1_TEMP_BED) " H" STRINGIFY(PREHEAT_1_TEMP_HOTEND) " P")); + MENU_ITEM(gcode, MSG_UBL_VALIDATE_ABS_MESH, PSTR("G28\nG26 C B" STRINGIFY(PREHEAT_2_TEMP_BED) " H" STRINGIFY(PREHEAT_2_TEMP_HOTEND) " P")); + #else + MENU_ITEM(gcode, MSG_UBL_VALIDATE_PLA_MESH, PSTR("G28\nG26 C B0 H" STRINGIFY(PREHEAT_1_TEMP_HOTEND) " P")); + MENU_ITEM(gcode, MSG_UBL_VALIDATE_ABS_MESH, PSTR("G28\nG26 C B0 H" STRINGIFY(PREHEAT_2_TEMP_HOTEND) " P")); + #endif + MENU_ITEM(function, MSG_UBL_VALIDATE_CUSTOM_MESH, _lcd_ubl_validate_custom_mesh); + MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); + END_MENU(); + } - /** - * UBL Grid Leveling Command - */ - void _lcd_ubl_grid_level_cmd() { - sprintf_P(UBL_LCD_GCODE, PSTR("G29 J%i"), SIDE_POINTS); - enqueue_and_echo_command(UBL_LCD_GCODE); - } + /** + * UBL Grid Leveling Command + */ + void _lcd_ubl_grid_level_cmd() { + char UBL_LCD_GCODE[10]; + sprintf_P(UBL_LCD_GCODE, PSTR("G29 J%i"), side_points); + enqueue_and_echo_command(UBL_LCD_GCODE); + } - /** - * UBL Grid Leveling submenu - */ - void _lcd_ubl_grid_level() { - START_MENU(); - MENU_BACK(MSG_UBL_TOOLS); - MENU_ITEM_EDIT(int3, MSG_UBL_SIDE_POINTS, &SIDE_POINTS, 2, 6); - MENU_ITEM(function, MSG_UBL_MESH_LEVEL, _lcd_ubl_grid_level_cmd); - END_MENU(); - } + /** + * UBL Grid Leveling submenu + */ + void _lcd_ubl_grid_level() { + START_MENU(); + MENU_BACK(MSG_UBL_TOOLS); + MENU_ITEM_EDIT(int3, MSG_UBL_SIDE_POINTS, &side_points, 2, 6); + MENU_ITEM(function, MSG_UBL_MESH_LEVEL, _lcd_ubl_grid_level_cmd); + END_MENU(); + } - /** - * UBL Mesh Leveling submenu - */ - void _lcd_ubl_mesh_leveling() { - START_MENU(); - MENU_BACK(MSG_UBL_TOOLS); - MENU_ITEM(gcode, MSG_UBL_3POINT_MESH_LEVELING, PSTR("G29 J0")); - MENU_ITEM(submenu, MSG_UBL_GRID_MESH_LEVELING, _lcd_ubl_grid_level); - MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); - END_MENU(); - } + /** + * UBL Mesh Leveling submenu + */ + void _lcd_ubl_mesh_leveling() { + START_MENU(); + MENU_BACK(MSG_UBL_TOOLS); + MENU_ITEM(gcode, MSG_UBL_3POINT_MESH_LEVELING, PSTR("G29 J0")); + MENU_ITEM(submenu, MSG_UBL_GRID_MESH_LEVELING, _lcd_ubl_grid_level); + MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); + END_MENU(); + } - /** - * UBL Fill-in Amount Mesh Command - */ - void _lcd_ubl_fillin_amount_cmd() { - sprintf_P(UBL_LCD_GCODE, PSTR("G29 P3 R C.%i"), UBL_FILLIN_AMOUNT); - enqueue_and_echo_command(UBL_LCD_GCODE); - } + /** + * UBL Fill-in Amount Mesh Command + */ + void _lcd_ubl_fillin_amount_cmd() { + char UBL_LCD_GCODE[16]; + sprintf_P(UBL_LCD_GCODE, PSTR("G29 P3 R C.%i"), ubl_fillin_amount); + enqueue_and_echo_command(UBL_LCD_GCODE); + } - /** - * UBL Smart Fill-in Command - */ - void _lcd_ubl_smart_fillin_cmd() { - sprintf_P(UBL_LCD_GCODE, PSTR("G29 P3 T%i"), map_type); - enqueue_and_echo_command(UBL_LCD_GCODE); - } + /** + * UBL Smart Fill-in Command + */ + void _lcd_ubl_smart_fillin_cmd() { + char UBL_LCD_GCODE[12]; + sprintf_P(UBL_LCD_GCODE, PSTR("G29 P3 T%i"), map_type); + enqueue_and_echo_command(UBL_LCD_GCODE); + } - /** - * UBL Fill-in Mesh submenu - */ - void _lcd_ubl_fillin_menu() { - START_MENU(); - MENU_BACK(MSG_UBL_BUILD_MESH_MENU); - MENU_ITEM_EDIT(int3, MSG_UBL_FILLIN_AMOUNT, &UBL_FILLIN_AMOUNT, 0, 9); - MENU_ITEM(function, MSG_UBL_FILLIN_MESH, _lcd_ubl_fillin_amount_cmd); - MENU_ITEM(function, MSG_UBL_SMART_FILLIN, _lcd_ubl_smart_fillin_cmd); - MENU_ITEM(gcode, MSG_UBL_MANUAL_FILLIN, PSTR("G29 P2 B T0")); - MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); - END_MENU(); - } + /** + * UBL Fill-in Mesh submenu + */ + void _lcd_ubl_fillin_menu() { + START_MENU(); + MENU_BACK(MSG_UBL_BUILD_MESH_MENU); + MENU_ITEM_EDIT(int3, MSG_UBL_FILLIN_AMOUNT, &ubl_fillin_amount, 0, 9); + MENU_ITEM(function, MSG_UBL_FILLIN_MESH, _lcd_ubl_fillin_amount_cmd); + MENU_ITEM(function, MSG_UBL_SMART_FILLIN, _lcd_ubl_smart_fillin_cmd); + MENU_ITEM(gcode, MSG_UBL_MANUAL_FILLIN, PSTR("G29 P2 B T0")); + MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); + END_MENU(); + } - void _lcd_ubl_invalidate() { - ubl.invalidate(); - SERIAL_PROTOCOLLNPGM("Mesh invalidated."); - } + void _lcd_ubl_invalidate() { + ubl.invalidate(); + SERIAL_PROTOCOLLNPGM("Mesh invalidated."); + } - /** - * UBL Build Mesh submenu - */ - void _lcd_ubl_build_mesh() { - START_MENU(); - MENU_BACK(MSG_UBL_TOOLS); - #if (WATCH_THE_BED) - MENU_ITEM(gcode, MSG_UBL_BUILD_PLA_MESH, PSTR("G28\nM190 S" STRINGIFY(PREHEAT_1_TEMP_BED) - "\nM109 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) "\nG29 P1\nM104 S0\nM140 S0")); - MENU_ITEM(gcode, MSG_UBL_BUILD_ABS_MESH, PSTR("G28\nM190 S" STRINGIFY(PREHEAT_1_TEMP_BED) - "\nM109 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) "\nG29 P1\nM104 S0\nM140 S0")); - #else - MENU_ITEM(gcode, MSG_UBL_BUILD_PLA_MESH, PSTR("G28\nM109 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) - "\nG29 P1\nM104 S0")); - MENU_ITEM(gcode, MSG_UBL_BUILD_ABS_MESH, PSTR("G28\nM109 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) - "\nG29 P1\nM104 S0")); - #endif - MENU_ITEM(submenu, MSG_UBL_BUILD_CUSTOM_MESH, _lcd_ubl_custom_mesh); - MENU_ITEM(gcode, MSG_UBL_BUILD_COLD_MESH, PSTR("G28\nG29 P1")); - MENU_ITEM(submenu, MSG_UBL_FILLIN_MESH, _lcd_ubl_fillin_menu); - MENU_ITEM(gcode, MSG_UBL_CONTINUE_MESH, PSTR("G29 P1 C")); - MENU_ITEM(function, MSG_UBL_INVALIDATE_ALL, _lcd_ubl_invalidate); - MENU_ITEM(gcode, MSG_UBL_INVALIDATE_CLOSEST, PSTR("G29 I")); - MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); - END_MENU(); - } + /** + * UBL Build Mesh submenu + */ + void _lcd_ubl_build_mesh() { + START_MENU(); + MENU_BACK(MSG_UBL_TOOLS); + #if WATCH_THE_BED + MENU_ITEM(gcode, MSG_UBL_BUILD_PLA_MESH, PSTR( + "G28\n" + "M190 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\n" + "M109 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) "\n" + "G29 P1\n" + "M104 S0\n" + "M140 S0" + )); + MENU_ITEM(gcode, MSG_UBL_BUILD_ABS_MESH, PSTR( + "G28\n" + "M190 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\n" + "M109 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) "\n" + "G29 P1\n" + "M104 S0\n" + "M140 S0" + )); + #else + MENU_ITEM(gcode, MSG_UBL_BUILD_PLA_MESH, PSTR( + "G28\n" + "M109 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) "\n" + "G29 P1\n" + "M104 S0" + )); + MENU_ITEM(gcode, MSG_UBL_BUILD_ABS_MESH, PSTR( + "G28\n" + "M109 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) "\n" + "G29 P1\n" + "M104 S0" + )); + #endif + MENU_ITEM(submenu, MSG_UBL_BUILD_CUSTOM_MESH, _lcd_ubl_custom_mesh); + MENU_ITEM(gcode, MSG_UBL_BUILD_COLD_MESH, PSTR("G28\nG29 P1")); + MENU_ITEM(submenu, MSG_UBL_FILLIN_MESH, _lcd_ubl_fillin_menu); + MENU_ITEM(gcode, MSG_UBL_CONTINUE_MESH, PSTR("G29 P1 C")); + MENU_ITEM(function, MSG_UBL_INVALIDATE_ALL, _lcd_ubl_invalidate); + MENU_ITEM(gcode, MSG_UBL_INVALIDATE_CLOSEST, PSTR("G29 I")); + MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); + END_MENU(); + } - /** - * UBL Load Mesh Command - */ - void _lcd_ubl_load_mesh_cmd() { - sprintf_P(UBL_LCD_GCODE, PSTR("G29 L%i"), UBL_STORAGE_SLOT); - enqueue_and_echo_command(UBL_LCD_GCODE); - } + /** + * UBL Load Mesh Command + */ + void _lcd_ubl_load_mesh_cmd() { + char UBL_LCD_GCODE[8]; + sprintf_P(UBL_LCD_GCODE, PSTR("G29 L%i"), ubl_storage_slot); + enqueue_and_echo_command(UBL_LCD_GCODE); + } - /** - * UBL Save Mesh Command - */ - void _lcd_ubl_save_mesh_cmd() { - sprintf_P(UBL_LCD_GCODE, PSTR("G29 S%i"), UBL_STORAGE_SLOT); - enqueue_and_echo_command(UBL_LCD_GCODE); - } + /** + * UBL Save Mesh Command + */ + void _lcd_ubl_save_mesh_cmd() { + char UBL_LCD_GCODE[8]; + sprintf_P(UBL_LCD_GCODE, PSTR("G29 S%i"), ubl_storage_slot); + enqueue_and_echo_command(UBL_LCD_GCODE); + } - /** - * UBL Mesh Storage submenu - */ - void _lcd_ubl_storage_mesh() { - START_MENU(); - MENU_BACK(MSG_UBL_LEVEL_BED); - MENU_ITEM_EDIT(int3, MSG_UBL_STORAGE_SLOT, &UBL_STORAGE_SLOT, 0, 9); - MENU_ITEM(function, MSG_UBL_LOAD_MESH, _lcd_ubl_load_mesh_cmd); - MENU_ITEM(function, MSG_UBL_SAVE_MESH, _lcd_ubl_save_mesh_cmd); - END_MENU(); - } + /** + * UBL Mesh Storage submenu + */ + void _lcd_ubl_storage_mesh() { + START_MENU(); + MENU_BACK(MSG_UBL_LEVEL_BED); + MENU_ITEM_EDIT(int3, MSG_UBL_STORAGE_SLOT, &ubl_storage_slot, 0, 9); + MENU_ITEM(function, MSG_UBL_LOAD_MESH, _lcd_ubl_load_mesh_cmd); + MENU_ITEM(function, MSG_UBL_SAVE_MESH, _lcd_ubl_save_mesh_cmd); + END_MENU(); + } - /** - * UBL Output map Command - */ - void _lcd_ubl_output_map_cmd() { - sprintf_P(UBL_LCD_GCODE, PSTR("G29 T%i"), map_type); - enqueue_and_echo_command(UBL_LCD_GCODE); - } + /** + * UBL Output map Command + */ + void _lcd_ubl_output_map_cmd() { + char UBL_LCD_GCODE[10]; + sprintf_P(UBL_LCD_GCODE, PSTR("G29 T%i"), map_type); + enqueue_and_echo_command(UBL_LCD_GCODE); + } - /** - * UBL Output map submenu - */ - void _lcd_ubl_output_map() { - START_MENU(); - MENU_BACK(MSG_UBL_LEVEL_BED); - MENU_ITEM_EDIT(int3, MSG_UBL_MAP_TYPE, &map_type, 0, 1); - if (map_type == 0) MENU_ITEM(function, MSG_UBL_OUTPUT_MAP_HOST, _lcd_ubl_output_map_cmd); - if (map_type == 1) MENU_ITEM(function, MSG_UBL_OUTPUT_MAP_CSV, _lcd_ubl_output_map_cmd); - END_MENU(); - } + /** + * UBL Output map submenu + */ + void _lcd_ubl_output_map() { + START_MENU(); + MENU_BACK(MSG_UBL_LEVEL_BED); + MENU_ITEM_EDIT(int3, MSG_UBL_MAP_TYPE, &map_type, 0, 1); + if (map_type == 0) MENU_ITEM(function, MSG_UBL_OUTPUT_MAP_HOST, _lcd_ubl_output_map_cmd); + if (map_type == 1) MENU_ITEM(function, MSG_UBL_OUTPUT_MAP_CSV, _lcd_ubl_output_map_cmd); + END_MENU(); + } - /** - * UBL Tools submenu - */ - void _lcd_ubl_tools_menu() { - START_MENU(); - MENU_BACK(MSG_UBL_LEVEL_BED); - MENU_ITEM(submenu, MSG_UBL_BUILD_MESH_MENU, _lcd_ubl_build_mesh); - MENU_ITEM(submenu, MSG_UBL_VALIDATE_MESH_MENU, _lcd_ubl_validate_mesh); - MENU_ITEM(submenu, MSG_UBL_EDIT_MESH_MENU, _lcd_ubl_edit_mesh); - MENU_ITEM(submenu, MSG_UBL_MESH_LEVELING, _lcd_ubl_mesh_leveling); - END_MENU(); - } + /** + * UBL Tools submenu + */ + void _lcd_ubl_tools_menu() { + START_MENU(); + MENU_BACK(MSG_UBL_LEVEL_BED); + MENU_ITEM(submenu, MSG_UBL_BUILD_MESH_MENU, _lcd_ubl_build_mesh); + MENU_ITEM(submenu, MSG_UBL_VALIDATE_MESH_MENU, _lcd_ubl_validate_mesh); + MENU_ITEM(submenu, MSG_UBL_EDIT_MESH_MENU, _lcd_ubl_edit_mesh); + MENU_ITEM(submenu, MSG_UBL_MESH_LEVELING, _lcd_ubl_mesh_leveling); + END_MENU(); + } - /** - * UBL System submenu - * - * Prepare - * - Unified Bed Leveling - * - Activate UBL - * - Deactivate UBL - * - Mesh Storage - * Memory Slot: - * Load Bed Mesh - * Save Bed Mesh - * - Output Map - * Map Type: - * Output Bed Mesh Host / Output Bed Mesh CSV - * - UBL Tools - * - Build Mesh - * Build PLA Mesh - * Build ABS Mesh - * - Build Custom Mesh - * Hotend Temp: - * Bed Temp: - * Build Custom Mesh - * Info Screen - * - Build Cold Mesh - * - Fill-in Mesh - * Fill-in Mesh - * Smart Fill-in - * Manual Fill-in - * Info Screen - * Continue Bed Mesh - * Invalidate All - * Invalidate Closest - * - Validate Mesh - * PLA Mesh Validation - * ABS Mesh Validation - * - Custom Mesh Validation - * Hotend Temp: - * Bed Temp: - * Validate Mesh - * Info Screen - * - Edit Mesh - * Fine Tune All - * Fine Tune Closest - * - Adjust Mesh Height - * Height Amount: - * Adjust Mesh Height - * Info Screen - * - Mesh Leveling - * 3-Point Mesh Leveling - * - Grid Mesh Leveling - * Side points: - * Level Mesh - * Info Screen - * - Output UBL Info - */ + /** + * UBL System submenu + * + * Prepare + * - Unified Bed Leveling + * - Activate UBL + * - Deactivate UBL + * - Mesh Storage + * Memory Slot: + * Load Bed Mesh + * Save Bed Mesh + * - Output Map + * Map Type: + * Output Bed Mesh Host / Output Bed Mesh CSV + * - UBL Tools + * - Build Mesh + * Build PLA Mesh + * Build ABS Mesh + * - Build Custom Mesh + * Hotend Temp: + * Bed Temp: + * Build Custom Mesh + * Info Screen + * - Build Cold Mesh + * - Fill-in Mesh + * Fill-in Mesh + * Smart Fill-in + * Manual Fill-in + * Info Screen + * Continue Bed Mesh + * Invalidate All + * Invalidate Closest + * - Validate Mesh + * PLA Mesh Validation + * ABS Mesh Validation + * - Custom Mesh Validation + * Hotend Temp: + * Bed Temp: + * Validate Mesh + * Info Screen + * - Edit Mesh + * Fine Tune All + * Fine Tune Closest + * - Adjust Mesh Height + * Height Amount: + * Adjust Mesh Height + * Info Screen + * - Mesh Leveling + * 3-Point Mesh Leveling + * - Grid Mesh Leveling + * Side points: + * Level Mesh + * Info Screen + * - Output UBL Info + */ - void _lcd_ubl_level_bed() { - START_MENU(); - MENU_BACK(MSG_PREPARE); - MENU_ITEM(gcode, MSG_UBL_ACTIVATE_MESH, PSTR("G29 A")); - MENU_ITEM(gcode, MSG_UBL_DEACTIVATE_MESH, PSTR("G29 D")); - MENU_ITEM(submenu, MSG_UBL_STORAGE_MESH_MENU, _lcd_ubl_storage_mesh); - MENU_ITEM(submenu, MSG_UBL_OUTPUT_MAP, _lcd_ubl_output_map); - MENU_ITEM(submenu, MSG_UBL_TOOLS, _lcd_ubl_tools_menu); - MENU_ITEM(gcode, MSG_UBL_INFO_UBL, PSTR("G29 W")); - END_MENU(); - } - #endif + void _lcd_ubl_level_bed() { + START_MENU(); + MENU_BACK(MSG_PREPARE); + MENU_ITEM(gcode, MSG_UBL_ACTIVATE_MESH, PSTR("G29 A")); + MENU_ITEM(gcode, MSG_UBL_DEACTIVATE_MESH, PSTR("G29 D")); + MENU_ITEM(submenu, MSG_UBL_STORAGE_MESH_MENU, _lcd_ubl_storage_mesh); + MENU_ITEM(submenu, MSG_UBL_OUTPUT_MAP, _lcd_ubl_output_map); + MENU_ITEM(submenu, MSG_UBL_TOOLS, _lcd_ubl_tools_menu); + MENU_ITEM(gcode, MSG_UBL_INFO_UBL, PSTR("G29 W")); + END_MENU(); + } + #endif #endif // LCD_BED_LEVELING || HAS_ABL @@ -2052,7 +2072,7 @@ void kill_screen(const char* lcd_msg) { MENU_ITEM(submenu, MSG_LEVEL_BED, lcd_level_bed); #endif - #endif + #endif // LCD_BED_LEVELING || HAS_ABL #if HAS_M206_COMMAND // From af81cb4cbbe58f4f93aa19751137a1d41705d2ce Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 24 May 2017 16:56:36 -0500 Subject: [PATCH 144/189] Patch for M503 output --- Marlin/configuration_store.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/configuration_store.cpp b/Marlin/configuration_store.cpp index f23ee7770..2d2a22579 100644 --- a/Marlin/configuration_store.cpp +++ b/Marlin/configuration_store.cpp @@ -1461,7 +1461,7 @@ void MarlinSettings::reset() { #endif SERIAL_EOL; #if ENABLED(DISTINCT_E_FACTORS) - SERIAL_ECHO_START; + CONFIG_ECHO_START; for (uint8_t i = 0; i < E_STEPPERS; i++) { SERIAL_ECHOPAIR(" M201 T", (int)i); SERIAL_ECHOLNPAIR(" E", VOLUMETRIC_UNIT(planner.max_acceleration_mm_per_s2[E_AXIS + i])); From 1f52c9f5df9849d35c622e98884794a55166cd92 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 19 May 2017 14:06:06 -0500 Subject: [PATCH 145/189] Neater Megatronics 3 pins --- Marlin/pins_MEGATRONICS_3.h | 39 ++++++++++++++++++++----------------- 1 file changed, 21 insertions(+), 18 deletions(-) diff --git a/Marlin/pins_MEGATRONICS_3.h b/Marlin/pins_MEGATRONICS_3.h index aa6c40374..5e4ca4b58 100644 --- a/Marlin/pins_MEGATRONICS_3.h +++ b/Marlin/pins_MEGATRONICS_3.h @@ -143,11 +143,14 @@ #define BTN_ENC 33 #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) + #define LCD_PINS_RS 56 // CS chip select / SS chip slave select #define LCD_PINS_ENABLE 51 // SID (MOSI) #define LCD_PINS_D4 52 // SCK (CLK) clock #define SD_DETECT_PIN 35 + #else + #define LCD_PINS_RS 32 #define LCD_PINS_ENABLE 31 #define LCD_PINS_D4 14 @@ -171,23 +174,23 @@ // // M3/M4/M5 - Spindle/Laser Control // -#if DISABLED(REPRAPWORLD_KEYPAD) // try to use the keypad connector first - #define SPINDLE_LASER_PWM_PIN 44 // MUST BE HARDWARE PWM - #define SPINDLE_LASER_ENABLE_PIN 43 // Pin should have a pullup! - #define SPINDLE_DIR_PIN 42 +#if DISABLED(REPRAPWORLD_KEYPAD) // try to use the keypad connector first + #define SPINDLE_LASER_PWM_PIN 44 // MUST BE HARDWARE PWM + #define SPINDLE_LASER_ENABLE_PIN 43 // Pin should have a pullup! + #define SPINDLE_DIR_PIN 42 #elif EXTRUDERS <= 2 - // try to hijack the last extruder so that we can get the PWM signal off the Y breakout - // move all the Y signals to the E2 extruder socket - makes dual Y steppers harder - #undef Y_ENABLE_PIN - #undef Y_STEP_PIN - #undef Y_DIR_PIN - #undef E2_STEP_PIN - #undef E2_ENABLE_PIN - #undef E2_DIR_PIN - #define Y_ENABLE_PIN 23 - #define Y_STEP_PIN 22 - #define Y_DIR_PIN 60 - #define SPINDLE_LASER_PWM_PIN 4 // MUST BE HARDWARE PWM - #define SPINDLE_LASER_ENABLE_PIN 17 // Pin should have a pullup! - #define SPINDLE_DIR_PIN 5 + // Hijack the last extruder so that we can get the PWM signal off the Y breakout + // Move Y to the E2 plug. This makes dual Y steppers harder + #undef Y_ENABLE_PIN // 4 + #undef Y_STEP_PIN // 5 + #undef Y_DIR_PIN // 17 + #undef E2_ENABLE_PIN // 23 + #undef E2_STEP_PIN // 22 + #undef E2_DIR_PIN // 60 + #define Y_ENABLE_PIN 23 + #define Y_STEP_PIN 22 + #define Y_DIR_PIN 60 + #define SPINDLE_LASER_PWM_PIN 4 // MUST BE HARDWARE PWM + #define SPINDLE_LASER_ENABLE_PIN 17 // Pin should have a pullup! + #define SPINDLE_DIR_PIN 5 #endif From 5cbe0244c592c848229a3711b995344504f6a8a2 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 19 May 2017 13:48:16 -0500 Subject: [PATCH 146/189] Fixes for spindle/laser and SCARA probe bounds --- Marlin/Conditionals_post.h | 6 ++++++ Marlin/pins_RAMPS.h | 2 +- 2 files changed, 7 insertions(+), 1 deletion(-) diff --git a/Marlin/Conditionals_post.h b/Marlin/Conditionals_post.h index a4ae28ff3..9fcd944ac 100644 --- a/Marlin/Conditionals_post.h +++ b/Marlin/Conditionals_post.h @@ -788,6 +788,12 @@ #define MAX_PROBE_X ( DELTA_PRINTABLE_RADIUS) #define MIN_PROBE_Y (-DELTA_PRINTABLE_RADIUS) #define MAX_PROBE_Y ( DELTA_PRINTABLE_RADIUS) + #elif IS_SCARA + #define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2) + #define MIN_PROBE_X (-SCARA_PRINTABLE_RADIUS) + #define MAX_PROBE_X ( SCARA_PRINTABLE_RADIUS) + #define MIN_PROBE_Y (-SCARA_PRINTABLE_RADIUS) + #define MAX_PROBE_Y ( SCARA_PRINTABLE_RADIUS) #else // Boundaries for probing based on set limits #define MIN_PROBE_X (max(X_MIN_POS, X_MIN_POS + X_PROBE_OFFSET_FROM_EXTRUDER)) diff --git a/Marlin/pins_RAMPS.h b/Marlin/pins_RAMPS.h index 9bd1a252c..d1502e7d9 100644 --- a/Marlin/pins_RAMPS.h +++ b/Marlin/pins_RAMPS.h @@ -375,7 +375,7 @@ // // M3/M4/M5 - Spindle/Laser Control // -#if ENABLED(SPINDLE_LASER_ENABLE) && !PIN_EXISTS(SPINDLE_LASER_ENABLE_PIN) +#if ENABLED(SPINDLE_LASER_ENABLE) && !PIN_EXISTS(SPINDLE_LASER_ENABLE) #if !defined(NUM_SERVOS) || NUM_SERVOS == 0 // try to use servo connector first #define SPINDLE_LASER_ENABLE_PIN 4 // Pin should have a pullup/pulldown! #define SPINDLE_LASER_PWM_PIN 6 // MUST BE HARDWARE PWM From 5ed63a5724be36e066104a5c17c3bc6b3563797b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 27 Apr 2017 10:36:15 -0500 Subject: [PATCH 147/189] Apply const in prepare_kinematic_move_to --- Marlin/Marlin_main.cpp | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 6547cc152..f24929f67 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -11193,8 +11193,12 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) { if (!position_is_reachable_xy(ltarget[X_AXIS], ltarget[Y_AXIS])) return true; // Get the cartesian distances moved in XYZE - float difference[XYZE]; - LOOP_XYZE(i) difference[i] = ltarget[i] - current_position[i]; + const float difference[XYZE] = { + ltarget[X_AXIS] - current_position[X_AXIS], + ltarget[Y_AXIS] - current_position[Y_AXIS], + ltarget[Z_AXIS] - current_position[Z_AXIS], + ltarget[E_AXIS] - current_position[E_AXIS] + }; // Get the linear distance in XYZ float cartesian_mm = sqrt(sq(difference[X_AXIS]) + sq(difference[Y_AXIS]) + sq(difference[Z_AXIS])); From 361cbba11373a497c8e6b6fc121f6786a056b839 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 24 May 2017 17:19:02 -0500 Subject: [PATCH 148/189] Use M665 to set SCARA angle offsets --- Marlin/Marlin_main.cpp | 42 ++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 42 insertions(+) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index f24929f67..a5c42c5f6 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -7678,6 +7678,10 @@ inline void gcode_M205() { /** * M206: Set Additional Homing Offset (X Y Z). SCARA aliases T=X, P=Y + * + * *** @thinkyhead: I recommend deprecating M206 for SCARA in favor of M665. + * *** M206 for SCARA will remain enabled in 1.1.x for compatibility. + * *** In the next 1.2 release, it will simply be disabled by default. */ inline void gcode_M206() { LOOP_XYZ(i) @@ -7757,6 +7761,44 @@ inline void gcode_M205() { LOOP_XYZ(i) endstop_adj[i] -= z_temp; } +#elif IS_SCARA + + /** + * M665: Set SCARA settings + * + * Parameters: + * + * S[segments-per-second] - Segments-per-second + * P[theta-psi-offset] - Theta-Psi offset, added to the shoulder (A/X) angle + * T[theta-offset] - Theta offset, added to the elbow (B/Y) angle + * + * A, P, and X are all aliases for the shoulder angle + * B, T, and Y are all aliases for the elbow angle + */ + inline void gcode_M665() { + if (parser.seen('S')) delta_segments_per_second = parser.value_float(); + + const bool hasA = parser.seen('A'), hasP = parser.seen('P'), hasX = parser.seen('X'); + const uint8_t sumAPX = hasA + hasP + hasX; + if (sumAPX == 1) + home_offset[A_AXIS] = parser.value_float(); + else if (sumAPX > 1) { + SERIAL_ERROR_START; + SERIAL_ERRORLNPGM("Only one of A, P, or X is allowed."); + return; + } + + const bool hasB = parser.seen('B'), hasT = parser.seen('T'), hasY = parser.seen('Y'); + const uint8_t sumBTY = hasB + hasT + hasY; + if (sumBTY == 1) + home_offset[B_AXIS] = parser.value_float(); + else if (sumBTY > 1) { + SERIAL_ERROR_START; + SERIAL_ERRORLNPGM("Only one of B, T, or Y is allowed."); + return; + } + } + #elif ENABLED(Z_DUAL_ENDSTOPS) // !DELTA && ENABLED(Z_DUAL_ENDSTOPS) /** From 44e657766e6de472dd9dffa1137f4535ad537247 Mon Sep 17 00:00:00 2001 From: Thomas Moore Date: Thu, 25 May 2017 08:06:27 -0500 Subject: [PATCH 149/189] Add incompatibility error to Sanity Check for MIXING_EXTRUDER and LIN_ADVANCE --- Marlin/SanityCheck.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index 952200d14..5d9d1b12c 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -372,6 +372,8 @@ #error "Please select either MIXING_EXTRUDER or SWITCHING_EXTRUDER, not both." #elif ENABLED(SINGLENOZZLE) #error "MIXING_EXTRUDER is incompatible with SINGLENOZZLE." + #elif ENABLED(LIN_ADVANCE) + #error "MIXING_EXTRUDER is incompatible with LIN_ADVANCE." #endif #endif From b15e5314641585cf62c8aa197802365dc089d6b5 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 25 May 2017 15:29:14 -0500 Subject: [PATCH 150/189] Fix screen change on character display --- Marlin/ultralcd.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index ebe97ccd2..9a2b9c46d 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -470,7 +470,7 @@ uint16_t max_display_update_time = 0; // For LCD_PROGRESS_BAR re-initialize custom characters lcd_set_custom_characters(screen == lcd_status_screen); #endif - lcdDrawUpdate = LCDVIEW_KEEP_REDRAWING; + lcdDrawUpdate = LCDVIEW_CALL_REDRAW_NEXT; screen_changed = true; #if ENABLED(DOGLCD) drawing_screen = false; From b1a478859326f09ec0f6d2abf79bac9e69dc5a90 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 25 May 2017 23:25:04 -0500 Subject: [PATCH 151/189] Add .ino.cpp to .gitignore --- .gitignore | 1 + 1 file changed, 1 insertion(+) diff --git a/.gitignore b/.gitignore index a9267a2dc..74f5a99dd 100755 --- a/.gitignore +++ b/.gitignore @@ -52,6 +52,7 @@ tags *.lo *.o *.obj +*.ino.cpp # Precompiled Headers *.gch From 082da233911659ee0d7f8f9693d16c6cd80d45da Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 25 May 2017 18:02:29 -0500 Subject: [PATCH 152/189] One fewer EOL in M503 output --- Marlin/configuration_store.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/configuration_store.cpp b/Marlin/configuration_store.cpp index 2d2a22579..c39508f50 100644 --- a/Marlin/configuration_store.cpp +++ b/Marlin/configuration_store.cpp @@ -1344,9 +1344,8 @@ void MarlinSettings::reset() { #else #define LINEAR_UNIT(N) N #define VOLUMETRIC_UNIT(N) N - SERIAL_ECHOLNPGM(" G21 ; Units in mm\n"); + SERIAL_ECHOLNPGM(" G21 ; Units in mm"); #endif - SERIAL_EOL; #if ENABLED(ULTIPANEL) @@ -1361,12 +1360,13 @@ void MarlinSettings::reset() { serialprintPGM(parser.temp_units_name()); #else #define TEMP_UNIT(N) N - SERIAL_ECHOLNPGM(" M149 C ; Units in Celsius\n"); + SERIAL_ECHOLNPGM(" M149 C ; Units in Celsius"); #endif - SERIAL_EOL; #endif + SERIAL_EOL; + /** * Volumetric extrusion M200 */ From 78af2b1444b3c82d255db5dac5010d2246bb0a04 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 25 May 2017 17:38:07 -0500 Subject: [PATCH 153/189] Fix PROBE_MANUALLY via G-code --- Marlin/Marlin_main.cpp | 48 ++++++++++++++++++++++++------------------ 1 file changed, 27 insertions(+), 21 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index a5c42c5f6..1af9cfbc4 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -4190,7 +4190,7 @@ void home_all_axes() { gcode_G28(true); } if (!g29_in_progress) { #if ENABLED(PROBE_MANUALLY) || ENABLED(AUTO_BED_LEVELING_LINEAR) - abl_probe_index = 0; + abl_probe_index = -1; #endif abl_should_enable = planner.abl_enabled; @@ -4397,8 +4397,17 @@ void home_all_axes() { gcode_G28(true); } #if ENABLED(PROBE_MANUALLY) + const bool seenA = parser.seen('A'), seenQ = parser.seen('Q'); + + // For manual probing, get the next index to probe now. + // On the first probe this will be incremented to 0. + if (!seenA && !seenQ) { + ++abl_probe_index; + g29_in_progress = true; + } + // Abort current G29 procedure, go back to ABLStart - if (parser.seen('A') && g29_in_progress) { + if (seenA && g29_in_progress) { SERIAL_PROTOCOLLNPGM("Manual G29 aborted"); #if HAS_SOFTWARE_ENDSTOPS soft_endstops_enabled = enable_soft_endstops; @@ -4408,7 +4417,7 @@ void home_all_axes() { gcode_G28(true); } } // Query G29 status - if (parser.seen('Q')) { + if (verbose_level || seenQ) { if (!g29_in_progress) SERIAL_PROTOCOLLNPGM("Manual G29 idle"); else { @@ -4417,10 +4426,7 @@ void home_all_axes() { gcode_G28(true); } } } - if (parser.seen('A') || parser.seen('Q')) return; - - // Fall through to probe the first point - g29_in_progress = true; + if (seenA || seenQ) return; if (abl_probe_index == 0) { // For the initial G29 save software endstop state @@ -4458,20 +4464,20 @@ void home_all_axes() { gcode_G28(true); } #if ABL_GRID - // Find a next point to probe - // On the first G29 this will be the first probe point + // Skip any unreachable points while (abl_probe_index < abl2) { // Set xCount, yCount based on abl_probe_index, with zig-zag PR_OUTER_VAR = abl_probe_index / PR_INNER_END; PR_INNER_VAR = abl_probe_index - (PR_OUTER_VAR * PR_INNER_END); - bool zig = (PR_OUTER_VAR & 1) != ((PR_OUTER_END) & 1); + // Probe in reverse order for every other row/column + bool zig = (PR_OUTER_VAR & 1); // != ((PR_OUTER_END) & 1); if (zig) PR_INNER_VAR = (PR_INNER_END - 1) - PR_INNER_VAR; - const float xBase = left_probe_bed_position + xGridSpacing * xCount, - yBase = front_probe_bed_position + yGridSpacing * yCount; + const float xBase = xCount * xGridSpacing + left_probe_bed_position, + yBase = yCount * yGridSpacing + front_probe_bed_position; xProbe = floor(xBase + (xBase < 0 ? 0 : 0.5)); yProbe = floor(yBase + (yBase < 0 ? 0 : 0.5)); @@ -4488,7 +4494,6 @@ void home_all_axes() { gcode_G28(true); } // Is there a next point to move to? if (abl_probe_index < abl2) { _manual_goto_xy(xProbe, yProbe); // Can be used here too! - ++abl_probe_index; #if HAS_SOFTWARE_ENDSTOPS // Disable software endstops to allow manual adjustment // If G29 is not completed, they will not be re-enabled @@ -4497,10 +4502,9 @@ void home_all_axes() { gcode_G28(true); } return; } else { - // Then leveling is done! - // G29 finishing code goes here - // After recording the last point, activate abl + // Leveling done! Fall through to G29 finishing code below + SERIAL_PROTOCOLLNPGM("Grid probing done."); g29_in_progress = false; @@ -4514,9 +4518,8 @@ void home_all_axes() { gcode_G28(true); } // Probe at 3 arbitrary points if (abl_probe_index < 3) { - xProbe = LOGICAL_X_POSITION(points[i].x); - yProbe = LOGICAL_Y_POSITION(points[i].y); - ++abl_probe_index; + xProbe = LOGICAL_X_POSITION(points[abl_probe_index].x); + yProbe = LOGICAL_Y_POSITION(points[abl_probe_index].y); #if HAS_SOFTWARE_ENDSTOPS // Disable software endstops to allow manual adjustment // If G29 is not completed, they will not be re-enabled @@ -4587,7 +4590,7 @@ void home_all_axes() { gcode_G28(true); } yProbe = floor(yBase + (yBase < 0 ? 0 : 0.5)); #if ENABLED(AUTO_BED_LEVELING_LINEAR) - indexIntoAB[xCount][yCount] = ++abl_probe_index; + indexIntoAB[xCount][yCount] = ++abl_probe_index; // 0... #endif #if IS_KINEMATIC @@ -4665,7 +4668,10 @@ void home_all_axes() { gcode_G28(true); } // G29 Finishing Code // // Unless this is a dry run, auto bed leveling will - // definitely be enabled after this point + // definitely be enabled after this point. + // + // If code above wants to continue leveling, it should + // return or loop before this point. // // Restore state after probing From b3a97b5013b880a02de2c6f1af29fd4afa89f524 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 25 May 2017 15:13:57 -0500 Subject: [PATCH 154/189] Patch up LCD level bed menus --- Marlin/Marlin_main.cpp | 24 +- Marlin/ultralcd.cpp | 879 +++++++++++++++++++---------------------- 2 files changed, 436 insertions(+), 467 deletions(-) mode change 100644 => 100755 Marlin/ultralcd.cpp diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 1af9cfbc4..1806188a8 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -3800,6 +3800,10 @@ void home_all_axes() { gcode_G28(true); } #if ENABLED(MESH_BED_LEVELING) || ENABLED(PROBE_MANUALLY) + #if ENABLED(PROBE_MANUALLY) && ENABLED(LCD_BED_LEVELING) + extern bool lcd_wait_for_move; + #endif + inline void _manual_goto_xy(const float &x, const float &y) { const float old_feedrate_mm_s = feedrate_mm_s; @@ -3822,6 +3826,10 @@ void home_all_axes() { gcode_G28(true); } feedrate_mm_s = old_feedrate_mm_s; stepper.synchronize(); + + #if ENABLED(PROBE_MANUALLY) && ENABLED(LCD_BED_LEVELING) + lcd_wait_for_move = false; + #endif } #endif @@ -4414,16 +4422,20 @@ void home_all_axes() { gcode_G28(true); } #endif planner.abl_enabled = abl_should_enable; g29_in_progress = false; + #if ENABLED(LCD_BED_LEVELING) + lcd_wait_for_move = false; + #endif } // Query G29 status if (verbose_level || seenQ) { - if (!g29_in_progress) - SERIAL_PROTOCOLLNPGM("Manual G29 idle"); - else { - SERIAL_PROTOCOLPAIR("Manual G29 point ", abl_probe_index + 1); + SERIAL_PROTOCOLPGM("Manual G29 "); + if (g29_in_progress) { + SERIAL_PROTOCOLPAIR("point ", abl_probe_index + 1); SERIAL_PROTOCOLLNPAIR(" of ", abl2); } + else + SERIAL_PROTOCOLLNPGM("idle"); } if (seenA || seenQ) return; @@ -4681,6 +4693,10 @@ void home_all_axes() { gcode_G28(true); } if (DEBUGGING(LEVELING)) DEBUG_POS("> probing complete", current_position); #endif + #if ENABLED(PROBE_MANUALLY) && ENABLED(LCD_BED_LEVELING) + lcd_wait_for_move = false; + #endif + // Calculate leveling, print reports, correct the position #if ENABLED(AUTO_BED_LEVELING_BILINEAR) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp old mode 100644 new mode 100755 index 9a2b9c46d..54da69fc5 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -78,9 +78,6 @@ uint16_t max_display_update_time = 0; #if ENABLED(DOGLCD) bool drawing_screen = false; - #define LCDVIEW_KEEP_REDRAWING LCDVIEW_CALL_REDRAW_NEXT -#else - #define LCDVIEW_KEEP_REDRAWING LCDVIEW_REDRAW_NOW #endif #if ENABLED(DAC_STEPPER_CURRENT) @@ -479,22 +476,18 @@ uint16_t max_display_update_time = 0; } /** - * Synchronize safely while holding the current screen - * This blocks all further screen or stripe updates once called + * Show "Moving..." till moves are done, then revert to previous display. */ - extern uint8_t commands_in_queue; - inline void lcd_synchronize() { static bool no_reentry = false; lcd_implementation_drawmenu_static(LCD_HEIGHT >= 4 ? 1 : 0, PSTR(MSG_MOVING)); if (no_reentry) return; + + // Make this the current handler till all moves are done no_reentry = true; screenFunc_t old_screen = currentScreen; lcd_goto_screen(lcd_synchronize); - while (commands_in_queue) { - idle(); - stepper.synchronize(); - } + stepper.synchronize(); no_reentry = false; lcd_goto_screen(old_screen); } @@ -879,7 +872,7 @@ void kill_screen(const char* lcd_msg) { if (encoderPosition) { const int babystep_increment = (int32_t)encoderPosition * (BABYSTEP_MULTIPLICATOR); encoderPosition = 0; - lcdDrawUpdate = LCDVIEW_KEEP_REDRAWING; + lcdDrawUpdate = LCDVIEW_REDRAW_NOW; thermalManager.babystep_axis(axis, babystep_increment); babysteps_done += babystep_increment; } @@ -912,7 +905,7 @@ void kill_screen(const char* lcd_msg) { zprobe_zoffset = new_zoffset; refresh_zprobe_zoffset(true); - lcdDrawUpdate = LCDVIEW_KEEP_REDRAWING; + lcdDrawUpdate = LCDVIEW_CALL_REDRAW_NEXT; } } if (lcdDrawUpdate) @@ -943,7 +936,7 @@ void kill_screen(const char* lcd_msg) { mesh_edit_accumulator += float(ubl_encoderPosition) * 0.005 / 2.0; mesh_edit_value = mesh_edit_accumulator; encoderPosition = 0; - lcdDrawUpdate = LCDVIEW_KEEP_REDRAWING; + lcdDrawUpdate = LCDVIEW_CALL_REDRAW_NEXT; const int32_t rounded = (int32_t)(mesh_edit_value * 1000.0); mesh_edit_value = float(rounded - (rounded % 5L)) / 1000.0; @@ -1422,7 +1415,7 @@ void kill_screen(const char* lcd_msg) { constexpr uint8_t total_probe_points = ( #if ENABLED(AUTO_BED_LEVELING_3POINT) 3 - #elif ABL_GRID || ENABLED(AUTO_BED_LEVELING_UBL) || ENABLED(MESH_BED_LEVELING) + #elif ABL_GRID || ENABLED(MESH_BED_LEVELING) GRID_MAX_POINTS #endif ); @@ -1447,26 +1440,12 @@ void kill_screen(const char* lcd_msg) { #endif // MESH_BED_LEVELING - #if ENABLED(MESH_BED_LEVELING) || ENABLED(PROBE_MANUALLY) - void _lcd_level_goto_next_point(); - #endif - void _lcd_level_bed_done() { if (lcdDrawUpdate) lcd_implementation_drawedit(PSTR(MSG_LEVEL_BED_DONE)); - lcdDrawUpdate = LCDVIEW_KEEP_REDRAWING; + lcdDrawUpdate = LCDVIEW_CALL_REDRAW_NEXT; } - /** - * Step 6: Display "Next point: 1 / 9" while waiting for move to finish - */ - void _lcd_level_bed_moving() { - if (lcdDrawUpdate) { - char msg[10]; - sprintf_P(msg, PSTR("%i / %u"), (int)(manual_probe_index + 1), total_probe_points); - lcd_implementation_drawedit(PSTR(MSG_LEVEL_BED_NEXT_POINT), msg); - } - lcdDrawUpdate = LCDVIEW_KEEP_REDRAWING; - } + void _lcd_level_goto_next_point(); /** * Step 7: Get the Z coordinate, click goes to the next point or exits @@ -1474,40 +1453,24 @@ void kill_screen(const char* lcd_msg) { void _lcd_level_bed_get_z() { ENCODER_DIRECTION_NORMAL(); - // Encoder knob or keypad buttons adjust the Z position - if (encoderPosition) { - refresh_cmd_timeout(); - current_position[Z_AXIS] += float((int32_t)encoderPosition) * (MBL_Z_STEP); - NOLESS(current_position[Z_AXIS], -(LCD_PROBE_Z_RANGE) * 0.5); - NOMORE(current_position[Z_AXIS], (LCD_PROBE_Z_RANGE) * 0.5); - line_to_current(Z_AXIS); - lcdDrawUpdate = LCDVIEW_KEEP_REDRAWING; - encoderPosition = 0; - } - if (lcd_clicked) { // Use a hook to set the probe point z - // (zigzag arranges in XY order) - #if ENABLED(AUTO_BED_LEVELING_UBL) + #if ENABLED(MESH_BED_LEVELING) - // UBL set-z handling goes here + // MBL records the position but doesn't move to the next one + mbl.set_zigzag_z(manual_probe_index, current_position[Z_AXIS]); #elif ENABLED(PROBE_MANUALLY) - // G29 helpfully records Z and goes to the next - // point (or beeps if done) - enqueue_and_echo_commands_P(PSTR("G29")); - manual_probe_index++; - - #elif ENABLED(MESH_BED_LEVELING) - - mbl.set_zigzag_z(manual_probe_index++, current_position[Z_AXIS]); + // The last G29 will record but not move + if (manual_probe_index == total_probe_points - 1) + enqueue_and_echo_commands_P("G29 V1"); #endif // If done... - if (manual_probe_index == total_probe_points) { + if (++manual_probe_index >= total_probe_points) { // Say "Done!" lcd_goto_screen(_lcd_level_bed_done); @@ -1526,10 +1489,6 @@ void kill_screen(const char* lcd_msg) { mbl.set_has_mesh(true); mesh_probing_done(); - #elif ENABLED(AUTO_BED_LEVELING_UBL) - - // UBL enable goes here - #elif ENABLED(PROBE_MANUALLY) // ABL will be enabled due to "G29". @@ -1540,19 +1499,21 @@ void kill_screen(const char* lcd_msg) { //LCD_MESSAGEPGM(MSG_LEVEL_BED_DONE); lcd_completion_feedback(); } - else { - - // Move to the next probe point, if needed - #if ENABLED(MESH_BED_LEVELING) || ENABLED(PROBE_MANUALLY) - - _lcd_level_goto_next_point(); - - #elif ENABLED(AUTO_BED_LEVELING_UBL) + else + _lcd_level_goto_next_point(); - // UBL goto-next-point goes here + return; + } - #endif - } + // Encoder knob or keypad buttons adjust the Z position + if (encoderPosition) { + refresh_cmd_timeout(); + current_position[Z_AXIS] += float((int32_t)encoderPosition) * (MBL_Z_STEP); + NOLESS(current_position[Z_AXIS], -(LCD_PROBE_Z_RANGE) * 0.5); + NOMORE(current_position[Z_AXIS], (LCD_PROBE_Z_RANGE) * 0.5); + line_to_current(Z_AXIS); + lcdDrawUpdate = LCDVIEW_CALL_REDRAW_NEXT; + encoderPosition = 0; } // Update on first display, then only on updates to Z position @@ -1563,43 +1524,56 @@ void kill_screen(const char* lcd_msg) { } } - #if ENABLED(MESH_BED_LEVELING) || ENABLED(PROBE_MANUALLY) - - /** - * Step 5: Initiate a move to the next point - */ - void _lcd_level_goto_next_point() { - - // Set the menu to display ahead of blocking call - lcd_goto_screen(_lcd_level_bed_moving); - - #if ENABLED(MESH_BED_LEVELING) + /** + * Step 6: Display "Next point: 1 / 9" while waiting for move to finish + */ - int8_t px, py; - mbl.zigzag(manual_probe_index, px, py); + #if ENABLED(PROBE_MANUALLY) + bool lcd_wait_for_move; + #endif - // Controls the loop until the move is done - _manual_probe_goto_xy( - LOGICAL_X_POSITION(mbl.index_to_xpos[px]), - LOGICAL_Y_POSITION(mbl.index_to_ypos[py]) - ); + void _lcd_level_bed_moving() { + if (lcdDrawUpdate) { + char msg[10]; + sprintf_P(msg, PSTR("%i / %u"), (int)(manual_probe_index + 1), total_probe_points); + lcd_implementation_drawedit(PSTR(MSG_LEVEL_BED_NEXT_POINT), msg); + } + lcdDrawUpdate = LCDVIEW_CALL_NO_REDRAW; + #if ENABLED(PROBE_MANUALLY) + if (!lcd_wait_for_move) lcd_goto_screen(_lcd_level_bed_get_z); + #endif + } - #elif ENABLED(AUTO_BED_LEVELING_UBL) + /** + * Step 5: Initiate a move to the next point + */ + void _lcd_level_goto_next_point() { - // UBL may have its own methodology + // Set the menu to display ahead of blocking call + lcd_goto_screen(_lcd_level_bed_moving); - #elif ENABLED(PROBE_MANUALLY) + #if ENABLED(MESH_BED_LEVELING) - // Just wait for the G29 move to complete - lcd_synchronize(); + int8_t px, py; + mbl.zigzag(manual_probe_index, px, py); - #endif + // Controls the loop until the move is done + _manual_probe_goto_xy( + LOGICAL_X_POSITION(mbl.index_to_xpos[px]), + LOGICAL_Y_POSITION(mbl.index_to_ypos[py]) + ); // After the blocking function returns, change menus lcd_goto_screen(_lcd_level_bed_get_z); - } - #endif // MESH_BED_LEVELING + #elif ENABLED(PROBE_MANUALLY) + + // G29 will signal when it's done + lcd_wait_for_move = true; + enqueue_and_echo_commands_P(PSTR("G29 V1")); + + #endif + } /** * Step 4: Display "Click to Begin", wait for click @@ -1609,14 +1583,7 @@ void kill_screen(const char* lcd_msg) { if (lcdDrawUpdate) lcd_implementation_drawedit(PSTR(MSG_LEVEL_BED_WAITING)); if (lcd_clicked) { manual_probe_index = 0; - #if ENABLED(MESH_BED_LEVELING) - _lcd_level_goto_next_point(); - #elif ENABLED(AUTO_BED_LEVELING_UBL) - // UBL click handling should go here - #elif ENABLED(PROBE_MANUALLY) - enqueue_and_echo_commands_P(PSTR("G29")); - _lcd_level_goto_next_point(); - #endif + _lcd_level_goto_next_point(); } } @@ -1625,15 +1592,11 @@ void kill_screen(const char* lcd_msg) { */ void _lcd_level_bed_homing() { if (lcdDrawUpdate) lcd_implementation_drawedit(PSTR(MSG_LEVEL_BED_HOMING), NULL); + lcdDrawUpdate = LCDVIEW_CALL_NO_REDRAW; if (axis_homed[X_AXIS] && axis_homed[Y_AXIS] && axis_homed[Z_AXIS]) lcd_goto_screen(_lcd_level_bed_homing_done); - lcdDrawUpdate = LCDVIEW_KEEP_REDRAWING; } - #endif // LCD_BED_LEVELING - - #if ENABLED(LCD_BED_LEVELING) || HAS_ABL - #if ENABLED(PROBE_MANUALLY) extern bool g29_in_progress; #endif @@ -1642,15 +1605,10 @@ void kill_screen(const char* lcd_msg) { * Step 2: Continue Bed Leveling... */ void _lcd_level_bed_continue() { - #if ENABLED(LCD_BED_LEVELING) defer_return_to_status = true; axis_homed[X_AXIS] = axis_homed[Y_AXIS] = axis_homed[Z_AXIS] = false; lcd_goto_screen(_lcd_level_bed_homing); enqueue_and_echo_commands_P(PSTR("G28")); - #else - lcd_return_to_status(); - enqueue_and_echo_commands_P(axis_homed[X_AXIS] && axis_homed[Y_AXIS] ? PSTR("G29") : PSTR("G28\nG29")); - #endif } /** @@ -1663,368 +1621,367 @@ void kill_screen(const char* lcd_msg) { END_MENU(); } - #if ENABLED(AUTO_BED_LEVELING_UBL) + #elif ENABLED(AUTO_BED_LEVELING_UBL) - void _lcd_ubl_level_bed(); + void _lcd_ubl_level_bed(); - static int ubl_storage_slot = 0, - custom_bed_temp = 50, - custom_hotend_temp = 190, - side_points = 3, - ubl_fillin_amount = 5, - ubl_height_amount, - map_type; + static int ubl_storage_slot = 0, + custom_bed_temp = 50, + custom_hotend_temp = 190, + side_points = 3, + ubl_fillin_amount = 5, + ubl_height_amount, + map_type; - /** - * UBL Build Custom Mesh Command - */ - void _lcd_ubl_build_custom_mesh() { - char UBL_LCD_GCODE[20]; - enqueue_and_echo_commands_P(PSTR("G28")); - #if WATCH_THE_BED - sprintf_P(UBL_LCD_GCODE, PSTR("M190 S%i"), custom_bed_temp); - enqueue_and_echo_command(UBL_LCD_GCODE); - #endif - sprintf_P(UBL_LCD_GCODE, PSTR("M109 S%i"), custom_hotend_temp); + /** + * UBL Build Custom Mesh Command + */ + void _lcd_ubl_build_custom_mesh() { + char UBL_LCD_GCODE[20]; + enqueue_and_echo_commands_P(PSTR("G28")); + #if WATCH_THE_BED + sprintf_P(UBL_LCD_GCODE, PSTR("M190 S%i"), custom_bed_temp); enqueue_and_echo_command(UBL_LCD_GCODE); - enqueue_and_echo_commands_P(PSTR("G29 P1")); - } - - /** - * UBL Custom Mesh submenu - */ - void _lcd_ubl_custom_mesh() { - START_MENU(); - MENU_BACK(MSG_UBL_BUILD_MESH_MENU); - MENU_ITEM_EDIT(int3, MSG_UBL_CUSTOM_HOTEND_TEMP, &custom_hotend_temp, EXTRUDE_MINTEMP, (HEATER_0_MAXTEMP - 10)); - #if WATCH_THE_BED - MENU_ITEM_EDIT(int3, MSG_UBL_CUSTOM_BED_TEMP, &custom_bed_temp, BED_MINTEMP, (BED_MAXTEMP - 5)); - #endif - MENU_ITEM(function, MSG_UBL_BUILD_CUSTOM_MESH, _lcd_ubl_build_custom_mesh); - END_MENU(); - } + #endif + sprintf_P(UBL_LCD_GCODE, PSTR("M109 S%i"), custom_hotend_temp); + enqueue_and_echo_command(UBL_LCD_GCODE); + enqueue_and_echo_commands_P(PSTR("G29 P1")); + } - /** - * UBL Adjust Mesh Height Command - */ - void _lcd_ubl_adjust_height_cmd() { - char UBL_LCD_GCODE[16]; - const int ind = ubl_height_amount < 0 ? 6 : 7; - strcpy_P(UBL_LCD_GCODE, PSTR("G29 P6-")); - sprintf_P(&UBL_LCD_GCODE[ind], PSTR(".%i"), abs(ubl_height_amount)); - enqueue_and_echo_command(UBL_LCD_GCODE); - } + /** + * UBL Custom Mesh submenu + */ + void _lcd_ubl_custom_mesh() { + START_MENU(); + MENU_BACK(MSG_UBL_BUILD_MESH_MENU); + MENU_ITEM_EDIT(int3, MSG_UBL_CUSTOM_HOTEND_TEMP, &custom_hotend_temp, EXTRUDE_MINTEMP, (HEATER_0_MAXTEMP - 10)); + #if WATCH_THE_BED + MENU_ITEM_EDIT(int3, MSG_UBL_CUSTOM_BED_TEMP, &custom_bed_temp, BED_MINTEMP, (BED_MAXTEMP - 5)); + #endif + MENU_ITEM(function, MSG_UBL_BUILD_CUSTOM_MESH, _lcd_ubl_build_custom_mesh); + END_MENU(); + } - /** - * UBL Adjust Mesh Height submenu - */ - void _lcd_ubl_height_adjust_menu() { - START_MENU(); - MENU_BACK(MSG_UBL_EDIT_MESH_MENU); - MENU_ITEM_EDIT(int3, MSG_UBL_MESH_HEIGHT_AMOUNT, &ubl_height_amount, -9, 9); - MENU_ITEM(function, MSG_UBL_MESH_HEIGHT_ADJUST, _lcd_ubl_adjust_height_cmd); - MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); - END_MENU(); - } + /** + * UBL Adjust Mesh Height Command + */ + void _lcd_ubl_adjust_height_cmd() { + char UBL_LCD_GCODE[16]; + const int ind = ubl_height_amount < 0 ? 6 : 7; + strcpy_P(UBL_LCD_GCODE, PSTR("G29 P6-")); + sprintf_P(&UBL_LCD_GCODE[ind], PSTR(".%i"), abs(ubl_height_amount)); + enqueue_and_echo_command(UBL_LCD_GCODE); + } - /** - * UBL Edit Mesh submenu - */ - void _lcd_ubl_edit_mesh() { - START_MENU(); - MENU_BACK(MSG_UBL_TOOLS); - MENU_BACK(MSG_UBL_LEVEL_BED); - MENU_ITEM(gcode, MSG_UBL_FINE_TUNE_ALL, PSTR("G29 P4 R T")); - MENU_ITEM(gcode, MSG_UBL_FINE_TUNE_CLOSEST, PSTR("G29 P4 T")); - MENU_ITEM(submenu, MSG_UBL_MESH_HEIGHT_ADJUST, _lcd_ubl_height_adjust_menu); - MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); - END_MENU(); - } + /** + * UBL Adjust Mesh Height submenu + */ + void _lcd_ubl_height_adjust_menu() { + START_MENU(); + MENU_BACK(MSG_UBL_EDIT_MESH_MENU); + MENU_ITEM_EDIT(int3, MSG_UBL_MESH_HEIGHT_AMOUNT, &ubl_height_amount, -9, 9); + MENU_ITEM(function, MSG_UBL_MESH_HEIGHT_ADJUST, _lcd_ubl_adjust_height_cmd); + MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); + END_MENU(); + } - /** - * UBL Validate Custom Mesh Command - */ - void _lcd_ubl_validate_custom_mesh() { - char UBL_LCD_GCODE[24]; - const int temp = - #if WATCH_THE_BED - custom_bed_temp - #else - 0 - #endif - ; - sprintf_P(UBL_LCD_GCODE, PSTR("G28\nG26 C B%i H%i P"), temp, custom_hotend_temp); - enqueue_and_echo_command(UBL_LCD_GCODE); - } + /** + * UBL Edit Mesh submenu + */ + void _lcd_ubl_edit_mesh() { + START_MENU(); + MENU_BACK(MSG_UBL_TOOLS); + MENU_BACK(MSG_UBL_LEVEL_BED); + MENU_ITEM(gcode, MSG_UBL_FINE_TUNE_ALL, PSTR("G29 P4 R T")); + MENU_ITEM(gcode, MSG_UBL_FINE_TUNE_CLOSEST, PSTR("G29 P4 T")); + MENU_ITEM(submenu, MSG_UBL_MESH_HEIGHT_ADJUST, _lcd_ubl_height_adjust_menu); + MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); + END_MENU(); + } - /** - * UBL Validate Mesh submenu - */ - void _lcd_ubl_validate_mesh() { - START_MENU(); - MENU_BACK(MSG_UBL_TOOLS); + /** + * UBL Validate Custom Mesh Command + */ + void _lcd_ubl_validate_custom_mesh() { + char UBL_LCD_GCODE[24]; + const int temp = #if WATCH_THE_BED - MENU_ITEM(gcode, MSG_UBL_VALIDATE_PLA_MESH, PSTR("G28\nG26 C B" STRINGIFY(PREHEAT_1_TEMP_BED) " H" STRINGIFY(PREHEAT_1_TEMP_HOTEND) " P")); - MENU_ITEM(gcode, MSG_UBL_VALIDATE_ABS_MESH, PSTR("G28\nG26 C B" STRINGIFY(PREHEAT_2_TEMP_BED) " H" STRINGIFY(PREHEAT_2_TEMP_HOTEND) " P")); + custom_bed_temp #else - MENU_ITEM(gcode, MSG_UBL_VALIDATE_PLA_MESH, PSTR("G28\nG26 C B0 H" STRINGIFY(PREHEAT_1_TEMP_HOTEND) " P")); - MENU_ITEM(gcode, MSG_UBL_VALIDATE_ABS_MESH, PSTR("G28\nG26 C B0 H" STRINGIFY(PREHEAT_2_TEMP_HOTEND) " P")); + 0 #endif - MENU_ITEM(function, MSG_UBL_VALIDATE_CUSTOM_MESH, _lcd_ubl_validate_custom_mesh); - MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); - END_MENU(); - } + ; + sprintf_P(UBL_LCD_GCODE, PSTR("G28\nG26 C B%i H%i P"), temp, custom_hotend_temp); + enqueue_and_echo_command(UBL_LCD_GCODE); + } - /** - * UBL Grid Leveling Command - */ - void _lcd_ubl_grid_level_cmd() { - char UBL_LCD_GCODE[10]; - sprintf_P(UBL_LCD_GCODE, PSTR("G29 J%i"), side_points); - enqueue_and_echo_command(UBL_LCD_GCODE); - } + /** + * UBL Validate Mesh submenu + */ + void _lcd_ubl_validate_mesh() { + START_MENU(); + MENU_BACK(MSG_UBL_TOOLS); + #if WATCH_THE_BED + MENU_ITEM(gcode, MSG_UBL_VALIDATE_PLA_MESH, PSTR("G28\nG26 C B" STRINGIFY(PREHEAT_1_TEMP_BED) " H" STRINGIFY(PREHEAT_1_TEMP_HOTEND) " P")); + MENU_ITEM(gcode, MSG_UBL_VALIDATE_ABS_MESH, PSTR("G28\nG26 C B" STRINGIFY(PREHEAT_2_TEMP_BED) " H" STRINGIFY(PREHEAT_2_TEMP_HOTEND) " P")); + #else + MENU_ITEM(gcode, MSG_UBL_VALIDATE_PLA_MESH, PSTR("G28\nG26 C B0 H" STRINGIFY(PREHEAT_1_TEMP_HOTEND) " P")); + MENU_ITEM(gcode, MSG_UBL_VALIDATE_ABS_MESH, PSTR("G28\nG26 C B0 H" STRINGIFY(PREHEAT_2_TEMP_HOTEND) " P")); + #endif + MENU_ITEM(function, MSG_UBL_VALIDATE_CUSTOM_MESH, _lcd_ubl_validate_custom_mesh); + MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); + END_MENU(); + } - /** - * UBL Grid Leveling submenu - */ - void _lcd_ubl_grid_level() { - START_MENU(); - MENU_BACK(MSG_UBL_TOOLS); - MENU_ITEM_EDIT(int3, MSG_UBL_SIDE_POINTS, &side_points, 2, 6); - MENU_ITEM(function, MSG_UBL_MESH_LEVEL, _lcd_ubl_grid_level_cmd); - END_MENU(); - } + /** + * UBL Grid Leveling Command + */ + void _lcd_ubl_grid_level_cmd() { + char UBL_LCD_GCODE[10]; + sprintf_P(UBL_LCD_GCODE, PSTR("G29 J%i"), side_points); + enqueue_and_echo_command(UBL_LCD_GCODE); + } - /** - * UBL Mesh Leveling submenu - */ - void _lcd_ubl_mesh_leveling() { - START_MENU(); - MENU_BACK(MSG_UBL_TOOLS); - MENU_ITEM(gcode, MSG_UBL_3POINT_MESH_LEVELING, PSTR("G29 J0")); - MENU_ITEM(submenu, MSG_UBL_GRID_MESH_LEVELING, _lcd_ubl_grid_level); - MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); - END_MENU(); - } + /** + * UBL Grid Leveling submenu + */ + void _lcd_ubl_grid_level() { + START_MENU(); + MENU_BACK(MSG_UBL_TOOLS); + MENU_ITEM_EDIT(int3, MSG_UBL_SIDE_POINTS, &side_points, 2, 6); + MENU_ITEM(function, MSG_UBL_MESH_LEVEL, _lcd_ubl_grid_level_cmd); + END_MENU(); + } - /** - * UBL Fill-in Amount Mesh Command - */ - void _lcd_ubl_fillin_amount_cmd() { - char UBL_LCD_GCODE[16]; - sprintf_P(UBL_LCD_GCODE, PSTR("G29 P3 R C.%i"), ubl_fillin_amount); - enqueue_and_echo_command(UBL_LCD_GCODE); - } + /** + * UBL Mesh Leveling submenu + */ + void _lcd_ubl_mesh_leveling() { + START_MENU(); + MENU_BACK(MSG_UBL_TOOLS); + MENU_ITEM(gcode, MSG_UBL_3POINT_MESH_LEVELING, PSTR("G29 J0")); + MENU_ITEM(submenu, MSG_UBL_GRID_MESH_LEVELING, _lcd_ubl_grid_level); + MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); + END_MENU(); + } - /** - * UBL Smart Fill-in Command - */ - void _lcd_ubl_smart_fillin_cmd() { - char UBL_LCD_GCODE[12]; - sprintf_P(UBL_LCD_GCODE, PSTR("G29 P3 T%i"), map_type); - enqueue_and_echo_command(UBL_LCD_GCODE); - } + /** + * UBL Fill-in Amount Mesh Command + */ + void _lcd_ubl_fillin_amount_cmd() { + char UBL_LCD_GCODE[16]; + sprintf_P(UBL_LCD_GCODE, PSTR("G29 P3 R C.%i"), ubl_fillin_amount); + enqueue_and_echo_command(UBL_LCD_GCODE); + } - /** - * UBL Fill-in Mesh submenu - */ - void _lcd_ubl_fillin_menu() { - START_MENU(); - MENU_BACK(MSG_UBL_BUILD_MESH_MENU); - MENU_ITEM_EDIT(int3, MSG_UBL_FILLIN_AMOUNT, &ubl_fillin_amount, 0, 9); - MENU_ITEM(function, MSG_UBL_FILLIN_MESH, _lcd_ubl_fillin_amount_cmd); - MENU_ITEM(function, MSG_UBL_SMART_FILLIN, _lcd_ubl_smart_fillin_cmd); - MENU_ITEM(gcode, MSG_UBL_MANUAL_FILLIN, PSTR("G29 P2 B T0")); - MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); - END_MENU(); - } + /** + * UBL Smart Fill-in Command + */ + void _lcd_ubl_smart_fillin_cmd() { + char UBL_LCD_GCODE[12]; + sprintf_P(UBL_LCD_GCODE, PSTR("G29 P3 T%i"), map_type); + enqueue_and_echo_command(UBL_LCD_GCODE); + } - void _lcd_ubl_invalidate() { - ubl.invalidate(); - SERIAL_PROTOCOLLNPGM("Mesh invalidated."); - } + /** + * UBL Fill-in Mesh submenu + */ + void _lcd_ubl_fillin_menu() { + START_MENU(); + MENU_BACK(MSG_UBL_BUILD_MESH_MENU); + MENU_ITEM_EDIT(int3, MSG_UBL_FILLIN_AMOUNT, &ubl_fillin_amount, 0, 9); + MENU_ITEM(function, MSG_UBL_FILLIN_MESH, _lcd_ubl_fillin_amount_cmd); + MENU_ITEM(function, MSG_UBL_SMART_FILLIN, _lcd_ubl_smart_fillin_cmd); + MENU_ITEM(gcode, MSG_UBL_MANUAL_FILLIN, PSTR("G29 P2 B T0")); + MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); + END_MENU(); + } - /** - * UBL Build Mesh submenu - */ - void _lcd_ubl_build_mesh() { - START_MENU(); - MENU_BACK(MSG_UBL_TOOLS); - #if WATCH_THE_BED - MENU_ITEM(gcode, MSG_UBL_BUILD_PLA_MESH, PSTR( - "G28\n" - "M190 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\n" - "M109 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) "\n" - "G29 P1\n" - "M104 S0\n" - "M140 S0" - )); - MENU_ITEM(gcode, MSG_UBL_BUILD_ABS_MESH, PSTR( - "G28\n" - "M190 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\n" - "M109 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) "\n" - "G29 P1\n" - "M104 S0\n" - "M140 S0" - )); - #else - MENU_ITEM(gcode, MSG_UBL_BUILD_PLA_MESH, PSTR( - "G28\n" - "M109 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) "\n" - "G29 P1\n" - "M104 S0" - )); - MENU_ITEM(gcode, MSG_UBL_BUILD_ABS_MESH, PSTR( - "G28\n" - "M109 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) "\n" - "G29 P1\n" - "M104 S0" - )); - #endif - MENU_ITEM(submenu, MSG_UBL_BUILD_CUSTOM_MESH, _lcd_ubl_custom_mesh); - MENU_ITEM(gcode, MSG_UBL_BUILD_COLD_MESH, PSTR("G28\nG29 P1")); - MENU_ITEM(submenu, MSG_UBL_FILLIN_MESH, _lcd_ubl_fillin_menu); - MENU_ITEM(gcode, MSG_UBL_CONTINUE_MESH, PSTR("G29 P1 C")); - MENU_ITEM(function, MSG_UBL_INVALIDATE_ALL, _lcd_ubl_invalidate); - MENU_ITEM(gcode, MSG_UBL_INVALIDATE_CLOSEST, PSTR("G29 I")); - MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); - END_MENU(); - } + void _lcd_ubl_invalidate() { + ubl.invalidate(); + SERIAL_PROTOCOLLNPGM("Mesh invalidated."); + } - /** - * UBL Load Mesh Command - */ - void _lcd_ubl_load_mesh_cmd() { - char UBL_LCD_GCODE[8]; - sprintf_P(UBL_LCD_GCODE, PSTR("G29 L%i"), ubl_storage_slot); - enqueue_and_echo_command(UBL_LCD_GCODE); - } + /** + * UBL Build Mesh submenu + */ + void _lcd_ubl_build_mesh() { + START_MENU(); + MENU_BACK(MSG_UBL_TOOLS); + #if WATCH_THE_BED + MENU_ITEM(gcode, MSG_UBL_BUILD_PLA_MESH, PSTR( + "G28\n" + "M190 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\n" + "M109 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) "\n" + "G29 P1\n" + "M104 S0\n" + "M140 S0" + )); + MENU_ITEM(gcode, MSG_UBL_BUILD_ABS_MESH, PSTR( + "G28\n" + "M190 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\n" + "M109 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) "\n" + "G29 P1\n" + "M104 S0\n" + "M140 S0" + )); + #else + MENU_ITEM(gcode, MSG_UBL_BUILD_PLA_MESH, PSTR( + "G28\n" + "M109 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) "\n" + "G29 P1\n" + "M104 S0" + )); + MENU_ITEM(gcode, MSG_UBL_BUILD_ABS_MESH, PSTR( + "G28\n" + "M109 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) "\n" + "G29 P1\n" + "M104 S0" + )); + #endif + MENU_ITEM(submenu, MSG_UBL_BUILD_CUSTOM_MESH, _lcd_ubl_custom_mesh); + MENU_ITEM(gcode, MSG_UBL_BUILD_COLD_MESH, PSTR("G28\nG29 P1")); + MENU_ITEM(submenu, MSG_UBL_FILLIN_MESH, _lcd_ubl_fillin_menu); + MENU_ITEM(gcode, MSG_UBL_CONTINUE_MESH, PSTR("G29 P1 C")); + MENU_ITEM(function, MSG_UBL_INVALIDATE_ALL, _lcd_ubl_invalidate); + MENU_ITEM(gcode, MSG_UBL_INVALIDATE_CLOSEST, PSTR("G29 I")); + MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); + END_MENU(); + } - /** - * UBL Save Mesh Command - */ - void _lcd_ubl_save_mesh_cmd() { - char UBL_LCD_GCODE[8]; - sprintf_P(UBL_LCD_GCODE, PSTR("G29 S%i"), ubl_storage_slot); - enqueue_and_echo_command(UBL_LCD_GCODE); - } + /** + * UBL Load Mesh Command + */ + void _lcd_ubl_load_mesh_cmd() { + char UBL_LCD_GCODE[8]; + sprintf_P(UBL_LCD_GCODE, PSTR("G29 L%i"), ubl_storage_slot); + enqueue_and_echo_command(UBL_LCD_GCODE); + } - /** - * UBL Mesh Storage submenu - */ - void _lcd_ubl_storage_mesh() { - START_MENU(); - MENU_BACK(MSG_UBL_LEVEL_BED); - MENU_ITEM_EDIT(int3, MSG_UBL_STORAGE_SLOT, &ubl_storage_slot, 0, 9); - MENU_ITEM(function, MSG_UBL_LOAD_MESH, _lcd_ubl_load_mesh_cmd); - MENU_ITEM(function, MSG_UBL_SAVE_MESH, _lcd_ubl_save_mesh_cmd); - END_MENU(); - } + /** + * UBL Save Mesh Command + */ + void _lcd_ubl_save_mesh_cmd() { + char UBL_LCD_GCODE[8]; + sprintf_P(UBL_LCD_GCODE, PSTR("G29 S%i"), ubl_storage_slot); + enqueue_and_echo_command(UBL_LCD_GCODE); + } - /** - * UBL Output map Command - */ - void _lcd_ubl_output_map_cmd() { - char UBL_LCD_GCODE[10]; - sprintf_P(UBL_LCD_GCODE, PSTR("G29 T%i"), map_type); - enqueue_and_echo_command(UBL_LCD_GCODE); - } + /** + * UBL Mesh Storage submenu + */ + void _lcd_ubl_storage_mesh() { + START_MENU(); + MENU_BACK(MSG_UBL_LEVEL_BED); + MENU_ITEM_EDIT(int3, MSG_UBL_STORAGE_SLOT, &ubl_storage_slot, 0, 9); + MENU_ITEM(function, MSG_UBL_LOAD_MESH, _lcd_ubl_load_mesh_cmd); + MENU_ITEM(function, MSG_UBL_SAVE_MESH, _lcd_ubl_save_mesh_cmd); + END_MENU(); + } - /** - * UBL Output map submenu - */ - void _lcd_ubl_output_map() { - START_MENU(); - MENU_BACK(MSG_UBL_LEVEL_BED); - MENU_ITEM_EDIT(int3, MSG_UBL_MAP_TYPE, &map_type, 0, 1); - if (map_type == 0) MENU_ITEM(function, MSG_UBL_OUTPUT_MAP_HOST, _lcd_ubl_output_map_cmd); - if (map_type == 1) MENU_ITEM(function, MSG_UBL_OUTPUT_MAP_CSV, _lcd_ubl_output_map_cmd); - END_MENU(); - } + /** + * UBL Output map Command + */ + void _lcd_ubl_output_map_cmd() { + char UBL_LCD_GCODE[10]; + sprintf_P(UBL_LCD_GCODE, PSTR("G29 T%i"), map_type); + enqueue_and_echo_command(UBL_LCD_GCODE); + } - /** - * UBL Tools submenu - */ - void _lcd_ubl_tools_menu() { - START_MENU(); - MENU_BACK(MSG_UBL_LEVEL_BED); - MENU_ITEM(submenu, MSG_UBL_BUILD_MESH_MENU, _lcd_ubl_build_mesh); - MENU_ITEM(submenu, MSG_UBL_VALIDATE_MESH_MENU, _lcd_ubl_validate_mesh); - MENU_ITEM(submenu, MSG_UBL_EDIT_MESH_MENU, _lcd_ubl_edit_mesh); - MENU_ITEM(submenu, MSG_UBL_MESH_LEVELING, _lcd_ubl_mesh_leveling); - END_MENU(); - } + /** + * UBL Output map submenu + */ + void _lcd_ubl_output_map() { + START_MENU(); + MENU_BACK(MSG_UBL_LEVEL_BED); + MENU_ITEM_EDIT(int3, MSG_UBL_MAP_TYPE, &map_type, 0, 1); + if (map_type == 0) MENU_ITEM(function, MSG_UBL_OUTPUT_MAP_HOST, _lcd_ubl_output_map_cmd); + if (map_type == 1) MENU_ITEM(function, MSG_UBL_OUTPUT_MAP_CSV, _lcd_ubl_output_map_cmd); + END_MENU(); + } - /** - * UBL System submenu - * - * Prepare - * - Unified Bed Leveling - * - Activate UBL - * - Deactivate UBL - * - Mesh Storage - * Memory Slot: - * Load Bed Mesh - * Save Bed Mesh - * - Output Map - * Map Type: - * Output Bed Mesh Host / Output Bed Mesh CSV - * - UBL Tools - * - Build Mesh - * Build PLA Mesh - * Build ABS Mesh - * - Build Custom Mesh - * Hotend Temp: - * Bed Temp: - * Build Custom Mesh - * Info Screen - * - Build Cold Mesh - * - Fill-in Mesh - * Fill-in Mesh - * Smart Fill-in - * Manual Fill-in - * Info Screen - * Continue Bed Mesh - * Invalidate All - * Invalidate Closest - * - Validate Mesh - * PLA Mesh Validation - * ABS Mesh Validation - * - Custom Mesh Validation - * Hotend Temp: - * Bed Temp: - * Validate Mesh - * Info Screen - * - Edit Mesh - * Fine Tune All - * Fine Tune Closest - * - Adjust Mesh Height - * Height Amount: - * Adjust Mesh Height - * Info Screen - * - Mesh Leveling - * 3-Point Mesh Leveling - * - Grid Mesh Leveling - * Side points: - * Level Mesh - * Info Screen - * - Output UBL Info - */ + /** + * UBL Tools submenu + */ + void _lcd_ubl_tools_menu() { + START_MENU(); + MENU_BACK(MSG_UBL_LEVEL_BED); + MENU_ITEM(submenu, MSG_UBL_BUILD_MESH_MENU, _lcd_ubl_build_mesh); + MENU_ITEM(submenu, MSG_UBL_VALIDATE_MESH_MENU, _lcd_ubl_validate_mesh); + MENU_ITEM(submenu, MSG_UBL_EDIT_MESH_MENU, _lcd_ubl_edit_mesh); + MENU_ITEM(submenu, MSG_UBL_MESH_LEVELING, _lcd_ubl_mesh_leveling); + END_MENU(); + } - void _lcd_ubl_level_bed() { - START_MENU(); - MENU_BACK(MSG_PREPARE); - MENU_ITEM(gcode, MSG_UBL_ACTIVATE_MESH, PSTR("G29 A")); - MENU_ITEM(gcode, MSG_UBL_DEACTIVATE_MESH, PSTR("G29 D")); - MENU_ITEM(submenu, MSG_UBL_STORAGE_MESH_MENU, _lcd_ubl_storage_mesh); - MENU_ITEM(submenu, MSG_UBL_OUTPUT_MAP, _lcd_ubl_output_map); - MENU_ITEM(submenu, MSG_UBL_TOOLS, _lcd_ubl_tools_menu); - MENU_ITEM(gcode, MSG_UBL_INFO_UBL, PSTR("G29 W")); - END_MENU(); - } - #endif + /** + * UBL System submenu + * + * Prepare + * - Unified Bed Leveling + * - Activate UBL + * - Deactivate UBL + * - Mesh Storage + * Memory Slot: + * Load Bed Mesh + * Save Bed Mesh + * - Output Map + * Map Type: + * Output Bed Mesh Host / Output Bed Mesh CSV + * - UBL Tools + * - Build Mesh + * Build PLA Mesh + * Build ABS Mesh + * - Build Custom Mesh + * Hotend Temp: + * Bed Temp: + * Build Custom Mesh + * Info Screen + * - Build Cold Mesh + * - Fill-in Mesh + * Fill-in Mesh + * Smart Fill-in + * Manual Fill-in + * Info Screen + * Continue Bed Mesh + * Invalidate All + * Invalidate Closest + * - Validate Mesh + * PLA Mesh Validation + * ABS Mesh Validation + * - Custom Mesh Validation + * Hotend Temp: + * Bed Temp: + * Validate Mesh + * Info Screen + * - Edit Mesh + * Fine Tune All + * Fine Tune Closest + * - Adjust Mesh Height + * Height Amount: + * Adjust Mesh Height + * Info Screen + * - Mesh Leveling + * 3-Point Mesh Leveling + * - Grid Mesh Leveling + * Side points: + * Level Mesh + * Info Screen + * - Output UBL Info + */ + + void _lcd_ubl_level_bed() { + START_MENU(); + MENU_BACK(MSG_PREPARE); + MENU_ITEM(gcode, MSG_UBL_ACTIVATE_MESH, PSTR("G29 A")); + MENU_ITEM(gcode, MSG_UBL_DEACTIVATE_MESH, PSTR("G29 D")); + MENU_ITEM(submenu, MSG_UBL_STORAGE_MESH_MENU, _lcd_ubl_storage_mesh); + MENU_ITEM(submenu, MSG_UBL_OUTPUT_MAP, _lcd_ubl_output_map); + MENU_ITEM(submenu, MSG_UBL_TOOLS, _lcd_ubl_tools_menu); + MENU_ITEM(gcode, MSG_UBL_INFO_UBL, PSTR("G29 W")); + END_MENU(); + } - #endif // LCD_BED_LEVELING || HAS_ABL + #endif // AUTO_BED_LEVELING_UBL /** * @@ -2061,18 +2018,14 @@ void kill_screen(const char* lcd_msg) { // // Level Bed // - #if ENABLED(LCD_BED_LEVELING) || HAS_ABL - + #if ENABLED(AUTO_BED_LEVELING_UBL) + MENU_ITEM(submenu, MSG_UBL_LEVEL_BED, _lcd_ubl_level_bed); + #elif ENABLED(LCD_BED_LEVELING) #if ENABLED(PROBE_MANUALLY) if (!g29_in_progress) #endif - #if ENABLED(AUTO_BED_LEVELING_UBL) - MENU_ITEM(submenu, MSG_UBL_LEVEL_BED, _lcd_ubl_level_bed); - #else - MENU_ITEM(submenu, MSG_LEVEL_BED, lcd_level_bed); - #endif - - #endif // LCD_BED_LEVELING || HAS_ABL + MENU_ITEM(submenu, MSG_LEVEL_BED, lcd_level_bed); + #endif #if HAS_M206_COMMAND // @@ -2158,7 +2111,7 @@ void kill_screen(const char* lcd_msg) { void _lcd_calibrate_homing() { if (lcdDrawUpdate) lcd_implementation_drawmenu_static(LCD_HEIGHT >= 4 ? 1 : 0, PSTR(MSG_LEVEL_BED_HOMING)); - lcdDrawUpdate = LCDVIEW_KEEP_REDRAWING; + lcdDrawUpdate = LCDVIEW_CALL_REDRAW_NEXT; if (axis_homed[X_AXIS] && axis_homed[Y_AXIS] && axis_homed[Z_AXIS]) lcd_goto_previous_menu(); } @@ -2292,7 +2245,7 @@ void kill_screen(const char* lcd_msg) { manual_move_to_current(axis); encoderPosition = 0; - lcdDrawUpdate = LCDVIEW_KEEP_REDRAWING; + lcdDrawUpdate = LCDVIEW_REDRAW_NOW; } if (lcdDrawUpdate) lcd_implementation_drawedit(name, ftostr41sign(current_position[axis])); } @@ -2314,7 +2267,7 @@ void kill_screen(const char* lcd_msg) { , eindex #endif ); - lcdDrawUpdate = LCDVIEW_KEEP_REDRAWING; + lcdDrawUpdate = LCDVIEW_REDRAW_NOW; } if (lcdDrawUpdate) { PGM_P pos_label; @@ -3243,7 +3196,7 @@ void kill_screen(const char* lcd_msg) { encoderPosition += ENCODER_STEPS_PER_MENU_ITEM; \ ++encoderLine; \ } \ - lcdDrawUpdate = LCDVIEW_KEEP_REDRAWING; \ + lcdDrawUpdate = LCDVIEW_CALL_REDRAW_NEXT; \ } \ ++_thisItemNr; \ } while(0) @@ -3775,9 +3728,9 @@ bool lcd_blink() { * - if (lcdDrawUpdate) { redraw } * - Before exiting the handler set lcdDrawUpdate to: * - LCDVIEW_CLEAR_CALL_REDRAW to clear screen and set LCDVIEW_CALL_REDRAW_NEXT. - * - LCDVIEW_REDRAW_NOW or LCDVIEW_NONE to keep drawing, but only in this loop. - * - LCDVIEW_CALL_REDRAW_NEXT to keep drawing and draw on the next loop also. - * - LCDVIEW_CALL_NO_REDRAW to keep drawing (or start drawing) with no redraw on the next loop. + * - 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. * @@ -3897,7 +3850,7 @@ void lcd_update() { encoderDiff = 0; } return_to_status_ms = ms + LCD_TIMEOUT_TO_STATUS; - lcdDrawUpdate = LCDVIEW_KEEP_REDRAWING; + lcdDrawUpdate = LCDVIEW_REDRAW_NOW; } #endif // ULTIPANEL From fb5e0ffe16be7ec4394aa485be4a855eb30cbee3 Mon Sep 17 00:00:00 2001 From: Thomas Moore Date: Fri, 26 May 2017 13:01:02 -0500 Subject: [PATCH 155/189] Unify M600 and M125 pause features (#6407) * Unify M600 and M125 pause features * Cleanup per thinkyhead's comments * Rename filament_change_menu_response to advanced_pause_menu_response * Include HAS_BED_PROBE in QUIET_PROBING * Update gMax example file * is_idle() is out of scope without the braces * Convert FT-i3-2020 to Advance Pause names... * Allow pause even if not printing --- Marlin/Conditionals_post.h | 2 +- Marlin/Configuration_adv.h | 31 +- Marlin/Marlin.h | 6 +- Marlin/Marlin_main.cpp | 616 ++++++++++-------- Marlin/SanityCheck.h | 45 +- Marlin/enum.h | 32 +- .../Cartesio/Configuration_adv.h | 31 +- .../Felix/Configuration_adv.h | 31 +- .../FolgerTech-i3-2020/Configuration_adv.h | 35 +- .../Hephestos/Configuration_adv.h | 31 +- .../Hephestos_2/Configuration_adv.h | 31 +- .../K8200/Configuration_adv.h | 31 +- .../K8400/Configuration_adv.h | 31 +- .../RigidBot/Configuration_adv.h | 31 +- .../SCARA/Configuration_adv.h | 31 +- .../TAZ4/Configuration_adv.h | 31 +- .../TinyBoy2/Configuration_adv.h | 31 +- .../WITBOX/Configuration_adv.h | 31 +- .../FLSUN/auto_calibrate/Configuration_adv.h | 31 +- .../FLSUN/kossel_mini/Configuration_adv.h | 31 +- .../delta/generic/Configuration_adv.h | 31 +- .../delta/kossel_mini/Configuration_adv.h | 31 +- .../delta/kossel_pro/Configuration_adv.h | 31 +- .../delta/kossel_xl/Configuration_adv.h | 31 +- .../gCreate_gMax1.5+/Configuration_adv.h | 33 +- .../makibox/Configuration_adv.h | 31 +- .../tvrrug/Round2/Configuration_adv.h | 31 +- .../wt150/Configuration_adv.h | 31 +- Marlin/language_an.h | 4 +- Marlin/language_bg.h | 4 +- Marlin/language_ca.h | 4 +- Marlin/language_cz.h | 4 +- Marlin/language_da.h | 4 +- Marlin/language_de.h | 4 +- Marlin/language_en.h | 7 +- Marlin/language_es.h | 4 +- Marlin/language_fr.h | 4 +- Marlin/language_gl.h | 4 +- Marlin/language_hr.h | 4 +- Marlin/language_it.h | 4 +- Marlin/language_kana.h | 4 +- Marlin/language_kana_utf8.h | 4 +- Marlin/language_nl.h | 4 +- Marlin/language_pl.h | 4 +- Marlin/language_tr.h | 4 +- Marlin/language_uk.h | 4 +- Marlin/language_zh_CN.h | 4 +- Marlin/language_zh_TW.h | 4 +- Marlin/temperature.cpp | 160 +++-- Marlin/temperature.h | 56 +- Marlin/ultralcd.cpp | 120 ++-- Marlin/ultralcd.h | 6 +- Marlin/ultralcd_impl_DOGM.h | 25 +- Marlin/ultralcd_impl_HD44780.h | 67 +- 54 files changed, 1091 insertions(+), 846 deletions(-) diff --git a/Marlin/Conditionals_post.h b/Marlin/Conditionals_post.h index 9fcd944ac..b0c281f1f 100644 --- a/Marlin/Conditionals_post.h +++ b/Marlin/Conditionals_post.h @@ -652,7 +652,7 @@ #if FAN_COUNT == 0 #undef PROBING_FANS_OFF #endif - #define QUIET_PROBING (ENABLED(PROBING_HEATERS_OFF) || ENABLED(PROBING_FANS_OFF)) + #define QUIET_PROBING (HAS_BED_PROBE && (ENABLED(PROBING_HEATERS_OFF) || ENABLED(PROBING_FANS_OFF))) /** * Servos and probes diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 515e66493..36291de0d 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -763,22 +763,23 @@ #endif /** - * Filament Change - * Experimental filament change support. + * Advanced Pause + * Experimental feature for filament change support and for parking the nozzle when paused. * Adds the GCode M600 for initiating filament change. + * If PARK_HEAD_ON_PAUSE enabled, adds the GCode M125 to pause printing and park the nozzle. * * Requires an LCD display. * This feature is required for the default FILAMENT_RUNOUT_SCRIPT. */ -//#define FILAMENT_CHANGE_FEATURE -#if ENABLED(FILAMENT_CHANGE_FEATURE) - #define FILAMENT_CHANGE_X_POS 3 // X position of hotend - #define FILAMENT_CHANGE_Y_POS 3 // Y position of hotend - #define FILAMENT_CHANGE_Z_ADD 10 // Z addition of hotend (lift) - #define FILAMENT_CHANGE_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) - #define FILAMENT_CHANGE_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) - #define FILAMENT_CHANGE_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s - #define FILAMENT_CHANGE_RETRACT_LENGTH 2 // Initial retract in mm +//#define ADVANCED_PAUSE_FEATURE +#if ENABLED(ADVANCED_PAUSE_FEATURE) + #define PAUSE_PARK_X_POS 3 // X position of hotend + #define PAUSE_PARK_Y_POS 3 // Y position of hotend + #define PAUSE_PARK_Z_ADD 10 // Z addition of hotend (lift) + #define PAUSE_PARK_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) + #define PAUSE_PARK_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) + #define PAUSE_PARK_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s + #define PAUSE_PARK_RETRACT_LENGTH 2 // Initial retract in mm // It is a short retract used immediately after print interrupt before move to filament exchange position #define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // Unload filament feedrate in mm/s - filament unloading can be fast #define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // Unload filament length from hotend in mm @@ -789,14 +790,14 @@ #define FILAMENT_CHANGE_LOAD_LENGTH 0 // Load filament length over hotend in mm // Longer length for bowden printers to fast load filament into whole bowden tube over the hotend, // Short or zero length for printers without bowden where loading is not used - #define FILAMENT_CHANGE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate - #define FILAMENT_CHANGE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, + #define ADVANCED_PAUSE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate + #define ADVANCED_PAUSE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, // 0 to disable for manual extrusion // Filament can be extruded repeatedly from the filament exchange menu to fill the hotend, // or until outcoming filament color is not clear for filament color change - #define FILAMENT_CHANGE_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds + #define PAUSE_PARK_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds #define FILAMENT_CHANGE_NUMBER_OF_ALERT_BEEPS 5 // Number of alert beeps before printer goes quiet - #define FILAMENT_CHANGE_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change + #define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change // even if it takes longer than DEFAULT_STEPPER_DEACTIVE_TIME. //#define PARK_HEAD_ON_PAUSE // Go to filament change position on pause, return to print position on resume #endif diff --git a/Marlin/Marlin.h b/Marlin/Marlin.h index aecd89b32..dcc9d0443 100644 --- a/Marlin/Marlin.h +++ b/Marlin/Marlin.h @@ -48,7 +48,7 @@ #endif void idle( - #if ENABLED(FILAMENT_CHANGE_FEATURE) + #if ENABLED(ADVANCED_PAUSE_FEATURE) bool no_stepper_sleep = false // pass true to keep steppers from disabling on timeout #endif ); @@ -369,8 +369,8 @@ extern float soft_endstop_min[XYZ], soft_endstop_max[XYZ]; extern int meas_delay_cm; // Delay distance #endif -#if ENABLED(FILAMENT_CHANGE_FEATURE) - extern FilamentChangeMenuResponse filament_change_menu_response; +#if ENABLED(ADVANCED_PAUSE_FEATURE) + extern AdvancedPauseMenuResponse advanced_pause_menu_response; #endif #if ENABLED(PID_EXTRUSION_SCALING) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 1806188a8..75edc0e6f 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -195,7 +195,7 @@ * M502 - Revert to the default "factory settings". ** Does not write them to EEPROM! ** * M503 - Print the current settings (in memory): "M503 S". S0 specifies compact output. * M540 - Enable/disable SD card abort on endstop hit: "M540 S". (Requires ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED) - * M600 - Pause for filament change: "M600 X Y Z E L". (Requires FILAMENT_CHANGE_FEATURE) + * M600 - Pause for filament change: "M600 X Y Z E L". (Requires ADVANCED_PAUSE_FEATURE) * M665 - Set delta configurations: "M665 L R S A B C I J K" (Requires DELTA) * M666 - Set delta endstop adjustment. (Requires DELTA) * M605 - Set dual x-carriage movement mode: "M605 S [X] [R]". (Requires DUAL_X_CARRIAGE) @@ -627,8 +627,8 @@ float cartes[XYZ] = { 0 }; static bool filament_ran_out = false; #endif -#if ENABLED(FILAMENT_CHANGE_FEATURE) - FilamentChangeMenuResponse filament_change_menu_response; +#if ENABLED(ADVANCED_PAUSE_FEATURE) + AdvancedPauseMenuResponse advanced_pause_menu_response; #endif #if ENABLED(MIXING_EXTRUDER) @@ -5738,14 +5738,244 @@ inline void gcode_M17() { #define RUNPLAN(RATE_MM_S) line_to_destination(RATE_MM_S) #endif -#if ENABLED(PARK_HEAD_ON_PAUSE) +#if ENABLED(ADVANCED_PAUSE_FEATURE) + + static float resume_position[XYZE]; + static bool move_away_flag = false; + #if ENABLED(SDSUPPORT) + static bool sd_print_paused = false; + #endif + + static void filament_change_beep(const int max_beep_count, const bool init=false) { + static millis_t next_buzz = 0; + static uint16_t runout_beep = 0; + + if (init) next_buzz = runout_beep = 0; + + const millis_t ms = millis(); + if (ELAPSED(ms, next_buzz)) { + if (max_beep_count < 0 || runout_beep < max_beep_count + 5) { // Only beep as long as we're supposed to + next_buzz = ms + ((max_beep_count < 0 || runout_beep < max_beep_count) ? 2500 : 400); + BUZZ(300, 2000); + runout_beep++; + } + } + } + + static bool pause_print(const float& retract, const float& z_lift, const float& x_pos, const float& y_pos, + const float& unload_length = 0 , int max_beep_count = 0, bool show_lcd = false) { + if (move_away_flag) return false; // already paused + + if (!DEBUGGING(DRYRUN) && thermalManager.tooColdToExtrude(active_extruder) && unload_length > 0) { + SERIAL_ERROR_START; + SERIAL_ERRORLNPGM(MSG_TOO_COLD_FOR_M600); + return false; + } + + const bool job_running = print_job_timer.isRunning(); + + // Indicate that the printer is paused + move_away_flag = true; + + // Pause the print job and timer + #if ENABLED(SDSUPPORT) + if (card.sdprinting) { + card.pauseSDPrint(); + sd_print_paused = true; + } + #endif + print_job_timer.pause(); + + // Show initial message and wait for synchronize steppers + if (show_lcd) { + #if ENABLED(ULTIPANEL) + lcd_advanced_pause_show_message(ADVANCED_PAUSE_MESSAGE_INIT); + #endif + } + stepper.synchronize(); + + // Save current position + COPY(resume_position, current_position); + set_destination_to_current(); + + // Initial retract before move to filament change position + destination[E_AXIS] += retract; + + RUNPLAN(PAUSE_PARK_RETRACT_FEEDRATE); + + // Lift Z axis + if (z_lift > 0) { + destination[Z_AXIS] += z_lift; + NOMORE(destination[Z_AXIS], Z_MAX_POS); + RUNPLAN(PAUSE_PARK_Z_FEEDRATE); + } + + // Move XY axes to filament exchange position + destination[X_AXIS] = x_pos; + destination[Y_AXIS] = y_pos; + + clamp_to_software_endstops(destination); + RUNPLAN(PAUSE_PARK_XY_FEEDRATE); + stepper.synchronize(); + + if (unload_length != 0) { + if (show_lcd) { + #if ENABLED(ULTIPANEL) + lcd_advanced_pause_show_message(ADVANCED_PAUSE_MESSAGE_UNLOAD); + idle(); + #endif + } + + // Unload filament + destination[E_AXIS] += unload_length; + RUNPLAN(FILAMENT_CHANGE_UNLOAD_FEEDRATE); + stepper.synchronize(); + + if (show_lcd) { + #if ENABLED(ULTIPANEL) + lcd_advanced_pause_show_message(ADVANCED_PAUSE_MESSAGE_INSERT); + #endif + } + + #if HAS_BUZZER + filament_change_beep(max_beep_count, true); + #endif + + idle(); + } + + // Disable extruders steppers for manual filament changing + disable_e_steppers(); + safe_delay(100); + + // Start the heater idle timers + const millis_t nozzle_timeout = (millis_t)(PAUSE_PARK_NOZZLE_TIMEOUT) * 1000UL; + + HOTEND_LOOP() + thermalManager.start_heater_idle_timer(e, nozzle_timeout); + + return true; + } + + static void wait_for_filament_reload(int max_beep_count = 0) { + bool nozzle_timed_out = false; + + // Wait for filament insert by user and press button + KEEPALIVE_STATE(PAUSED_FOR_USER); + wait_for_user = true; // LCD click or M108 will clear this + while (wait_for_user) { + #if HAS_BUZZER + filament_change_beep(max_beep_count); + #endif - float resume_position[XYZE]; - bool move_away_flag = false; + if (!nozzle_timed_out) + HOTEND_LOOP() + nozzle_timed_out |= thermalManager.is_heater_idle(e); + + #if ENABLED(ULTIPANEL) + if (nozzle_timed_out) + lcd_advanced_pause_show_message(ADVANCED_PAUSE_MESSAGE_CLICK_TO_HEAT_NOZZLE); + #endif + + idle(true); + } + KEEPALIVE_STATE(IN_HANDLER); + } + + static void resume_print(const float& load_length = 0, const float& initial_extrude_length = 0, int max_beep_count = 0) { + bool nozzle_timed_out = false; - inline void move_back_on_resume() { if (!move_away_flag) return; - move_away_flag = false; + + // Re-enable the heaters if they timed out + HOTEND_LOOP() { + nozzle_timed_out |= thermalManager.is_heater_idle(e); + thermalManager.reset_heater_idle_timer(e); + } + + #if ENABLED(ULTIPANEL) + // Show "wait for heating" + lcd_advanced_pause_show_message(ADVANCED_PAUSE_MESSAGE_WAIT_FOR_NOZZLES_TO_HEAT); + #endif + + wait_for_heatup = true; + while (wait_for_heatup) { + idle(); + wait_for_heatup = false; + HOTEND_LOOP() { + if (abs(thermalManager.degHotend(e) - thermalManager.degTargetHotend(e)) > 3) { + wait_for_heatup = true; + break; + } + } + } + + #if HAS_BUZZER + filament_change_beep(max_beep_count, true); + #endif + + if (load_length != 0) { + #if ENABLED(ULTIPANEL) + // Show "insert filament" + if (nozzle_timed_out) + lcd_advanced_pause_show_message(ADVANCED_PAUSE_MESSAGE_INSERT); + #endif + + KEEPALIVE_STATE(PAUSED_FOR_USER); + wait_for_user = true; // LCD click or M108 will clear this + while (wait_for_user && nozzle_timed_out) { + #if HAS_BUZZER + filament_change_beep(max_beep_count); + #endif + idle(true); + } + KEEPALIVE_STATE(IN_HANDLER); + + #if ENABLED(ULTIPANEL) + // Show "load" message + lcd_advanced_pause_show_message(ADVANCED_PAUSE_MESSAGE_LOAD); + #endif + + // Load filament + destination[E_AXIS] += load_length; + + RUNPLAN(FILAMENT_CHANGE_LOAD_FEEDRATE); + stepper.synchronize(); + } + + #if ENABLED(ULTIPANEL) && defined(ADVANCED_PAUSE_EXTRUDE_LENGTH) && ADVANCED_PAUSE_EXTRUDE_LENGTH > 0 + + float extrude_length = initial_extrude_length; + + do { + if (extrude_length > 0) { + // "Wait for filament extrude" + lcd_advanced_pause_show_message(ADVANCED_PAUSE_MESSAGE_EXTRUDE); + + // Extrude filament to get into hotend + destination[E_AXIS] += extrude_length; + RUNPLAN(ADVANCED_PAUSE_EXTRUDE_FEEDRATE); + stepper.synchronize(); + } + + // Show "Extrude More" / "Resume" menu and wait for reply + KEEPALIVE_STATE(PAUSED_FOR_USER); + wait_for_user = false; + lcd_advanced_pause_show_message(ADVANCED_PAUSE_MESSAGE_OPTION); + while (advanced_pause_menu_response == ADVANCED_PAUSE_RESPONSE_WAIT_FOR) idle(true); + KEEPALIVE_STATE(IN_HANDLER); + + extrude_length = ADVANCED_PAUSE_EXTRUDE_LENGTH; + + // Keep looping if "Extrude More" was selected + } while (advanced_pause_menu_response == ADVANCED_PAUSE_RESPONSE_EXTRUDE_MORE); + + #endif + + #if ENABLED(ULTIPANEL) + // "Wait for print to resume" + lcd_advanced_pause_show_message(ADVANCED_PAUSE_MESSAGE_RESUME); + #endif // Set extruder to saved position destination[E_AXIS] = current_position[E_AXIS] = resume_position[E_AXIS]; @@ -5753,24 +5983,38 @@ inline void gcode_M17() { #if IS_KINEMATIC // Move XYZ to starting position - planner.buffer_line_kinematic(lastpos, FILAMENT_CHANGE_XY_FEEDRATE, active_extruder); + planner.buffer_line_kinematic(lastpos, PAUSE_PARK_XY_FEEDRATE, active_extruder); #else // Move XY to starting position, then Z destination[X_AXIS] = resume_position[X_AXIS]; destination[Y_AXIS] = resume_position[Y_AXIS]; - RUNPLAN(FILAMENT_CHANGE_XY_FEEDRATE); + RUNPLAN(PAUSE_PARK_XY_FEEDRATE); destination[Z_AXIS] = resume_position[Z_AXIS]; - RUNPLAN(FILAMENT_CHANGE_Z_FEEDRATE); + RUNPLAN(PAUSE_PARK_Z_FEEDRATE); #endif stepper.synchronize(); #if ENABLED(FILAMENT_RUNOUT_SENSOR) filament_ran_out = false; #endif + set_current_to_destination(); - } -#endif // PARK_HEAD_ON_PAUSE + #if ENABLED(ULTIPANEL) + // Show status screen + lcd_advanced_pause_show_message(ADVANCED_PAUSE_MESSAGE_STATUS); + #endif + + #if ENABLED(SDSUPPORT) + if (sd_print_paused) { + card.startFileprint(); + sd_print_paused = false; + } + #endif + + move_away_flag = false; + } +#endif // ADVANCED_PAUSE_FEATURE #if ENABLED(SDSUPPORT) @@ -5803,7 +6047,7 @@ inline void gcode_M17() { */ inline void gcode_M24() { #if ENABLED(PARK_HEAD_ON_PAUSE) - move_back_on_resume(); + resume_print(); #endif card.startFileprint(); @@ -7462,89 +7706,55 @@ inline void gcode_M121() { endstops.enable_globally(false); } * Z = override Z raise */ inline void gcode_M125() { - if (move_away_flag) return; // already paused - - const bool job_running = print_job_timer.isRunning(); - - // there are blocks after this one, or sd printing - move_away_flag = job_running || planner.blocks_queued() - #if ENABLED(SDSUPPORT) - || card.sdprinting - #endif - ; - - if (!move_away_flag) return; // nothing to pause - - // M125 can be used to pause a print too - #if ENABLED(SDSUPPORT) - card.pauseSDPrint(); - #endif - print_job_timer.pause(); - - // Save current position - COPY(resume_position, current_position); - - set_destination_to_current(); // Initial retract before move to filament change position - destination[E_AXIS] += parser.seen('L') ? parser.value_axis_units(E_AXIS) : 0 - #if defined(FILAMENT_CHANGE_RETRACT_LENGTH) && FILAMENT_CHANGE_RETRACT_LENGTH > 0 - - (FILAMENT_CHANGE_RETRACT_LENGTH) + const float retract = parser.seen('L') ? parser.value_axis_units(E_AXIS) : 0 + #if defined(PAUSE_PARK_RETRACT_LENGTH) && PAUSE_PARK_RETRACT_LENGTH > 0 + - (PAUSE_PARK_RETRACT_LENGTH) #endif ; - RUNPLAN(FILAMENT_CHANGE_RETRACT_FEEDRATE); // Lift Z axis const float z_lift = parser.seen('Z') ? parser.value_linear_units() : - #if defined(FILAMENT_CHANGE_Z_ADD) && FILAMENT_CHANGE_Z_ADD > 0 - FILAMENT_CHANGE_Z_ADD + #if defined(PAUSE_PARK_Z_ADD) && PAUSE_PARK_Z_ADD > 0 + PAUSE_PARK_Z_ADD #else 0 #endif ; - if (z_lift > 0) { - destination[Z_AXIS] += z_lift; - NOMORE(destination[Z_AXIS], Z_MAX_POS); - RUNPLAN(FILAMENT_CHANGE_Z_FEEDRATE); - } // Move XY axes to filament change position or given position - destination[X_AXIS] = parser.seen('X') ? parser.value_linear_units() : 0 - #ifdef FILAMENT_CHANGE_X_POS - + FILAMENT_CHANGE_X_POS + const float x_pos = parser.seen('X') ? parser.value_linear_units() : 0 + #ifdef PAUSE_PARK_X_POS + + PAUSE_PARK_X_POS #endif ; - destination[Y_AXIS] = parser.seen('Y') ? parser.value_linear_units() : 0 - #ifdef FILAMENT_CHANGE_Y_POS - + FILAMENT_CHANGE_Y_POS + const float y_pos = parser.seen('Y') ? parser.value_linear_units() : 0 + #ifdef PAUSE_PARK_Y_POS + + PAUSE_PARK_Y_POS #endif ; #if HOTENDS > 1 && DISABLED(DUAL_X_CARRIAGE) if (active_extruder > 0) { - if (!parser.seen('X')) destination[X_AXIS] += hotend_offset[X_AXIS][active_extruder]; - if (!parser.seen('Y')) destination[Y_AXIS] += hotend_offset[Y_AXIS][active_extruder]; + if (!parser.seen('X')) x_pos += hotend_offset[X_AXIS][active_extruder]; + if (!parser.seen('Y')) y_pos += hotend_offset[Y_AXIS][active_extruder]; } #endif - clamp_to_software_endstops(destination); - RUNPLAN(FILAMENT_CHANGE_XY_FEEDRATE); - set_current_to_destination(); - stepper.synchronize(); - disable_e_steppers(); + const bool job_running = print_job_timer.isRunning(); - #if DISABLED(SDSUPPORT) - // Wait for lcd click or M108 - KEEPALIVE_STATE(PAUSED_FOR_USER); - wait_for_user = true; - while (wait_for_user) idle(); - KEEPALIVE_STATE(IN_HANDLER); + if (pause_print(retract, z_lift, x_pos, y_pos)) { + #if DISABLED(SDSUPPORT) + // Wait for lcd click or M108 + wait_for_filament_reload(); - // Return to print position and continue - move_back_on_resume(); - if (job_running) print_job_timer.start(); - move_away_flag = false; - #endif + // Return to print position and continue + resume_print(); + + if (job_running) print_job_timer.start(); + #endif + } } #endif // PARK_HEAD_ON_PAUSE @@ -8812,25 +9022,7 @@ inline void gcode_M503() { #endif // HAS_BED_PROBE -#if ENABLED(FILAMENT_CHANGE_FEATURE) - - void filament_change_beep(const bool init=false) { - static millis_t next_buzz = 0; - static uint16_t runout_beep = 0; - - if (init) next_buzz = runout_beep = 0; - - const millis_t ms = millis(); - if (ELAPSED(ms, next_buzz)) { - if (runout_beep <= FILAMENT_CHANGE_NUMBER_OF_ALERT_BEEPS + 5) { // Only beep as long as we're supposed to - next_buzz = ms + (runout_beep <= FILAMENT_CHANGE_NUMBER_OF_ALERT_BEEPS ? 2500 : 400); - BUZZ(300, 2000); - runout_beep++; - } - } - } - - static bool busy_doing_M600 = false; +#if ENABLED(ADVANCED_PAUSE_FEATURE) /** * M600: Pause for filament change @@ -8839,231 +9031,77 @@ inline void gcode_M503() { * Z[distance] - Move the Z axis by this distance * X[position] - Move to this X position, with Y * Y[position] - Move to this Y position, with X - * L[distance] - Retract distance for removal (manual reload) + * U[distance] - Retract distance for removal (negative value) (manual reload) + * L[distance] - Extrude distance for insertion (positive value) (manual reload) + * B[count] - Number of times to beep, -1 for indefinite (if equipped with a buzzer) * * Default values are used for omitted arguments. * */ inline void gcode_M600() { - if (!DEBUGGING(DRYRUN) && thermalManager.tooColdToExtrude(active_extruder)) { - SERIAL_ERROR_START; - SERIAL_ERRORLNPGM(MSG_TOO_COLD_FOR_M600); - return; - } - - busy_doing_M600 = true; // Stepper Motors can't timeout when this is set - - // Pause the print job timer - const bool job_running = print_job_timer.isRunning(); - - print_job_timer.pause(); - - // Show initial message and wait for synchronize steppers - lcd_filament_change_show_message(FILAMENT_CHANGE_MESSAGE_INIT); - stepper.synchronize(); - - // Save current position of all axes - float lastpos[XYZE]; - COPY(lastpos, current_position); - set_destination_to_current(); - // Initial retract before move to filament change position - destination[E_AXIS] += parser.seen('E') ? parser.value_axis_units(E_AXIS) : 0 - #if defined(FILAMENT_CHANGE_RETRACT_LENGTH) && FILAMENT_CHANGE_RETRACT_LENGTH > 0 - - (FILAMENT_CHANGE_RETRACT_LENGTH) + const float retract = parser.seen('E') ? parser.value_axis_units(E_AXIS) : 0 + #if defined(PAUSE_PARK_RETRACT_LENGTH) && PAUSE_PARK_RETRACT_LENGTH > 0 + - (PAUSE_PARK_RETRACT_LENGTH) #endif ; - RUNPLAN(FILAMENT_CHANGE_RETRACT_FEEDRATE); - // Lift Z axis - float z_lift = parser.seen('Z') ? parser.value_linear_units() : - #if defined(FILAMENT_CHANGE_Z_ADD) && FILAMENT_CHANGE_Z_ADD > 0 - FILAMENT_CHANGE_Z_ADD + const float z_lift = parser.seen('Z') ? parser.value_linear_units() : + #if defined(PAUSE_PARK_Z_ADD) && PAUSE_PARK_Z_ADD > 0 + PAUSE_PARK_Z_ADD #else 0 #endif ; - if (z_lift > 0) { - destination[Z_AXIS] += z_lift; - NOMORE(destination[Z_AXIS], Z_MAX_POS); - RUNPLAN(FILAMENT_CHANGE_Z_FEEDRATE); - } - // Move XY axes to filament exchange position - if (parser.seen('X')) destination[X_AXIS] = parser.value_linear_units(); - #ifdef FILAMENT_CHANGE_X_POS - else destination[X_AXIS] = FILAMENT_CHANGE_X_POS; - #endif - - if (parser.seen('Y')) destination[Y_AXIS] = parser.value_linear_units(); - #ifdef FILAMENT_CHANGE_Y_POS - else destination[Y_AXIS] = FILAMENT_CHANGE_Y_POS; - #endif - - RUNPLAN(FILAMENT_CHANGE_XY_FEEDRATE); - - stepper.synchronize(); - lcd_filament_change_show_message(FILAMENT_CHANGE_MESSAGE_UNLOAD); - idle(); - - // Unload filament - destination[E_AXIS] += parser.seen('L') ? parser.value_axis_units(E_AXIS) : 0 - #if FILAMENT_CHANGE_UNLOAD_LENGTH > 0 - - (FILAMENT_CHANGE_UNLOAD_LENGTH) + const float x_pos = parser.seen('X') ? parser.value_linear_units() : 0 + #ifdef PAUSE_PARK_X_POS + + PAUSE_PARK_X_POS #endif ; - - RUNPLAN(FILAMENT_CHANGE_UNLOAD_FEEDRATE); - - // Synchronize steppers and then disable extruders steppers for manual filament changing - stepper.synchronize(); - disable_e_steppers(); - safe_delay(100); - - const millis_t nozzle_timeout = millis() + (millis_t)(FILAMENT_CHANGE_NOZZLE_TIMEOUT) * 1000UL; - bool nozzle_timed_out = false; - - // Wait for filament insert by user and press button - lcd_filament_change_show_message(FILAMENT_CHANGE_MESSAGE_INSERT); - - #if HAS_BUZZER - filament_change_beep(true); - #endif - - idle(); - - int16_t temps[HOTENDS]; - HOTEND_LOOP() temps[e] = thermalManager.target_temperature[e]; // Save nozzle temps - - KEEPALIVE_STATE(PAUSED_FOR_USER); - wait_for_user = true; // LCD click or M108 will clear this - while (wait_for_user) { - - if (nozzle_timed_out) - lcd_filament_change_show_message(FILAMENT_CHANGE_MESSAGE_CLICK_TO_HEAT_NOZZLE); - - #if HAS_BUZZER - filament_change_beep(); + const float y_pos = parser.seen('Y') ? parser.value_linear_units() : 0 + #ifdef PAUSE_PARK_Y_POS + + PAUSE_PARK_Y_POS #endif + ; - if (!nozzle_timed_out && ELAPSED(millis(), nozzle_timeout)) { - nozzle_timed_out = true; // on nozzle timeout remember the nozzles need to be reheated - HOTEND_LOOP() thermalManager.setTargetHotend(0, e); // Turn off all the nozzles - lcd_filament_change_show_message(FILAMENT_CHANGE_MESSAGE_CLICK_TO_HEAT_NOZZLE); - } - idle(true); - } - KEEPALIVE_STATE(IN_HANDLER); - - if (nozzle_timed_out) // Turn nozzles back on if they were turned off - HOTEND_LOOP() thermalManager.setTargetHotend(temps[e], e); - - // Show "wait for heating" - lcd_filament_change_show_message(FILAMENT_CHANGE_MESSAGE_WAIT_FOR_NOZZLES_TO_HEAT); - - wait_for_heatup = true; - while (wait_for_heatup) { - idle(); - wait_for_heatup = false; - HOTEND_LOOP() { - if (abs(thermalManager.degHotend(e) - temps[e]) > 3) { - wait_for_heatup = true; - break; - } - } - } - - // Show "insert filament" - if (nozzle_timed_out) - lcd_filament_change_show_message(FILAMENT_CHANGE_MESSAGE_INSERT); - - #if HAS_BUZZER - filament_change_beep(true); - #endif - - KEEPALIVE_STATE(PAUSED_FOR_USER); - wait_for_user = true; // LCD click or M108 will clear this - while (wait_for_user && nozzle_timed_out) { - #if HAS_BUZZER - filament_change_beep(); + // Unload filament + const float unload_length = parser.seen('U') ? parser.value_axis_units(E_AXIS) : 0 + #if defined(FILAMENT_CHANGE_UNLOAD_LENGTH) && FILAMENT_CHANGE_UNLOAD_LENGTH > 0 + - (FILAMENT_CHANGE_UNLOAD_LENGTH) #endif - idle(true); - } - KEEPALIVE_STATE(IN_HANDLER); - - // Show "load" message - lcd_filament_change_show_message(FILAMENT_CHANGE_MESSAGE_LOAD); + ; // Load filament - destination[E_AXIS] += parser.seen('L') ? -parser.value_axis_units(E_AXIS) : 0 - #if FILAMENT_CHANGE_LOAD_LENGTH > 0 + const float load_length = parser.seen('L') ? parser.value_axis_units(E_AXIS) : 0 + #ifdef FILAMENT_CHANGE_LOAD_LENGTH + FILAMENT_CHANGE_LOAD_LENGTH #endif ; - RUNPLAN(FILAMENT_CHANGE_LOAD_FEEDRATE); - stepper.synchronize(); - - #if defined(FILAMENT_CHANGE_EXTRUDE_LENGTH) && FILAMENT_CHANGE_EXTRUDE_LENGTH > 0 - - do { - // "Wait for filament extrude" - lcd_filament_change_show_message(FILAMENT_CHANGE_MESSAGE_EXTRUDE); - - // Extrude filament to get into hotend - destination[E_AXIS] += FILAMENT_CHANGE_EXTRUDE_LENGTH; - RUNPLAN(FILAMENT_CHANGE_EXTRUDE_FEEDRATE); - stepper.synchronize(); - - // Show "Extrude More" / "Resume" menu and wait for reply - KEEPALIVE_STATE(PAUSED_FOR_USER); - wait_for_user = false; - lcd_filament_change_show_message(FILAMENT_CHANGE_MESSAGE_OPTION); - while (filament_change_menu_response == FILAMENT_CHANGE_RESPONSE_WAIT_FOR) idle(true); - KEEPALIVE_STATE(IN_HANDLER); - - // Keep looping if "Extrude More" was selected - } while (filament_change_menu_response == FILAMENT_CHANGE_RESPONSE_EXTRUDE_MORE); - - #endif - - // "Wait for print to resume" - lcd_filament_change_show_message(FILAMENT_CHANGE_MESSAGE_RESUME); - - // Set extruder to saved position - destination[E_AXIS] = current_position[E_AXIS] = lastpos[E_AXIS]; - planner.set_e_position_mm(current_position[E_AXIS]); - - #if IS_KINEMATIC - // Move XYZ to starting position - planner.buffer_line_kinematic(lastpos, FILAMENT_CHANGE_XY_FEEDRATE, active_extruder); - #else - // Move XY to starting position, then Z - destination[X_AXIS] = lastpos[X_AXIS]; - destination[Y_AXIS] = lastpos[Y_AXIS]; - RUNPLAN(FILAMENT_CHANGE_XY_FEEDRATE); - destination[Z_AXIS] = lastpos[Z_AXIS]; - RUNPLAN(FILAMENT_CHANGE_Z_FEEDRATE); - #endif - stepper.synchronize(); + const int beep_count = parser.seen('B') ? parser.value_int() : + #ifdef FILAMENT_CHANGE_NUMBER_OF_ALERT_BEEPS + FILAMENT_CHANGE_NUMBER_OF_ALERT_BEEPS + #else + -1 + #endif + ; - #if ENABLED(FILAMENT_RUNOUT_SENSOR) - filament_ran_out = false; - #endif + const bool job_running = print_job_timer.isRunning(); - // Show status screen - lcd_filament_change_show_message(FILAMENT_CHANGE_MESSAGE_STATUS); + if (pause_print(retract, z_lift, x_pos, y_pos, unload_length, beep_count, true)) { + wait_for_filament_reload(beep_count); + resume_print(load_length, ADVANCED_PAUSE_EXTRUDE_LENGTH, beep_count); + } // Resume the print job timer if it was running if (job_running) print_job_timer.start(); - - busy_doing_M600 = false; // Allow Stepper Motors to be turned off during inactivity } -#endif // FILAMENT_CHANGE_FEATURE +#endif // ADVANCED_PAUSE_FEATURE #if ENABLED(DUAL_X_CARRIAGE) @@ -10569,11 +10607,11 @@ void process_next_command() { break; #endif // HAS_BED_PROBE - #if ENABLED(FILAMENT_CHANGE_FEATURE) + #if ENABLED(ADVANCED_PAUSE_FEATURE) case 600: // M600: Pause for filament change gcode_M600(); break; - #endif // FILAMENT_CHANGE_FEATURE + #endif // ADVANCED_PAUSE_FEATURE #if ENABLED(DUAL_X_CARRIAGE) || ENABLED(DUAL_NOZZLE_DUPLICATION_MODE) case 605: // M605: Set Dual X Carriage movement mode @@ -12064,13 +12102,13 @@ void manage_inactivity(bool ignore_stepper_queue/*=false*/) { } // Prevent steppers timing-out in the middle of M600 - #if ENABLED(FILAMENT_CHANGE_FEATURE) && ENABLED(FILAMENT_CHANGE_NO_STEPPER_TIMEOUT) - #define M600_TEST !busy_doing_M600 + #if ENABLED(ADVANCED_PAUSE_FEATURE) && ENABLED(PAUSE_PARK_NO_STEPPER_TIMEOUT) + #define MOVE_AWAY_TEST !move_away_flag #else - #define M600_TEST true + #define MOVE_AWAY_TEST true #endif - if (M600_TEST && stepper_inactive_time && ELAPSED(ms, previous_cmd_ms + stepper_inactive_time) + if (MOVE_AWAY_TEST && stepper_inactive_time && ELAPSED(ms, previous_cmd_ms + stepper_inactive_time) && !ignore_stepper_queue && !planner.blocks_queued()) { #if ENABLED(DISABLE_INACTIVE_X) disable_X(); @@ -12216,7 +12254,7 @@ void manage_inactivity(bool ignore_stepper_queue/*=false*/) { * Standard idle routine keeps the machine alive */ void idle( - #if ENABLED(FILAMENT_CHANGE_FEATURE) + #if ENABLED(ADVANCED_PAUSE_FEATURE) bool no_stepper_sleep/*=false*/ #endif ) { @@ -12229,7 +12267,7 @@ void idle( #endif manage_inactivity( - #if ENABLED(FILAMENT_CHANGE_FEATURE) + #if ENABLED(ADVANCED_PAUSE_FEATURE) no_stepper_sleep #endif ); diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index 952200d14..f6c7245a2 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -99,7 +99,31 @@ #elif defined(SERVO_DEACTIVATION_DELAY) #error "SERVO_DEACTIVATION_DELAY is deprecated. Use SERVO_DELAY instead." #elif ENABLED(FILAMENTCHANGEENABLE) - #error "FILAMENTCHANGEENABLE is now FILAMENT_CHANGE_FEATURE. Please update your configuration." + #error "FILAMENTCHANGEENABLE is now ADVANCED_PAUSE_FEATURE. Please update your configuration." +#elif ENABLED(FILAMENT_CHANGE_FEATURE) + #error "FILAMENT_CHANGE_FEATURE is now ADVANCED_PAUSE_FEATURE. Please update your configuration." +#elif ENABLED(FILAMENT_CHANGE_X_POS) + #error "FILAMENT_CHANGE_X_POS is now PAUSE_PARK_X_POS. Please update your configuration." +#elif ENABLED(FILAMENT_CHANGE_Y_POS) + #error "FILAMENT_CHANGE_Y_POS is now PAUSE_PARK_Y_POS. Please update your configuration." +#elif ENABLED(FILAMENT_CHANGE_Z_ADD) + #error "FILAMENT_CHANGE_Z_ADD is now PAUSE_PARK_Z_ADD. Please update your configuration." +#elif ENABLED(FILAMENT_CHANGE_XY_FEEDRATE) + #error "FILAMENT_CHANGE_XY_FEEDRATE is now PAUSE_PARK_XY_FEEDRATE. Please update your configuration." +#elif ENABLED(FILAMENT_CHANGE_Z_FEEDRATE) + #error "FILAMENT_CHANGE_Z_FEEDRATE is now PAUSE_PARK_Z_FEEDRATE. Please update your configuration." +#elif ENABLED(FILAMENT_CHANGE_RETRACT_FEEDRATE) + #error "FILAMENT_CHANGE_RETRACT_FEEDRATE is now PAUSE_PARK_RETRACT_FEEDRATE. Please update your configuration." +#elif ENABLED(FILAMENT_CHANGE_RETRACT_LENGTH) + #error "FILAMENT_CHANGE_RETRACT_LENGTH is now PAUSE_PARK_RETRACT_LENGTH. Please update your configuration." +#elif ENABLED(FILAMENT_CHANGE_EXTRUDE_FEEDRATE) + #error "FILAMENT_CHANGE_EXTRUDE_FEEDRATE is now ADVANCED_PAUSE_EXTRUDE_FEEDRATE. Please update your configuration." +#elif ENABLED(FILAMENT_CHANGE_EXTRUDE_LENGTH) + #error "FILAMENT_CHANGE_EXTRUDE_LENGTH is now ADVANCED_PAUSE_EXTRUDE_LENGTH. Please update your configuration." +#elif ENABLED(FILAMENT_CHANGE_NOZZLE_TIMEOUT) + #error "FILAMENT_CHANGE_NOZZLE_TIMEOUT is now PAUSE_PARK_NOZZLE_TIMEOUT. Please update your configuration." +#elif ENABLED(FILAMENT_CHANGE_NO_STEPPER_TIMEOUT) + #error "FILAMENT_CHANGE_NO_STEPPER_TIMEOUT is now PAUSE_PARK_NO_STEPPER_TIMEOUT. Please update your configuration." #elif defined(PLA_PREHEAT_HOTEND_TEMP) #error "PLA_PREHEAT_HOTEND_TEMP is now PREHEAT_1_TEMP_HOTEND. Please update your configuration." #elif defined(PLA_PREHEAT_HPB_TEMP) @@ -286,19 +310,19 @@ #error "FILAMENT_RUNOUT_SENSOR requires FIL_RUNOUT_PIN." #elif DISABLED(SDSUPPORT) && DISABLED(PRINTJOB_TIMER_AUTOSTART) #error "FILAMENT_RUNOUT_SENSOR requires SDSUPPORT or PRINTJOB_TIMER_AUTOSTART." - #elif DISABLED(FILAMENT_CHANGE_FEATURE) - static_assert(NULL == strstr(FILAMENT_RUNOUT_SCRIPT, "M600"), "FILAMENT_CHANGE_FEATURE is required to use M600 with FILAMENT_RUNOUT_SENSOR."); + #elif DISABLED(ADVANCED_PAUSE_FEATURE) + static_assert(NULL == strstr(FILAMENT_RUNOUT_SCRIPT, "M600"), "ADVANCED_PAUSE_FEATURE is required to use M600 with FILAMENT_RUNOUT_SENSOR."); #endif #endif /** - * Filament Change with Extruder Runout Prevention + * Advanced Pause */ -#if ENABLED(FILAMENT_CHANGE_FEATURE) +#if ENABLED(ADVANCED_PAUSE_FEATURE) #if DISABLED(ULTIPANEL) - #error "FILAMENT_CHANGE_FEATURE currently requires an LCD controller." + #error "ADVANCED_PAUSE_FEATURE currently requires an LCD controller." #elif ENABLED(EXTRUDER_RUNOUT_PREVENT) - #error "EXTRUDER_RUNOUT_PREVENT is incompatible with FILAMENT_CHANGE_FEATURE." + #error "EXTRUDER_RUNOUT_PREVENT is incompatible with ADVANCED_PAUSE_FEATURE." #elif ENABLED(PARK_HEAD_ON_PAUSE) && DISABLED(SDSUPPORT) && DISABLED(ULTIPANEL) && DISABLED(EMERGENCY_PARSER) #error "PARK_HEAD_ON_PAUSE requires SDSUPPORT, EMERGENCY_PARSER, or an LCD controller." #endif @@ -545,6 +569,13 @@ static_assert(1 >= 0 #error "Probes need Z_CLEARANCE_BETWEEN_PROBES >= 0." #endif + /** + * Advanced Pause is required in order to turn the heaters off during probing + */ + #if (ENABLED(PROBING_HEATERS_OFF) && DISABLED(ADVANCED_PAUSE_FEATURE)) + #error "PROBING_HEATERS_OFF requires ADVANCED_PAUSE_FEATURE" + #endif + #else /** diff --git a/Marlin/enum.h b/Marlin/enum.h index 642e331b4..999164187 100644 --- a/Marlin/enum.h +++ b/Marlin/enum.h @@ -108,25 +108,25 @@ enum EndstopEnum { }; #endif -#if ENABLED(FILAMENT_CHANGE_FEATURE) - enum FilamentChangeMenuResponse { - FILAMENT_CHANGE_RESPONSE_WAIT_FOR, - FILAMENT_CHANGE_RESPONSE_EXTRUDE_MORE, - FILAMENT_CHANGE_RESPONSE_RESUME_PRINT +#if ENABLED(ADVANCED_PAUSE_FEATURE) + enum AdvancedPauseMenuResponse { + ADVANCED_PAUSE_RESPONSE_WAIT_FOR, + ADVANCED_PAUSE_RESPONSE_EXTRUDE_MORE, + ADVANCED_PAUSE_RESPONSE_RESUME_PRINT }; #if ENABLED(ULTIPANEL) - enum FilamentChangeMessage { - FILAMENT_CHANGE_MESSAGE_INIT, - FILAMENT_CHANGE_MESSAGE_UNLOAD, - FILAMENT_CHANGE_MESSAGE_INSERT, - FILAMENT_CHANGE_MESSAGE_LOAD, - FILAMENT_CHANGE_MESSAGE_EXTRUDE, - FILAMENT_CHANGE_MESSAGE_OPTION, - FILAMENT_CHANGE_MESSAGE_RESUME, - FILAMENT_CHANGE_MESSAGE_STATUS, - FILAMENT_CHANGE_MESSAGE_CLICK_TO_HEAT_NOZZLE, - FILAMENT_CHANGE_MESSAGE_WAIT_FOR_NOZZLES_TO_HEAT + enum AdvancedPauseMessage { + ADVANCED_PAUSE_MESSAGE_INIT, + ADVANCED_PAUSE_MESSAGE_UNLOAD, + ADVANCED_PAUSE_MESSAGE_INSERT, + ADVANCED_PAUSE_MESSAGE_LOAD, + ADVANCED_PAUSE_MESSAGE_EXTRUDE, + ADVANCED_PAUSE_MESSAGE_OPTION, + ADVANCED_PAUSE_MESSAGE_RESUME, + ADVANCED_PAUSE_MESSAGE_STATUS, + ADVANCED_PAUSE_MESSAGE_CLICK_TO_HEAT_NOZZLE, + ADVANCED_PAUSE_MESSAGE_WAIT_FOR_NOZZLES_TO_HEAT }; #endif #endif diff --git a/Marlin/example_configurations/Cartesio/Configuration_adv.h b/Marlin/example_configurations/Cartesio/Configuration_adv.h index 9e942e7cd..5a1184c93 100644 --- a/Marlin/example_configurations/Cartesio/Configuration_adv.h +++ b/Marlin/example_configurations/Cartesio/Configuration_adv.h @@ -756,22 +756,23 @@ #endif /** - * Filament Change - * Experimental filament change support. + * Advanced Pause + * Experimental feature for filament change support and for parking the nozzle when paused. * Adds the GCode M600 for initiating filament change. + * If PARK_HEAD_ON_PAUSE enabled, adds the GCode M125 to pause printing and park the nozzle. * * Requires an LCD display. * This feature is required for the default FILAMENT_RUNOUT_SCRIPT. */ -//#define FILAMENT_CHANGE_FEATURE -#if ENABLED(FILAMENT_CHANGE_FEATURE) - #define FILAMENT_CHANGE_X_POS 30 // X position of hotend - #define FILAMENT_CHANGE_Y_POS 10 // Y position of hotend - #define FILAMENT_CHANGE_Z_ADD 10 // Z addition of hotend (lift) - #define FILAMENT_CHANGE_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) - #define FILAMENT_CHANGE_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) - #define FILAMENT_CHANGE_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s - #define FILAMENT_CHANGE_RETRACT_LENGTH 1 // Initial retract in mm +//#define ADVANCED_PAUSE_FEATURE +#if ENABLED(ADVANCED_PAUSE_FEATURE) + #define PAUSE_PARK_X_POS 30 // X position of hotend + #define PAUSE_PARK_Y_POS 10 // Y position of hotend + #define PAUSE_PARK_Z_ADD 10 // Z addition of hotend (lift) + #define PAUSE_PARK_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) + #define PAUSE_PARK_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) + #define PAUSE_PARK_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s + #define PAUSE_PARK_RETRACT_LENGTH 1 // Initial retract in mm // It is a short retract used immediately after print interrupt before move to filament exchange position #define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // Unload filament feedrate in mm/s - filament unloading can be fast //#define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // Unload filament length from hotend in mm @@ -782,14 +783,14 @@ #define FILAMENT_CHANGE_LOAD_LENGTH 0 // Load filament length over hotend in mm // Longer length for bowden printers to fast load filament into whole bowden tube over the hotend, // Short or zero length for printers without bowden where loading is not used - #define FILAMENT_CHANGE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate - #define FILAMENT_CHANGE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, + #define ADVANCED_PAUSE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate + #define ADVANCED_PAUSE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, // 0 to disable for manual extrusion // Filament can be extruded repeatedly from the filament exchange menu to fill the hotend, // or until outcoming filament color is not clear for filament color change - #define FILAMENT_CHANGE_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds + #define PAUSE_PARK_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds #define FILAMENT_CHANGE_NUMBER_OF_ALERT_BEEPS 5 // Number of alert beeps before printer goes quiet - #define FILAMENT_CHANGE_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change + #define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change // even if it takes longer than DEFAULT_STEPPER_DEACTIVE_TIME. //#define PARK_HEAD_ON_PAUSE // Go to filament change position on pause, return to print position on resume #endif diff --git a/Marlin/example_configurations/Felix/Configuration_adv.h b/Marlin/example_configurations/Felix/Configuration_adv.h index f3329be78..a0daae4e6 100644 --- a/Marlin/example_configurations/Felix/Configuration_adv.h +++ b/Marlin/example_configurations/Felix/Configuration_adv.h @@ -756,22 +756,23 @@ #endif /** - * Filament Change - * Experimental filament change support. + * Advanced Pause + * Experimental feature for filament change support and for parking the nozzle when paused. * Adds the GCode M600 for initiating filament change. + * If PARK_HEAD_ON_PAUSE enabled, adds the GCode M125 to pause printing and park the nozzle. * * Requires an LCD display. * This feature is required for the default FILAMENT_RUNOUT_SCRIPT. */ -//#define FILAMENT_CHANGE_FEATURE -#if ENABLED(FILAMENT_CHANGE_FEATURE) - #define FILAMENT_CHANGE_X_POS 3 // X position of hotend - #define FILAMENT_CHANGE_Y_POS 3 // Y position of hotend - #define FILAMENT_CHANGE_Z_ADD 10 // Z addition of hotend (lift) - #define FILAMENT_CHANGE_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) - #define FILAMENT_CHANGE_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) - #define FILAMENT_CHANGE_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s - #define FILAMENT_CHANGE_RETRACT_LENGTH 2 // Initial retract in mm +//#define ADVANCED_PAUSE_FEATURE +#if ENABLED(ADVANCED_PAUSE_FEATURE) + #define PAUSE_PARK_X_POS 3 // X position of hotend + #define PAUSE_PARK_Y_POS 3 // Y position of hotend + #define PAUSE_PARK_Z_ADD 10 // Z addition of hotend (lift) + #define PAUSE_PARK_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) + #define PAUSE_PARK_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) + #define PAUSE_PARK_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s + #define PAUSE_PARK_RETRACT_LENGTH 2 // Initial retract in mm // It is a short retract used immediately after print interrupt before move to filament exchange position #define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // Unload filament feedrate in mm/s - filament unloading can be fast #define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // Unload filament length from hotend in mm @@ -782,14 +783,14 @@ #define FILAMENT_CHANGE_LOAD_LENGTH 0 // Load filament length over hotend in mm // Longer length for bowden printers to fast load filament into whole bowden tube over the hotend, // Short or zero length for printers without bowden where loading is not used - #define FILAMENT_CHANGE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate - #define FILAMENT_CHANGE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, + #define ADVANCED_PAUSE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate + #define ADVANCED_PAUSE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, // 0 to disable for manual extrusion // Filament can be extruded repeatedly from the filament exchange menu to fill the hotend, // or until outcoming filament color is not clear for filament color change - #define FILAMENT_CHANGE_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds + #define PAUSE_PARK_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds #define FILAMENT_CHANGE_NUMBER_OF_ALERT_BEEPS 5 // Number of alert beeps before printer goes quiet - #define FILAMENT_CHANGE_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change + #define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change // even if it takes longer than DEFAULT_STEPPER_DEACTIVE_TIME. //#define PARK_HEAD_ON_PAUSE // Go to filament change position on pause, return to print position on resume #endif diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h index e2cd30cc2..14488300c 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h @@ -763,22 +763,25 @@ #endif /** - * Filament Change - * Experimental filament change support. + * Advanced Pause + * Experimental feature for filament change support and for parking the nozzle when paused. * Adds the GCode M600 for initiating filament change. + * If PARK_HEAD_ON_PAUSE enabled, adds the GCode M125 to pause printing and park the nozzle. * * Requires an LCD display. * This feature is required for the default FILAMENT_RUNOUT_SCRIPT. */ -#define FILAMENT_CHANGE_FEATURE -#if ENABLED(FILAMENT_CHANGE_FEATURE) - #define FILAMENT_CHANGE_X_POS 3 // X position of hotend - #define FILAMENT_CHANGE_Y_POS 3 // Y position of hotend - #define FILAMENT_CHANGE_Z_ADD 10 // Z addition of hotend (lift) - #define FILAMENT_CHANGE_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) - #define FILAMENT_CHANGE_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) - #define FILAMENT_CHANGE_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s - #define FILAMENT_CHANGE_RETRACT_LENGTH 2 // Initial retract in mm + +#define ADVANCED_PAUSE_FEATURE +#if ENABLED(ADVANCED_PAUSE_FEATURE) + #define PAUSE_PARK_X_POS 10 // X position of hotend + #define PAUSE_PARK_Y_POS 10 // Y position of hotend + #define PAUSE_PARK_Z_ADD 10 // Z addition of hotend (lift) + #define PAUSE_PARK_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) + #define PAUSE_PARK_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) + #define PAUSE_PARK_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s + #define PAUSE_PARK_RETRACT_LENGTH 2 // Initial retract in mm + // It is a short retract used immediately after print interrupt before move to filament exchange position #define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // Unload filament feedrate in mm/s - filament unloading can be fast #define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // Unload filament length from hotend in mm @@ -789,16 +792,16 @@ #define FILAMENT_CHANGE_LOAD_LENGTH 0 // Load filament length over hotend in mm // Longer length for bowden printers to fast load filament into whole bowden tube over the hotend, // Short or zero length for printers without bowden where loading is not used - #define FILAMENT_CHANGE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate - #define FILAMENT_CHANGE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, + #define ADVANCED_PAUSE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate + #define ADVANCED_PAUSE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, // 0 to disable for manual extrusion // Filament can be extruded repeatedly from the filament exchange menu to fill the hotend, // or until outcoming filament color is not clear for filament color change - #define FILAMENT_CHANGE_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds + #define PAUSE_PARK_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds #define FILAMENT_CHANGE_NUMBER_OF_ALERT_BEEPS 5 // Number of alert beeps before printer goes quiet - #define FILAMENT_CHANGE_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change + #define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change // even if it takes longer than DEFAULT_STEPPER_DEACTIVE_TIME. - //#define PARK_HEAD_ON_PAUSE // Go to filament change position on pause, return to print position on resume + #define PARK_HEAD_ON_PAUSE // Go to filament change position on pause, return to print position on resume #endif // @section tmc diff --git a/Marlin/example_configurations/Hephestos/Configuration_adv.h b/Marlin/example_configurations/Hephestos/Configuration_adv.h index 4504ea3c9..e165a7fc3 100644 --- a/Marlin/example_configurations/Hephestos/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos/Configuration_adv.h @@ -756,22 +756,23 @@ #endif /** - * Filament Change - * Experimental filament change support. + * Advanced Pause + * Experimental feature for filament change support and for parking the nozzle when paused. * Adds the GCode M600 for initiating filament change. + * If PARK_HEAD_ON_PAUSE enabled, adds the GCode M125 to pause printing and park the nozzle. * * Requires an LCD display. * This feature is required for the default FILAMENT_RUNOUT_SCRIPT. */ -//#define FILAMENT_CHANGE_FEATURE -#if ENABLED(FILAMENT_CHANGE_FEATURE) - #define FILAMENT_CHANGE_X_POS 3 // X position of hotend - #define FILAMENT_CHANGE_Y_POS 3 // Y position of hotend - #define FILAMENT_CHANGE_Z_ADD 10 // Z addition of hotend (lift) - #define FILAMENT_CHANGE_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) - #define FILAMENT_CHANGE_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) - #define FILAMENT_CHANGE_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s - #define FILAMENT_CHANGE_RETRACT_LENGTH 2 // Initial retract in mm +//#define ADVANCED_PAUSE_FEATURE +#if ENABLED(ADVANCED_PAUSE_FEATURE) + #define PAUSE_PARK_X_POS 3 // X position of hotend + #define PAUSE_PARK_Y_POS 3 // Y position of hotend + #define PAUSE_PARK_Z_ADD 10 // Z addition of hotend (lift) + #define PAUSE_PARK_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) + #define PAUSE_PARK_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) + #define PAUSE_PARK_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s + #define PAUSE_PARK_RETRACT_LENGTH 2 // Initial retract in mm // It is a short retract used immediately after print interrupt before move to filament exchange position #define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // Unload filament feedrate in mm/s - filament unloading can be fast #define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // Unload filament length from hotend in mm @@ -782,14 +783,14 @@ #define FILAMENT_CHANGE_LOAD_LENGTH 0 // Load filament length over hotend in mm // Longer length for bowden printers to fast load filament into whole bowden tube over the hotend, // Short or zero length for printers without bowden where loading is not used - #define FILAMENT_CHANGE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate - #define FILAMENT_CHANGE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, + #define ADVANCED_PAUSE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate + #define ADVANCED_PAUSE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, // 0 to disable for manual extrusion // Filament can be extruded repeatedly from the filament exchange menu to fill the hotend, // or until outcoming filament color is not clear for filament color change - #define FILAMENT_CHANGE_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds + #define PAUSE_PARK_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds #define FILAMENT_CHANGE_NUMBER_OF_ALERT_BEEPS 5 // Number of alert beeps before printer goes quiet - #define FILAMENT_CHANGE_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change + #define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change // even if it takes longer than DEFAULT_STEPPER_DEACTIVE_TIME. //#define PARK_HEAD_ON_PAUSE // Go to filament change position on pause, return to print position on resume #endif diff --git a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h index c8629af1a..7fe59aa6d 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h @@ -740,22 +740,23 @@ #endif /** - * Filament Change - * Experimental filament change support. + * Advanced Pause + * Experimental feature for filament change support and for parking the nozzle when paused. * Adds the GCode M600 for initiating filament change. + * If PARK_HEAD_ON_PAUSE enabled, adds the GCode M125 to pause printing and park the nozzle. * * Requires an LCD display. * This feature is required for the default FILAMENT_RUNOUT_SCRIPT. */ -//#define FILAMENT_CHANGE_FEATURE -#if ENABLED(FILAMENT_CHANGE_FEATURE) - #define FILAMENT_CHANGE_X_POS 3 // X position of hotend - #define FILAMENT_CHANGE_Y_POS 3 // Y position of hotend - #define FILAMENT_CHANGE_Z_ADD 10 // Z addition of hotend (lift) - #define FILAMENT_CHANGE_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) - #define FILAMENT_CHANGE_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) - #define FILAMENT_CHANGE_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s - #define FILAMENT_CHANGE_RETRACT_LENGTH 2 // Initial retract in mm +//#define ADVANCED_PAUSE_FEATURE +#if ENABLED(ADVANCED_PAUSE_FEATURE) + #define PAUSE_PARK_X_POS 3 // X position of hotend + #define PAUSE_PARK_Y_POS 3 // Y position of hotend + #define PAUSE_PARK_Z_ADD 10 // Z addition of hotend (lift) + #define PAUSE_PARK_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) + #define PAUSE_PARK_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) + #define PAUSE_PARK_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s + #define PAUSE_PARK_RETRACT_LENGTH 2 // Initial retract in mm // It is a short retract used immediately after print interrupt before move to filament exchange position #define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // Unload filament feedrate in mm/s - filament unloading can be fast #define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // Unload filament length from hotend in mm @@ -766,14 +767,14 @@ #define FILAMENT_CHANGE_LOAD_LENGTH 0 // Load filament length over hotend in mm // Longer length for bowden printers to fast load filament into whole bowden tube over the hotend, // Short or zero length for printers without bowden where loading is not used - #define FILAMENT_CHANGE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate - #define FILAMENT_CHANGE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, + #define ADVANCED_PAUSE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate + #define ADVANCED_PAUSE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, // 0 to disable for manual extrusion // Filament can be extruded repeatedly from the filament exchange menu to fill the hotend, // or until outcoming filament color is not clear for filament color change - #define FILAMENT_CHANGE_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds + #define PAUSE_PARK_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds #define FILAMENT_CHANGE_NUMBER_OF_ALERT_BEEPS 5 // Number of alert beeps before printer goes quiet - #define FILAMENT_CHANGE_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change + #define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change // even if it takes longer than DEFAULT_STEPPER_DEACTIVE_TIME. //#define PARK_HEAD_ON_PAUSE // Go to filament change position on pause, return to print position on resume #endif diff --git a/Marlin/example_configurations/K8200/Configuration_adv.h b/Marlin/example_configurations/K8200/Configuration_adv.h index 821ea345d..2311850eb 100644 --- a/Marlin/example_configurations/K8200/Configuration_adv.h +++ b/Marlin/example_configurations/K8200/Configuration_adv.h @@ -769,22 +769,23 @@ #endif /** - * Filament Change - * Experimental filament change support. + * Advanced Pause + * Experimental feature for filament change support and for parking the nozzle when paused. * Adds the GCode M600 for initiating filament change. + * If PARK_HEAD_ON_PAUSE enabled, adds the GCode M125 to pause printing and park the nozzle. * * Requires an LCD display. * This feature is required for the default FILAMENT_RUNOUT_SCRIPT. */ -//#define FILAMENT_CHANGE_FEATURE -#if ENABLED(FILAMENT_CHANGE_FEATURE) - #define FILAMENT_CHANGE_X_POS (X_MAX_POS-3) // X position of hotend - #define FILAMENT_CHANGE_Y_POS 3 // Y position of hotend - #define FILAMENT_CHANGE_Z_ADD 10 // Z addition of hotend (lift) - #define FILAMENT_CHANGE_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) - #define FILAMENT_CHANGE_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) - #define FILAMENT_CHANGE_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s - #define FILAMENT_CHANGE_RETRACT_LENGTH 2 // Initial retract in mm +//#define ADVANCED_PAUSE_FEATURE +#if ENABLED(ADVANCED_PAUSE_FEATURE) + #define PAUSE_PARK_X_POS (X_MAX_POS-3) // X position of hotend + #define PAUSE_PARK_Y_POS 3 // Y position of hotend + #define PAUSE_PARK_Z_ADD 10 // Z addition of hotend (lift) + #define PAUSE_PARK_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) + #define PAUSE_PARK_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) + #define PAUSE_PARK_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s + #define PAUSE_PARK_RETRACT_LENGTH 2 // Initial retract in mm // It is a short retract used immediately after print interrupt before move to filament exchange position #define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // Unload filament feedrate in mm/s - filament unloading can be fast #define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // Unload filament length from hotend in mm @@ -795,14 +796,14 @@ #define FILAMENT_CHANGE_LOAD_LENGTH 0 // Load filament length over hotend in mm // Longer length for bowden printers to fast load filament into whole bowden tube over the hotend, // Short or zero length for printers without bowden where loading is not used - #define FILAMENT_CHANGE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate - #define FILAMENT_CHANGE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, + #define ADVANCED_PAUSE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate + #define ADVANCED_PAUSE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, // 0 to disable for manual extrusion // Filament can be extruded repeatedly from the filament exchange menu to fill the hotend, // or until outcoming filament color is not clear for filament color change - #define FILAMENT_CHANGE_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds + #define PAUSE_PARK_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds #define FILAMENT_CHANGE_NUMBER_OF_ALERT_BEEPS 5 // Number of alert beeps before printer goes quiet - #define FILAMENT_CHANGE_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change + #define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change // even if it takes longer than DEFAULT_STEPPER_DEACTIVE_TIME. //#define PARK_HEAD_ON_PAUSE // Go to filament change position on pause, return to print position on resume #endif diff --git a/Marlin/example_configurations/K8400/Configuration_adv.h b/Marlin/example_configurations/K8400/Configuration_adv.h index f85b55e99..538c121d8 100644 --- a/Marlin/example_configurations/K8400/Configuration_adv.h +++ b/Marlin/example_configurations/K8400/Configuration_adv.h @@ -756,22 +756,23 @@ #endif /** - * Filament Change - * Experimental filament change support. + * Advanced Pause + * Experimental feature for filament change support and for parking the nozzle when paused. * Adds the GCode M600 for initiating filament change. + * If PARK_HEAD_ON_PAUSE enabled, adds the GCode M125 to pause printing and park the nozzle. * * Requires an LCD display. * This feature is required for the default FILAMENT_RUNOUT_SCRIPT. */ -//#define FILAMENT_CHANGE_FEATURE -#if ENABLED(FILAMENT_CHANGE_FEATURE) - #define FILAMENT_CHANGE_X_POS 100 // X position of hotend - #define FILAMENT_CHANGE_Y_POS 100 // Y position of hotend - #define FILAMENT_CHANGE_Z_ADD 20 // Z addition of hotend (lift) - #define FILAMENT_CHANGE_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) - #define FILAMENT_CHANGE_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) - #define FILAMENT_CHANGE_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s - #define FILAMENT_CHANGE_RETRACT_LENGTH 5 // Initial retract in mm +//#define ADVANCED_PAUSE_FEATURE +#if ENABLED(ADVANCED_PAUSE_FEATURE) + #define PAUSE_PARK_X_POS 100 // X position of hotend + #define PAUSE_PARK_Y_POS 100 // Y position of hotend + #define PAUSE_PARK_Z_ADD 20 // Z addition of hotend (lift) + #define PAUSE_PARK_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) + #define PAUSE_PARK_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) + #define PAUSE_PARK_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s + #define PAUSE_PARK_RETRACT_LENGTH 5 // Initial retract in mm // It is a short retract used immediately after print interrupt before move to filament exchange position #define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // Unload filament feedrate in mm/s - filament unloading can be fast #define FILAMENT_CHANGE_UNLOAD_LENGTH 600 // Unload filament length from hotend in mm @@ -782,14 +783,14 @@ #define FILAMENT_CHANGE_LOAD_LENGTH 0 // Load filament length over hotend in mm // Longer length for bowden printers to fast load filament into whole bowden tube over the hotend, // Short or zero length for printers without bowden where loading is not used - #define FILAMENT_CHANGE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate - #define FILAMENT_CHANGE_EXTRUDE_LENGTH 100 // Extrude filament length in mm after filament is loaded over the hotend, + #define ADVANCED_PAUSE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate + #define ADVANCED_PAUSE_EXTRUDE_LENGTH 100 // Extrude filament length in mm after filament is loaded over the hotend, // 0 to disable for manual extrusion // Filament can be extruded repeatedly from the filament exchange menu to fill the hotend, // or until outcoming filament color is not clear for filament color change - #define FILAMENT_CHANGE_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds + #define PAUSE_PARK_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds #define FILAMENT_CHANGE_NUMBER_OF_ALERT_BEEPS 5 // Number of alert beeps before printer goes quiet - #define FILAMENT_CHANGE_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change + #define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change // even if it takes longer than DEFAULT_STEPPER_DEACTIVE_TIME. //#define PARK_HEAD_ON_PAUSE // Go to filament change position on pause, return to print position on resume #endif diff --git a/Marlin/example_configurations/RigidBot/Configuration_adv.h b/Marlin/example_configurations/RigidBot/Configuration_adv.h index 8b278778c..0df6dfc18 100644 --- a/Marlin/example_configurations/RigidBot/Configuration_adv.h +++ b/Marlin/example_configurations/RigidBot/Configuration_adv.h @@ -756,22 +756,23 @@ #endif /** - * Filament Change - * Experimental filament change support. + * Advanced Pause + * Experimental feature for filament change support and for parking the nozzle when paused. * Adds the GCode M600 for initiating filament change. + * If PARK_HEAD_ON_PAUSE enabled, adds the GCode M125 to pause printing and park the nozzle. * * Requires an LCD display. * This feature is required for the default FILAMENT_RUNOUT_SCRIPT. */ -//#define FILAMENT_CHANGE_FEATURE -#if ENABLED(FILAMENT_CHANGE_FEATURE) - #define FILAMENT_CHANGE_X_POS 3 // X position of hotend - #define FILAMENT_CHANGE_Y_POS 3 // Y position of hotend - #define FILAMENT_CHANGE_Z_ADD 10 // Z addition of hotend (lift) - #define FILAMENT_CHANGE_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) - #define FILAMENT_CHANGE_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) - #define FILAMENT_CHANGE_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s - #define FILAMENT_CHANGE_RETRACT_LENGTH 2 // Initial retract in mm +//#define ADVANCED_PAUSE_FEATURE +#if ENABLED(ADVANCED_PAUSE_FEATURE) + #define PAUSE_PARK_X_POS 3 // X position of hotend + #define PAUSE_PARK_Y_POS 3 // Y position of hotend + #define PAUSE_PARK_Z_ADD 10 // Z addition of hotend (lift) + #define PAUSE_PARK_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) + #define PAUSE_PARK_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) + #define PAUSE_PARK_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s + #define PAUSE_PARK_RETRACT_LENGTH 2 // Initial retract in mm // It is a short retract used immediately after print interrupt before move to filament exchange position #define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // Unload filament feedrate in mm/s - filament unloading can be fast #define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // Unload filament length from hotend in mm @@ -782,14 +783,14 @@ #define FILAMENT_CHANGE_LOAD_LENGTH 0 // Load filament length over hotend in mm // Longer length for bowden printers to fast load filament into whole bowden tube over the hotend, // Short or zero length for printers without bowden where loading is not used - #define FILAMENT_CHANGE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate - #define FILAMENT_CHANGE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, + #define ADVANCED_PAUSE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate + #define ADVANCED_PAUSE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, // 0 to disable for manual extrusion // Filament can be extruded repeatedly from the filament exchange menu to fill the hotend, // or until outcoming filament color is not clear for filament color change - #define FILAMENT_CHANGE_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds + #define PAUSE_PARK_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds #define FILAMENT_CHANGE_NUMBER_OF_ALERT_BEEPS 5 // Number of alert beeps before printer goes quiet - #define FILAMENT_CHANGE_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change + #define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change // even if it takes longer than DEFAULT_STEPPER_DEACTIVE_TIME. //#define PARK_HEAD_ON_PAUSE // Go to filament change position on pause, return to print position on resume #endif diff --git a/Marlin/example_configurations/SCARA/Configuration_adv.h b/Marlin/example_configurations/SCARA/Configuration_adv.h index e3e327588..60b47073c 100644 --- a/Marlin/example_configurations/SCARA/Configuration_adv.h +++ b/Marlin/example_configurations/SCARA/Configuration_adv.h @@ -756,22 +756,23 @@ #endif /** - * Filament Change - * Experimental filament change support. + * Advanced Pause + * Experimental feature for filament change support and for parking the nozzle when paused. * Adds the GCode M600 for initiating filament change. + * If PARK_HEAD_ON_PAUSE enabled, adds the GCode M125 to pause printing and park the nozzle. * * Requires an LCD display. * This feature is required for the default FILAMENT_RUNOUT_SCRIPT. */ -//#define FILAMENT_CHANGE_FEATURE -#if ENABLED(FILAMENT_CHANGE_FEATURE) - #define FILAMENT_CHANGE_X_POS 3 // X position of hotend - #define FILAMENT_CHANGE_Y_POS 3 // Y position of hotend - #define FILAMENT_CHANGE_Z_ADD 10 // Z addition of hotend (lift) - #define FILAMENT_CHANGE_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) - #define FILAMENT_CHANGE_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) - #define FILAMENT_CHANGE_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s - #define FILAMENT_CHANGE_RETRACT_LENGTH 2 // Initial retract in mm +//#define ADVANCED_PAUSE_FEATURE +#if ENABLED(ADVANCED_PAUSE_FEATURE) + #define PAUSE_PARK_X_POS 3 // X position of hotend + #define PAUSE_PARK_Y_POS 3 // Y position of hotend + #define PAUSE_PARK_Z_ADD 10 // Z addition of hotend (lift) + #define PAUSE_PARK_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) + #define PAUSE_PARK_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) + #define PAUSE_PARK_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s + #define PAUSE_PARK_RETRACT_LENGTH 2 // Initial retract in mm // It is a short retract used immediately after print interrupt before move to filament exchange position #define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // Unload filament feedrate in mm/s - filament unloading can be fast #define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // Unload filament length from hotend in mm @@ -782,14 +783,14 @@ #define FILAMENT_CHANGE_LOAD_LENGTH 0 // Load filament length over hotend in mm // Longer length for bowden printers to fast load filament into whole bowden tube over the hotend, // Short or zero length for printers without bowden where loading is not used - #define FILAMENT_CHANGE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate - #define FILAMENT_CHANGE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, + #define ADVANCED_PAUSE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate + #define ADVANCED_PAUSE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, // 0 to disable for manual extrusion // Filament can be extruded repeatedly from the filament exchange menu to fill the hotend, // or until outcoming filament color is not clear for filament color change - #define FILAMENT_CHANGE_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds + #define PAUSE_PARK_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds #define FILAMENT_CHANGE_NUMBER_OF_ALERT_BEEPS 5 // Number of alert beeps before printer goes quiet - #define FILAMENT_CHANGE_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change + #define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change // even if it takes longer than DEFAULT_STEPPER_DEACTIVE_TIME. //#define PARK_HEAD_ON_PAUSE // Go to filament change position on pause, return to print position on resume #endif diff --git a/Marlin/example_configurations/TAZ4/Configuration_adv.h b/Marlin/example_configurations/TAZ4/Configuration_adv.h index 86d5353df..7bc66c6d4 100644 --- a/Marlin/example_configurations/TAZ4/Configuration_adv.h +++ b/Marlin/example_configurations/TAZ4/Configuration_adv.h @@ -756,22 +756,23 @@ #endif /** - * Filament Change - * Experimental filament change support. + * Advanced Pause + * Experimental feature for filament change support and for parking the nozzle when paused. * Adds the GCode M600 for initiating filament change. + * If PARK_HEAD_ON_PAUSE enabled, adds the GCode M125 to pause printing and park the nozzle. * * Requires an LCD display. * This feature is required for the default FILAMENT_RUNOUT_SCRIPT. */ -//#define FILAMENT_CHANGE_FEATURE -#if ENABLED(FILAMENT_CHANGE_FEATURE) - #define FILAMENT_CHANGE_X_POS 3 // X position of hotend - #define FILAMENT_CHANGE_Y_POS 3 // Y position of hotend - #define FILAMENT_CHANGE_Z_ADD 10 // Z addition of hotend (lift) - #define FILAMENT_CHANGE_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) - #define FILAMENT_CHANGE_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) - #define FILAMENT_CHANGE_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s - #define FILAMENT_CHANGE_RETRACT_LENGTH 2 // Initial retract in mm +//#define ADVANCED_PAUSE_FEATURE +#if ENABLED(ADVANCED_PAUSE_FEATURE) + #define PAUSE_PARK_X_POS 3 // X position of hotend + #define PAUSE_PARK_Y_POS 3 // Y position of hotend + #define PAUSE_PARK_Z_ADD 10 // Z addition of hotend (lift) + #define PAUSE_PARK_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) + #define PAUSE_PARK_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) + #define PAUSE_PARK_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s + #define PAUSE_PARK_RETRACT_LENGTH 2 // Initial retract in mm // It is a short retract used immediately after print interrupt before move to filament exchange position #define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // Unload filament feedrate in mm/s - filament unloading can be fast #define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // Unload filament length from hotend in mm @@ -782,14 +783,14 @@ #define FILAMENT_CHANGE_LOAD_LENGTH 0 // Load filament length over hotend in mm // Longer length for bowden printers to fast load filament into whole bowden tube over the hotend, // Short or zero length for printers without bowden where loading is not used - #define FILAMENT_CHANGE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate - #define FILAMENT_CHANGE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, + #define ADVANCED_PAUSE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate + #define ADVANCED_PAUSE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, // 0 to disable for manual extrusion // Filament can be extruded repeatedly from the filament exchange menu to fill the hotend, // or until outcoming filament color is not clear for filament color change - #define FILAMENT_CHANGE_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds + #define PAUSE_PARK_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds #define FILAMENT_CHANGE_NUMBER_OF_ALERT_BEEPS 5 // Number of alert beeps before printer goes quiet - #define FILAMENT_CHANGE_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change + #define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change // even if it takes longer than DEFAULT_STEPPER_DEACTIVE_TIME. //#define PARK_HEAD_ON_PAUSE // Go to filament change position on pause, return to print position on resume #endif diff --git a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h index 82c1f030d..36623187d 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h @@ -759,22 +759,23 @@ #endif /** - * Filament Change - * Experimental filament change support. + * Advanced Pause + * Experimental feature for filament change support and for parking the nozzle when paused. * Adds the GCode M600 for initiating filament change. + * If PARK_HEAD_ON_PAUSE enabled, adds the GCode M125 to pause printing and park the nozzle. * * Requires an LCD display. * This feature is required for the default FILAMENT_RUNOUT_SCRIPT. */ -//#define FILAMENT_CHANGE_FEATURE -#if ENABLED(FILAMENT_CHANGE_FEATURE) - #define FILAMENT_CHANGE_X_POS 3 // X position of hotend - #define FILAMENT_CHANGE_Y_POS 3 // Y position of hotend - #define FILAMENT_CHANGE_Z_ADD 10 // Z addition of hotend (lift) - #define FILAMENT_CHANGE_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) - #define FILAMENT_CHANGE_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) - #define FILAMENT_CHANGE_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s - #define FILAMENT_CHANGE_RETRACT_LENGTH 2 // Initial retract in mm +//#define ADVANCED_PAUSE_FEATURE +#if ENABLED(ADVANCED_PAUSE_FEATURE) + #define PAUSE_PARK_X_POS 3 // X position of hotend + #define PAUSE_PARK_Y_POS 3 // Y position of hotend + #define PAUSE_PARK_Z_ADD 10 // Z addition of hotend (lift) + #define PAUSE_PARK_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) + #define PAUSE_PARK_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) + #define PAUSE_PARK_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s + #define PAUSE_PARK_RETRACT_LENGTH 2 // Initial retract in mm // It is a short retract used immediately after print interrupt before move to filament exchange position #define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // Unload filament feedrate in mm/s - filament unloading can be fast #define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // Unload filament length from hotend in mm @@ -785,14 +786,14 @@ #define FILAMENT_CHANGE_LOAD_LENGTH 0 // Load filament length over hotend in mm // Longer length for bowden printers to fast load filament into whole bowden tube over the hotend, // Short or zero length for printers without bowden where loading is not used - #define FILAMENT_CHANGE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate - #define FILAMENT_CHANGE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, + #define ADVANCED_PAUSE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate + #define ADVANCED_PAUSE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, // 0 to disable for manual extrusion // Filament can be extruded repeatedly from the filament exchange menu to fill the hotend, // or until outcoming filament color is not clear for filament color change - #define FILAMENT_CHANGE_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds + #define PAUSE_PARK_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds #define FILAMENT_CHANGE_NUMBER_OF_ALERT_BEEPS 5 // Number of alert beeps before printer goes quiet - #define FILAMENT_CHANGE_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change + #define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change // even if it takes longer than DEFAULT_STEPPER_DEACTIVE_TIME. //#define PARK_HEAD_ON_PAUSE // Go to filament change position on pause, return to print position on resume #endif diff --git a/Marlin/example_configurations/WITBOX/Configuration_adv.h b/Marlin/example_configurations/WITBOX/Configuration_adv.h index 4504ea3c9..e165a7fc3 100644 --- a/Marlin/example_configurations/WITBOX/Configuration_adv.h +++ b/Marlin/example_configurations/WITBOX/Configuration_adv.h @@ -756,22 +756,23 @@ #endif /** - * Filament Change - * Experimental filament change support. + * Advanced Pause + * Experimental feature for filament change support and for parking the nozzle when paused. * Adds the GCode M600 for initiating filament change. + * If PARK_HEAD_ON_PAUSE enabled, adds the GCode M125 to pause printing and park the nozzle. * * Requires an LCD display. * This feature is required for the default FILAMENT_RUNOUT_SCRIPT. */ -//#define FILAMENT_CHANGE_FEATURE -#if ENABLED(FILAMENT_CHANGE_FEATURE) - #define FILAMENT_CHANGE_X_POS 3 // X position of hotend - #define FILAMENT_CHANGE_Y_POS 3 // Y position of hotend - #define FILAMENT_CHANGE_Z_ADD 10 // Z addition of hotend (lift) - #define FILAMENT_CHANGE_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) - #define FILAMENT_CHANGE_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) - #define FILAMENT_CHANGE_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s - #define FILAMENT_CHANGE_RETRACT_LENGTH 2 // Initial retract in mm +//#define ADVANCED_PAUSE_FEATURE +#if ENABLED(ADVANCED_PAUSE_FEATURE) + #define PAUSE_PARK_X_POS 3 // X position of hotend + #define PAUSE_PARK_Y_POS 3 // Y position of hotend + #define PAUSE_PARK_Z_ADD 10 // Z addition of hotend (lift) + #define PAUSE_PARK_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) + #define PAUSE_PARK_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) + #define PAUSE_PARK_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s + #define PAUSE_PARK_RETRACT_LENGTH 2 // Initial retract in mm // It is a short retract used immediately after print interrupt before move to filament exchange position #define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // Unload filament feedrate in mm/s - filament unloading can be fast #define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // Unload filament length from hotend in mm @@ -782,14 +783,14 @@ #define FILAMENT_CHANGE_LOAD_LENGTH 0 // Load filament length over hotend in mm // Longer length for bowden printers to fast load filament into whole bowden tube over the hotend, // Short or zero length for printers without bowden where loading is not used - #define FILAMENT_CHANGE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate - #define FILAMENT_CHANGE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, + #define ADVANCED_PAUSE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate + #define ADVANCED_PAUSE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, // 0 to disable for manual extrusion // Filament can be extruded repeatedly from the filament exchange menu to fill the hotend, // or until outcoming filament color is not clear for filament color change - #define FILAMENT_CHANGE_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds + #define PAUSE_PARK_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds #define FILAMENT_CHANGE_NUMBER_OF_ALERT_BEEPS 5 // Number of alert beeps before printer goes quiet - #define FILAMENT_CHANGE_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change + #define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change // even if it takes longer than DEFAULT_STEPPER_DEACTIVE_TIME. //#define PARK_HEAD_ON_PAUSE // Go to filament change position on pause, return to print position on resume #endif diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h index 5e5f5ca73..62eaf358b 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h @@ -761,22 +761,23 @@ #endif /** - * Filament Change - * Experimental filament change support. + * Advanced Pause + * Experimental feature for filament change support and for parking the nozzle when paused. * Adds the GCode M600 for initiating filament change. + * If PARK_HEAD_ON_PAUSE enabled, adds the GCode M125 to pause printing and park the nozzle. * * Requires an LCD display. * This feature is required for the default FILAMENT_RUNOUT_SCRIPT. */ -//#define FILAMENT_CHANGE_FEATURE -#if ENABLED(FILAMENT_CHANGE_FEATURE) - #define FILAMENT_CHANGE_X_POS 3 // X position of hotend - #define FILAMENT_CHANGE_Y_POS 3 // Y position of hotend - #define FILAMENT_CHANGE_Z_ADD 10 // Z addition of hotend (lift) - #define FILAMENT_CHANGE_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) - #define FILAMENT_CHANGE_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) - #define FILAMENT_CHANGE_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s - #define FILAMENT_CHANGE_RETRACT_LENGTH 2 // Initial retract in mm +//#define ADVANCED_PAUSE_FEATURE +#if ENABLED(ADVANCED_PAUSE_FEATURE) + #define PAUSE_PARK_X_POS 3 // X position of hotend + #define PAUSE_PARK_Y_POS 3 // Y position of hotend + #define PAUSE_PARK_Z_ADD 10 // Z addition of hotend (lift) + #define PAUSE_PARK_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) + #define PAUSE_PARK_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) + #define PAUSE_PARK_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s + #define PAUSE_PARK_RETRACT_LENGTH 2 // Initial retract in mm // It is a short retract used immediately after print interrupt before move to filament exchange position #define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // Unload filament feedrate in mm/s - filament unloading can be fast #define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // Unload filament length from hotend in mm @@ -787,14 +788,14 @@ #define FILAMENT_CHANGE_LOAD_LENGTH 0 // Load filament length over hotend in mm // Longer length for bowden printers to fast load filament into whole bowden tube over the hotend, // Short or zero length for printers without bowden where loading is not used - #define FILAMENT_CHANGE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate - #define FILAMENT_CHANGE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, + #define ADVANCED_PAUSE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate + #define ADVANCED_PAUSE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, // 0 to disable for manual extrusion // Filament can be extruded repeatedly from the filament exchange menu to fill the hotend, // or until outcoming filament color is not clear for filament color change - #define FILAMENT_CHANGE_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds + #define PAUSE_PARK_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds #define FILAMENT_CHANGE_NUMBER_OF_ALERT_BEEPS 5 // Number of alert beeps before printer goes quiet - #define FILAMENT_CHANGE_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change + #define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change // even if it takes longer than DEFAULT_STEPPER_DEACTIVE_TIME. //#define PARK_HEAD_ON_PAUSE // Go to filament change position on pause, return to print position on resume #endif diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h index fa5a1de66..6ad9e985f 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h @@ -760,22 +760,23 @@ #endif /** - * Filament Change - * Experimental filament change support. + * Advanced Pause + * Experimental feature for filament change support and for parking the nozzle when paused. * Adds the GCode M600 for initiating filament change. + * If PARK_HEAD_ON_PAUSE enabled, adds the GCode M125 to pause printing and park the nozzle. * * Requires an LCD display. * This feature is required for the default FILAMENT_RUNOUT_SCRIPT. */ -//#define FILAMENT_CHANGE_FEATURE -#if ENABLED(FILAMENT_CHANGE_FEATURE) - #define FILAMENT_CHANGE_X_POS 3 // X position of hotend - #define FILAMENT_CHANGE_Y_POS 3 // Y position of hotend - #define FILAMENT_CHANGE_Z_ADD 10 // Z addition of hotend (lift) - #define FILAMENT_CHANGE_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) - #define FILAMENT_CHANGE_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) - #define FILAMENT_CHANGE_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s - #define FILAMENT_CHANGE_RETRACT_LENGTH 2 // Initial retract in mm +//#define ADVANCED_PAUSE_FEATURE +#if ENABLED(ADVANCED_PAUSE_FEATURE) + #define PAUSE_PARK_X_POS 3 // X position of hotend + #define PAUSE_PARK_Y_POS 3 // Y position of hotend + #define PAUSE_PARK_Z_ADD 10 // Z addition of hotend (lift) + #define PAUSE_PARK_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) + #define PAUSE_PARK_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) + #define PAUSE_PARK_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s + #define PAUSE_PARK_RETRACT_LENGTH 2 // Initial retract in mm // It is a short retract used immediately after print interrupt before move to filament exchange position #define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // Unload filament feedrate in mm/s - filament unloading can be fast #define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // Unload filament length from hotend in mm @@ -786,14 +787,14 @@ #define FILAMENT_CHANGE_LOAD_LENGTH 0 // Load filament length over hotend in mm // Longer length for bowden printers to fast load filament into whole bowden tube over the hotend, // Short or zero length for printers without bowden where loading is not used - #define FILAMENT_CHANGE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate - #define FILAMENT_CHANGE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, + #define ADVANCED_PAUSE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate + #define ADVANCED_PAUSE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, // 0 to disable for manual extrusion // Filament can be extruded repeatedly from the filament exchange menu to fill the hotend, // or until outcoming filament color is not clear for filament color change - #define FILAMENT_CHANGE_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds + #define PAUSE_PARK_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds #define FILAMENT_CHANGE_NUMBER_OF_ALERT_BEEPS 5 // Number of alert beeps before printer goes quiet - #define FILAMENT_CHANGE_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change + #define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change // even if it takes longer than DEFAULT_STEPPER_DEACTIVE_TIME. //#define PARK_HEAD_ON_PAUSE // Go to filament change position on pause, return to print position on resume #endif diff --git a/Marlin/example_configurations/delta/generic/Configuration_adv.h b/Marlin/example_configurations/delta/generic/Configuration_adv.h index e0d7e538d..2664b31be 100644 --- a/Marlin/example_configurations/delta/generic/Configuration_adv.h +++ b/Marlin/example_configurations/delta/generic/Configuration_adv.h @@ -758,22 +758,23 @@ #endif /** - * Filament Change - * Experimental filament change support. + * Advanced Pause + * Experimental feature for filament change support and for parking the nozzle when paused. * Adds the GCode M600 for initiating filament change. + * If PARK_HEAD_ON_PAUSE enabled, adds the GCode M125 to pause printing and park the nozzle. * * Requires an LCD display. * This feature is required for the default FILAMENT_RUNOUT_SCRIPT. */ -//#define FILAMENT_CHANGE_FEATURE -#if ENABLED(FILAMENT_CHANGE_FEATURE) - #define FILAMENT_CHANGE_X_POS 3 // X position of hotend - #define FILAMENT_CHANGE_Y_POS 3 // Y position of hotend - #define FILAMENT_CHANGE_Z_ADD 10 // Z addition of hotend (lift) - #define FILAMENT_CHANGE_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) - #define FILAMENT_CHANGE_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) - #define FILAMENT_CHANGE_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s - #define FILAMENT_CHANGE_RETRACT_LENGTH 2 // Initial retract in mm +//#define ADVANCED_PAUSE_FEATURE +#if ENABLED(ADVANCED_PAUSE_FEATURE) + #define PAUSE_PARK_X_POS 3 // X position of hotend + #define PAUSE_PARK_Y_POS 3 // Y position of hotend + #define PAUSE_PARK_Z_ADD 10 // Z addition of hotend (lift) + #define PAUSE_PARK_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) + #define PAUSE_PARK_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) + #define PAUSE_PARK_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s + #define PAUSE_PARK_RETRACT_LENGTH 2 // Initial retract in mm // It is a short retract used immediately after print interrupt before move to filament exchange position #define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // Unload filament feedrate in mm/s - filament unloading can be fast #define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // Unload filament length from hotend in mm @@ -784,14 +785,14 @@ #define FILAMENT_CHANGE_LOAD_LENGTH 0 // Load filament length over hotend in mm // Longer length for bowden printers to fast load filament into whole bowden tube over the hotend, // Short or zero length for printers without bowden where loading is not used - #define FILAMENT_CHANGE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate - #define FILAMENT_CHANGE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, + #define ADVANCED_PAUSE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate + #define ADVANCED_PAUSE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, // 0 to disable for manual extrusion // Filament can be extruded repeatedly from the filament exchange menu to fill the hotend, // or until outcoming filament color is not clear for filament color change - #define FILAMENT_CHANGE_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds + #define PAUSE_PARK_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds #define FILAMENT_CHANGE_NUMBER_OF_ALERT_BEEPS 5 // Number of alert beeps before printer goes quiet - #define FILAMENT_CHANGE_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change + #define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change // even if it takes longer than DEFAULT_STEPPER_DEACTIVE_TIME. //#define PARK_HEAD_ON_PAUSE // Go to filament change position on pause, return to print position on resume #endif diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h index e0d7e538d..2664b31be 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h @@ -758,22 +758,23 @@ #endif /** - * Filament Change - * Experimental filament change support. + * Advanced Pause + * Experimental feature for filament change support and for parking the nozzle when paused. * Adds the GCode M600 for initiating filament change. + * If PARK_HEAD_ON_PAUSE enabled, adds the GCode M125 to pause printing and park the nozzle. * * Requires an LCD display. * This feature is required for the default FILAMENT_RUNOUT_SCRIPT. */ -//#define FILAMENT_CHANGE_FEATURE -#if ENABLED(FILAMENT_CHANGE_FEATURE) - #define FILAMENT_CHANGE_X_POS 3 // X position of hotend - #define FILAMENT_CHANGE_Y_POS 3 // Y position of hotend - #define FILAMENT_CHANGE_Z_ADD 10 // Z addition of hotend (lift) - #define FILAMENT_CHANGE_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) - #define FILAMENT_CHANGE_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) - #define FILAMENT_CHANGE_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s - #define FILAMENT_CHANGE_RETRACT_LENGTH 2 // Initial retract in mm +//#define ADVANCED_PAUSE_FEATURE +#if ENABLED(ADVANCED_PAUSE_FEATURE) + #define PAUSE_PARK_X_POS 3 // X position of hotend + #define PAUSE_PARK_Y_POS 3 // Y position of hotend + #define PAUSE_PARK_Z_ADD 10 // Z addition of hotend (lift) + #define PAUSE_PARK_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) + #define PAUSE_PARK_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) + #define PAUSE_PARK_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s + #define PAUSE_PARK_RETRACT_LENGTH 2 // Initial retract in mm // It is a short retract used immediately after print interrupt before move to filament exchange position #define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // Unload filament feedrate in mm/s - filament unloading can be fast #define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // Unload filament length from hotend in mm @@ -784,14 +785,14 @@ #define FILAMENT_CHANGE_LOAD_LENGTH 0 // Load filament length over hotend in mm // Longer length for bowden printers to fast load filament into whole bowden tube over the hotend, // Short or zero length for printers without bowden where loading is not used - #define FILAMENT_CHANGE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate - #define FILAMENT_CHANGE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, + #define ADVANCED_PAUSE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate + #define ADVANCED_PAUSE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, // 0 to disable for manual extrusion // Filament can be extruded repeatedly from the filament exchange menu to fill the hotend, // or until outcoming filament color is not clear for filament color change - #define FILAMENT_CHANGE_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds + #define PAUSE_PARK_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds #define FILAMENT_CHANGE_NUMBER_OF_ALERT_BEEPS 5 // Number of alert beeps before printer goes quiet - #define FILAMENT_CHANGE_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change + #define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change // even if it takes longer than DEFAULT_STEPPER_DEACTIVE_TIME. //#define PARK_HEAD_ON_PAUSE // Go to filament change position on pause, return to print position on resume #endif diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h index d7e7c7ebc..e7142cf16 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h @@ -763,22 +763,23 @@ #endif /** - * Filament Change - * Experimental filament change support. + * Advanced Pause + * Experimental feature for filament change support and for parking the nozzle when paused. * Adds the GCode M600 for initiating filament change. + * If PARK_HEAD_ON_PAUSE enabled, adds the GCode M125 to pause printing and park the nozzle. * * Requires an LCD display. * This feature is required for the default FILAMENT_RUNOUT_SCRIPT. */ -//#define FILAMENT_CHANGE_FEATURE -#if ENABLED(FILAMENT_CHANGE_FEATURE) - #define FILAMENT_CHANGE_X_POS 3 // X position of hotend - #define FILAMENT_CHANGE_Y_POS 3 // Y position of hotend - #define FILAMENT_CHANGE_Z_ADD 10 // Z addition of hotend (lift) - #define FILAMENT_CHANGE_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) - #define FILAMENT_CHANGE_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) - #define FILAMENT_CHANGE_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s - #define FILAMENT_CHANGE_RETRACT_LENGTH 2 // Initial retract in mm +//#define ADVANCED_PAUSE_FEATURE +#if ENABLED(ADVANCED_PAUSE_FEATURE) + #define PAUSE_PARK_X_POS 3 // X position of hotend + #define PAUSE_PARK_Y_POS 3 // Y position of hotend + #define PAUSE_PARK_Z_ADD 10 // Z addition of hotend (lift) + #define PAUSE_PARK_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) + #define PAUSE_PARK_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) + #define PAUSE_PARK_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s + #define PAUSE_PARK_RETRACT_LENGTH 2 // Initial retract in mm // It is a short retract used immediately after print interrupt before move to filament exchange position #define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // Unload filament feedrate in mm/s - filament unloading can be fast #define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // Unload filament length from hotend in mm @@ -789,14 +790,14 @@ #define FILAMENT_CHANGE_LOAD_LENGTH 0 // Load filament length over hotend in mm // Longer length for bowden printers to fast load filament into whole bowden tube over the hotend, // Short or zero length for printers without bowden where loading is not used - #define FILAMENT_CHANGE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate - #define FILAMENT_CHANGE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, + #define ADVANCED_PAUSE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate + #define ADVANCED_PAUSE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, // 0 to disable for manual extrusion // Filament can be extruded repeatedly from the filament exchange menu to fill the hotend, // or until outcoming filament color is not clear for filament color change - #define FILAMENT_CHANGE_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds + #define PAUSE_PARK_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds #define FILAMENT_CHANGE_NUMBER_OF_ALERT_BEEPS 5 // Number of alert beeps before printer goes quiet - #define FILAMENT_CHANGE_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change + #define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change // even if it takes longer than DEFAULT_STEPPER_DEACTIVE_TIME. //#define PARK_HEAD_ON_PAUSE // Go to filament change position on pause, return to print position on resume #endif diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h index 33515e271..e1fe86a0e 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h @@ -758,22 +758,23 @@ #endif /** - * Filament Change - * Experimental filament change support. + * Advanced Pause + * Experimental feature for filament change support and for parking the nozzle when paused. * Adds the GCode M600 for initiating filament change. + * If PARK_HEAD_ON_PAUSE enabled, adds the GCode M125 to pause printing and park the nozzle. * * Requires an LCD display. * This feature is required for the default FILAMENT_RUNOUT_SCRIPT. */ -//#define FILAMENT_CHANGE_FEATURE -#if ENABLED(FILAMENT_CHANGE_FEATURE) - #define FILAMENT_CHANGE_X_POS 3 // X position of hotend - #define FILAMENT_CHANGE_Y_POS 3 // Y position of hotend - #define FILAMENT_CHANGE_Z_ADD 10 // Z addition of hotend (lift) - #define FILAMENT_CHANGE_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) - #define FILAMENT_CHANGE_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) - #define FILAMENT_CHANGE_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s - #define FILAMENT_CHANGE_RETRACT_LENGTH 2 // Initial retract in mm +//#define ADVANCED_PAUSE_FEATURE +#if ENABLED(ADVANCED_PAUSE_FEATURE) + #define PAUSE_PARK_X_POS 3 // X position of hotend + #define PAUSE_PARK_Y_POS 3 // Y position of hotend + #define PAUSE_PARK_Z_ADD 10 // Z addition of hotend (lift) + #define PAUSE_PARK_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) + #define PAUSE_PARK_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) + #define PAUSE_PARK_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s + #define PAUSE_PARK_RETRACT_LENGTH 2 // Initial retract in mm // It is a short retract used immediately after print interrupt before move to filament exchange position #define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // Unload filament feedrate in mm/s - filament unloading can be fast #define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // Unload filament length from hotend in mm @@ -784,14 +785,14 @@ #define FILAMENT_CHANGE_LOAD_LENGTH 0 // Load filament length over hotend in mm // Longer length for bowden printers to fast load filament into whole bowden tube over the hotend, // Short or zero length for printers without bowden where loading is not used - #define FILAMENT_CHANGE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate - #define FILAMENT_CHANGE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, + #define ADVANCED_PAUSE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate + #define ADVANCED_PAUSE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, // 0 to disable for manual extrusion // Filament can be extruded repeatedly from the filament exchange menu to fill the hotend, // or until outcoming filament color is not clear for filament color change - #define FILAMENT_CHANGE_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds + #define PAUSE_PARK_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds #define FILAMENT_CHANGE_NUMBER_OF_ALERT_BEEPS 5 // Number of alert beeps before printer goes quiet - #define FILAMENT_CHANGE_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change + #define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change // even if it takes longer than DEFAULT_STEPPER_DEACTIVE_TIME. //#define PARK_HEAD_ON_PAUSE // Go to filament change position on pause, return to print position on resume #endif diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h index 65fb22c3c..59b43ccb6 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h @@ -763,22 +763,25 @@ #endif /** - * Filament Change - * Experimental filament change support. + * Advanced Pause + * Experimental feature for filament change support and for parking the nozzle when paused. * Adds the GCode M600 for initiating filament change. + * If PARK_HEAD_ON_PAUSE enabled, adds the GCode M125 to pause printing and park the nozzle. * * Requires an LCD display. * This feature is required for the default FILAMENT_RUNOUT_SCRIPT. */ -#define FILAMENT_CHANGE_FEATURE -#if ENABLED(FILAMENT_CHANGE_FEATURE) - #define FILAMENT_CHANGE_X_POS 3 // X position of hotend - #define FILAMENT_CHANGE_Y_POS 3 // Y position of hotend - #define FILAMENT_CHANGE_Z_ADD 10 // Z addition of hotend (lift) - #define FILAMENT_CHANGE_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) - #define FILAMENT_CHANGE_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) - #define FILAMENT_CHANGE_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s - #define FILAMENT_CHANGE_RETRACT_LENGTH 2 // Initial retract in mm + +#define ADVANCED_PAUSE_FEATURE +#if ENABLED(ADVANCED_PAUSE_FEATURE) + #define PAUSE_PARK_X_POS 75 // X position of hotend + #define PAUSE_PARK_Y_POS 75 // Y position of hotend + #define PAUSE_PARK_Z_ADD 10 // Z addition of hotend (lift) + #define PAUSE_PARK_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) + #define PAUSE_PARK_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) + #define PAUSE_PARK_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s + #define PAUSE_PARK_RETRACT_LENGTH 2 // Initial retract in mm + // It is a short retract used immediately after print interrupt before move to filament exchange position #define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // Unload filament feedrate in mm/s - filament unloading can be fast #define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // Unload filament length from hotend in mm @@ -789,14 +792,14 @@ #define FILAMENT_CHANGE_LOAD_LENGTH 0 // Load filament length over hotend in mm // Longer length for bowden printers to fast load filament into whole bowden tube over the hotend, // Short or zero length for printers without bowden where loading is not used - #define FILAMENT_CHANGE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate - #define FILAMENT_CHANGE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, + #define ADVANCED_PAUSE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate + #define ADVANCED_PAUSE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, // 0 to disable for manual extrusion // Filament can be extruded repeatedly from the filament exchange menu to fill the hotend, // or until outcoming filament color is not clear for filament color change - #define FILAMENT_CHANGE_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds + #define PAUSE_PARK_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds #define FILAMENT_CHANGE_NUMBER_OF_ALERT_BEEPS 5 // Number of alert beeps before printer goes quiet - #define FILAMENT_CHANGE_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change + #define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change // even if it takes longer than DEFAULT_STEPPER_DEACTIVE_TIME. #define PARK_HEAD_ON_PAUSE // Go to filament change position on pause, return to print position on resume #endif diff --git a/Marlin/example_configurations/makibox/Configuration_adv.h b/Marlin/example_configurations/makibox/Configuration_adv.h index 49e41368d..5483576d9 100644 --- a/Marlin/example_configurations/makibox/Configuration_adv.h +++ b/Marlin/example_configurations/makibox/Configuration_adv.h @@ -756,22 +756,23 @@ #endif /** - * Filament Change - * Experimental filament change support. + * Advanced Pause + * Experimental feature for filament change support and for parking the nozzle when paused. * Adds the GCode M600 for initiating filament change. + * If PARK_HEAD_ON_PAUSE enabled, adds the GCode M125 to pause printing and park the nozzle. * * Requires an LCD display. * This feature is required for the default FILAMENT_RUNOUT_SCRIPT. */ -//#define FILAMENT_CHANGE_FEATURE -#if ENABLED(FILAMENT_CHANGE_FEATURE) - #define FILAMENT_CHANGE_X_POS 3 // X position of hotend - #define FILAMENT_CHANGE_Y_POS 3 // Y position of hotend - #define FILAMENT_CHANGE_Z_ADD 10 // Z addition of hotend (lift) - #define FILAMENT_CHANGE_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) - #define FILAMENT_CHANGE_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) - #define FILAMENT_CHANGE_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s - #define FILAMENT_CHANGE_RETRACT_LENGTH 2 // Initial retract in mm +//#define ADVANCED_PAUSE_FEATURE +#if ENABLED(ADVANCED_PAUSE_FEATURE) + #define PAUSE_PARK_X_POS 3 // X position of hotend + #define PAUSE_PARK_Y_POS 3 // Y position of hotend + #define PAUSE_PARK_Z_ADD 10 // Z addition of hotend (lift) + #define PAUSE_PARK_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) + #define PAUSE_PARK_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) + #define PAUSE_PARK_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s + #define PAUSE_PARK_RETRACT_LENGTH 2 // Initial retract in mm // It is a short retract used immediately after print interrupt before move to filament exchange position #define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // Unload filament feedrate in mm/s - filament unloading can be fast #define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // Unload filament length from hotend in mm @@ -782,14 +783,14 @@ #define FILAMENT_CHANGE_LOAD_LENGTH 0 // Load filament length over hotend in mm // Longer length for bowden printers to fast load filament into whole bowden tube over the hotend, // Short or zero length for printers without bowden where loading is not used - #define FILAMENT_CHANGE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate - #define FILAMENT_CHANGE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, + #define ADVANCED_PAUSE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate + #define ADVANCED_PAUSE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, // 0 to disable for manual extrusion // Filament can be extruded repeatedly from the filament exchange menu to fill the hotend, // or until outcoming filament color is not clear for filament color change - #define FILAMENT_CHANGE_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds + #define PAUSE_PARK_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds #define FILAMENT_CHANGE_NUMBER_OF_ALERT_BEEPS 5 // Number of alert beeps before printer goes quiet - #define FILAMENT_CHANGE_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change + #define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change // even if it takes longer than DEFAULT_STEPPER_DEACTIVE_TIME. //#define PARK_HEAD_ON_PAUSE // Go to filament change position on pause, return to print position on resume #endif diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h index a5441c127..8dcc348ab 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h @@ -756,22 +756,23 @@ #endif /** - * Filament Change - * Experimental filament change support. + * Advanced Pause + * Experimental feature for filament change support and for parking the nozzle when paused. * Adds the GCode M600 for initiating filament change. + * If PARK_HEAD_ON_PAUSE enabled, adds the GCode M125 to pause printing and park the nozzle. * * Requires an LCD display. * This feature is required for the default FILAMENT_RUNOUT_SCRIPT. */ -//#define FILAMENT_CHANGE_FEATURE -#if ENABLED(FILAMENT_CHANGE_FEATURE) - #define FILAMENT_CHANGE_X_POS 3 // X position of hotend - #define FILAMENT_CHANGE_Y_POS 3 // Y position of hotend - #define FILAMENT_CHANGE_Z_ADD 10 // Z addition of hotend (lift) - #define FILAMENT_CHANGE_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) - #define FILAMENT_CHANGE_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) - #define FILAMENT_CHANGE_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s - #define FILAMENT_CHANGE_RETRACT_LENGTH 2 // Initial retract in mm +//#define ADVANCED_PAUSE_FEATURE +#if ENABLED(ADVANCED_PAUSE_FEATURE) + #define PAUSE_PARK_X_POS 3 // X position of hotend + #define PAUSE_PARK_Y_POS 3 // Y position of hotend + #define PAUSE_PARK_Z_ADD 10 // Z addition of hotend (lift) + #define PAUSE_PARK_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) + #define PAUSE_PARK_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) + #define PAUSE_PARK_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s + #define PAUSE_PARK_RETRACT_LENGTH 2 // Initial retract in mm // It is a short retract used immediately after print interrupt before move to filament exchange position #define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // Unload filament feedrate in mm/s - filament unloading can be fast #define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // Unload filament length from hotend in mm @@ -782,14 +783,14 @@ #define FILAMENT_CHANGE_LOAD_LENGTH 0 // Load filament length over hotend in mm // Longer length for bowden printers to fast load filament into whole bowden tube over the hotend, // Short or zero length for printers without bowden where loading is not used - #define FILAMENT_CHANGE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate - #define FILAMENT_CHANGE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, + #define ADVANCED_PAUSE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate + #define ADVANCED_PAUSE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, // 0 to disable for manual extrusion // Filament can be extruded repeatedly from the filament exchange menu to fill the hotend, // or until outcoming filament color is not clear for filament color change - #define FILAMENT_CHANGE_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds + #define PAUSE_PARK_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds #define FILAMENT_CHANGE_NUMBER_OF_ALERT_BEEPS 5 // Number of alert beeps before printer goes quiet - #define FILAMENT_CHANGE_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change + #define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change // even if it takes longer than DEFAULT_STEPPER_DEACTIVE_TIME. //#define PARK_HEAD_ON_PAUSE // Go to filament change position on pause, return to print position on resume #endif diff --git a/Marlin/example_configurations/wt150/Configuration_adv.h b/Marlin/example_configurations/wt150/Configuration_adv.h index ab2b4cb73..700c5227f 100644 --- a/Marlin/example_configurations/wt150/Configuration_adv.h +++ b/Marlin/example_configurations/wt150/Configuration_adv.h @@ -759,22 +759,23 @@ #endif /** - * Filament Change - * Experimental filament change support. + * Advanced Pause + * Experimental feature for filament change support and for parking the nozzle when paused. * Adds the GCode M600 for initiating filament change. + * If PARK_HEAD_ON_PAUSE enabled, adds the GCode M125 to pause printing and park the nozzle. * * Requires an LCD display. * This feature is required for the default FILAMENT_RUNOUT_SCRIPT. */ -//#define FILAMENT_CHANGE_FEATURE -#if ENABLED(FILAMENT_CHANGE_FEATURE) - #define FILAMENT_CHANGE_X_POS 3 // X position of hotend - #define FILAMENT_CHANGE_Y_POS 3 // Y position of hotend - #define FILAMENT_CHANGE_Z_ADD 10 // Z addition of hotend (lift) - #define FILAMENT_CHANGE_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) - #define FILAMENT_CHANGE_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) - #define FILAMENT_CHANGE_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s - #define FILAMENT_CHANGE_RETRACT_LENGTH 2 // Initial retract in mm +//#define ADVANCED_PAUSE_FEATURE +#if ENABLED(ADVANCED_PAUSE_FEATURE) + #define PAUSE_PARK_X_POS 3 // X position of hotend + #define PAUSE_PARK_Y_POS 3 // Y position of hotend + #define PAUSE_PARK_Z_ADD 10 // Z addition of hotend (lift) + #define PAUSE_PARK_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) + #define PAUSE_PARK_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) + #define PAUSE_PARK_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s + #define PAUSE_PARK_RETRACT_LENGTH 2 // Initial retract in mm // It is a short retract used immediately after print interrupt before move to filament exchange position #define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // Unload filament feedrate in mm/s - filament unloading can be fast #define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // Unload filament length from hotend in mm @@ -785,14 +786,14 @@ #define FILAMENT_CHANGE_LOAD_LENGTH 0 // Load filament length over hotend in mm // Longer length for bowden printers to fast load filament into whole bowden tube over the hotend, // Short or zero length for printers without bowden where loading is not used - #define FILAMENT_CHANGE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate - #define FILAMENT_CHANGE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, + #define ADVANCED_PAUSE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate + #define ADVANCED_PAUSE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, // 0 to disable for manual extrusion // Filament can be extruded repeatedly from the filament exchange menu to fill the hotend, // or until outcoming filament color is not clear for filament color change - #define FILAMENT_CHANGE_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds + #define PAUSE_PARK_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds #define FILAMENT_CHANGE_NUMBER_OF_ALERT_BEEPS 5 // Number of alert beeps before printer goes quiet - #define FILAMENT_CHANGE_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change + #define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change // even if it takes longer than DEFAULT_STEPPER_DEACTIVE_TIME. //#define PARK_HEAD_ON_PAUSE // Go to filament change position on pause, return to print position on resume #endif diff --git a/Marlin/language_an.h b/Marlin/language_an.h index d4983591d..f8cecfbc3 100644 --- a/Marlin/language_an.h +++ b/Marlin/language_an.h @@ -214,8 +214,8 @@ #define MSG_DRIVE_STRENGTH _UxGT("Fuerza d'o driver") #define MSG_DAC_PERCENT _UxGT("Driver %") #define MSG_DAC_EEPROM_WRITE _UxGT("Escri. DAC EEPROM") -#define MSG_FILAMENT_CHANGE_HEADER _UxGT("Cambear filamento") -#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("Opcion de cambio:") +#define MSG_FILAMENT_CHANGE_HEADER _UxGT("PRINT PAUSED") +#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("RESUME OPTIONS:") #define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("Extruir mas") #define MSG_FILAMENT_CHANGE_OPTION_RESUME _UxGT("Resumir imp.") diff --git a/Marlin/language_bg.h b/Marlin/language_bg.h index fedb8ca7c..6b58a96e5 100644 --- a/Marlin/language_bg.h +++ b/Marlin/language_bg.h @@ -216,8 +216,8 @@ #define MSG_DAC_PERCENT _UxGT("Driver %") #define MSG_DAC_EEPROM_WRITE _UxGT("DAC EEPROM Write") -#define MSG_FILAMENT_CHANGE_HEADER _UxGT("CHANGE FILAMENT") -#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("CHANGE OPTIONS:") +#define MSG_FILAMENT_CHANGE_HEADER _UxGT("PRINT PAUSED") +#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("RESUME OPTIONS:") #define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("Extrude more") #define MSG_FILAMENT_CHANGE_OPTION_RESUME _UxGT("Resume print") diff --git a/Marlin/language_ca.h b/Marlin/language_ca.h index 8502e1cac..7ed1de93f 100644 --- a/Marlin/language_ca.h +++ b/Marlin/language_ca.h @@ -218,8 +218,8 @@ #define MSG_DRIVE_STRENGTH _UxGT("Força motor") #define MSG_DAC_PERCENT _UxGT("Driver %") #define MSG_DAC_EEPROM_WRITE _UxGT("DAC EEPROM Write") -#define MSG_FILAMENT_CHANGE_HEADER _UxGT("CANVI DE FILAMENT") -#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("OPCIONS CANVI:") +#define MSG_FILAMENT_CHANGE_HEADER _UxGT("PRINT PAUSED") +#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("RESUME OPTIONS:") #define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("Extrudeix mes") #define MSG_FILAMENT_CHANGE_OPTION_RESUME _UxGT("Repren impressió") #define MSG_FILAMENT_CHANGE_MINTEMP _UxGT("Temp minima es ") diff --git a/Marlin/language_cz.h b/Marlin/language_cz.h index 57eb9e5d5..2372f68fb 100644 --- a/Marlin/language_cz.h +++ b/Marlin/language_cz.h @@ -225,8 +225,8 @@ #define MSG_DAC_PERCENT _UxGT("Motor %") #define MSG_DAC_EEPROM_WRITE _UxGT("Ulozit do EEPROM") -#define MSG_FILAMENT_CHANGE_HEADER _UxGT("VYMENA FILAMENTU") -#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("CO DAL?") +#define MSG_FILAMENT_CHANGE_HEADER _UxGT("PRINT PAUSED") +#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("RESUME OPTIONS:") #define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("Jeste vytlacit") #define MSG_FILAMENT_CHANGE_OPTION_RESUME _UxGT("Obnovit tisk") #define MSG_FILAMENT_CHANGE_MINTEMP _UxGT("Min. teplota je ") diff --git a/Marlin/language_da.h b/Marlin/language_da.h index 9b8c45ecd..69d196529 100644 --- a/Marlin/language_da.h +++ b/Marlin/language_da.h @@ -215,8 +215,8 @@ #define MSG_DAC_PERCENT _UxGT("Driv %") #define MSG_DAC_EEPROM_WRITE _UxGT("DAC EEPROM Skriv") -#define MSG_FILAMENT_CHANGE_HEADER _UxGT("SKIFT FILAMENT") -#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("Skift muligheder:") +#define MSG_FILAMENT_CHANGE_HEADER _UxGT("PRINT PAUSED") +#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("RESUME OPTIONS:") #define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("Extruder mere") #define MSG_FILAMENT_CHANGE_OPTION_RESUME _UxGT("Forsæt print") diff --git a/Marlin/language_de.h b/Marlin/language_de.h index a72d60ab2..59b337027 100644 --- a/Marlin/language_de.h +++ b/Marlin/language_de.h @@ -227,8 +227,8 @@ #define MSG_DAC_PERCENT _UxGT("Treiber %") #define MSG_DAC_EEPROM_WRITE _UxGT("Werte speichern") -#define MSG_FILAMENT_CHANGE_HEADER _UxGT("ÄNDERE FILAMENT") -#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("ÄNDERE OPTIONEN:") +#define MSG_FILAMENT_CHANGE_HEADER _UxGT("PRINT PAUSED") +#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("RESUME OPTIONS:") #define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("Extrude mehr") #define MSG_FILAMENT_CHANGE_OPTION_RESUME _UxGT("Drucke weiter") #define MSG_FILAMENT_CHANGE_MINTEMP _UxGT("Min. Temperatur ist ") diff --git a/Marlin/language_en.h b/Marlin/language_en.h index ba8cb807d..d274ab84e 100644 --- a/Marlin/language_en.h +++ b/Marlin/language_en.h @@ -499,6 +499,9 @@ #ifndef MSG_USERWAIT #define MSG_USERWAIT _UxGT("Click to resume...") #endif +#ifndef MSG_PRINT_PAUSED + #define MSG_PRINT_PAUSED _UxGT("Print paused") +#endif #ifndef MSG_RESUMING #define MSG_RESUMING _UxGT("Resuming print") #endif @@ -742,10 +745,10 @@ #define MSG_DAC_EEPROM_WRITE _UxGT("DAC EEPROM Write") #endif #ifndef MSG_FILAMENT_CHANGE_HEADER - #define MSG_FILAMENT_CHANGE_HEADER _UxGT("CHANGE FILAMENT") + #define MSG_FILAMENT_CHANGE_HEADER _UxGT("PRINT PAUSED") #endif #ifndef MSG_FILAMENT_CHANGE_OPTION_HEADER - #define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("CHANGE OPTIONS:") + #define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("RESUME OPTIONS:") #endif #ifndef MSG_FILAMENT_CHANGE_OPTION_EXTRUDE #define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("Extrude more") diff --git a/Marlin/language_es.h b/Marlin/language_es.h index 21bd330a8..003caf8c3 100644 --- a/Marlin/language_es.h +++ b/Marlin/language_es.h @@ -221,8 +221,8 @@ #define MSG_DAC_PERCENT _UxGT("Driver %") #define MSG_DAC_EEPROM_WRITE _UxGT("Escribe DAC EEPROM") -#define MSG_FILAMENT_CHANGE_HEADER _UxGT("Cambiar Filamento") -#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("Opciones de cambio:") +#define MSG_FILAMENT_CHANGE_HEADER _UxGT("PRINT PAUSED") +#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("RESUME OPTIONS:") #define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("Extruir mas") #define MSG_FILAMENT_CHANGE_OPTION_RESUME _UxGT("Resumir imp.") diff --git a/Marlin/language_fr.h b/Marlin/language_fr.h index 61097ea84..c541dc9e3 100644 --- a/Marlin/language_fr.h +++ b/Marlin/language_fr.h @@ -229,8 +229,8 @@ #define MSG_DAC_PERCENT _UxGT("Driver %") #define MSG_DAC_EEPROM_WRITE _UxGT("DAC EEPROM sauv.") -#define MSG_FILAMENT_CHANGE_HEADER _UxGT("CHANGER FILAMENT") -#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("CHANGER OPTIONS:") +#define MSG_FILAMENT_CHANGE_HEADER _UxGT("PRINT PAUSED") +#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("RESUME OPTIONS:") #define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("+ extrusion") #define MSG_FILAMENT_CHANGE_OPTION_RESUME _UxGT("Reprendre impr.") #define MSG_FILAMENT_CHANGE_MINTEMP _UxGT("La temp. minimum est ") diff --git a/Marlin/language_gl.h b/Marlin/language_gl.h index a3dcac180..67ad89ffb 100644 --- a/Marlin/language_gl.h +++ b/Marlin/language_gl.h @@ -212,8 +212,8 @@ #define MSG_DAC_PERCENT _UxGT("Motor %") #define MSG_DAC_EEPROM_WRITE _UxGT("Garda DAC EEPROM") -#define MSG_FILAMENT_CHANGE_HEADER _UxGT("TROCO FILAMENTO") -#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("OPCIONS TROCO:") +#define MSG_FILAMENT_CHANGE_HEADER _UxGT("PRINT PAUSED") +#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("RESUME OPTIONS:") #define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("Extruir mais") #define MSG_FILAMENT_CHANGE_OPTION_RESUME _UxGT("Segue traballo") diff --git a/Marlin/language_hr.h b/Marlin/language_hr.h index 0d5bae21b..7ec0b0dbb 100644 --- a/Marlin/language_hr.h +++ b/Marlin/language_hr.h @@ -213,8 +213,8 @@ #define MSG_DAC_PERCENT _UxGT("Driver %") #define MSG_DAC_EEPROM_WRITE _UxGT("DAC EEPROM Write") -#define MSG_FILAMENT_CHANGE_HEADER _UxGT("CHANGE FILAMENT") -#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("CHANGE OPTIONS:") +#define MSG_FILAMENT_CHANGE_HEADER _UxGT("PRINT PAUSED") +#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("RESUME OPTIONS:") #define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("Extrudiraj više") #define MSG_FILAMENT_CHANGE_OPTION_RESUME _UxGT("Nastavi print") diff --git a/Marlin/language_it.h b/Marlin/language_it.h index f3e8d353d..b1c5b6623 100644 --- a/Marlin/language_it.h +++ b/Marlin/language_it.h @@ -238,8 +238,8 @@ #define MSG_DAC_PERCENT _UxGT("Driver %") #define MSG_DAC_EEPROM_WRITE _UxGT("Scrivi DAC EEPROM") -#define MSG_FILAMENT_CHANGE_HEADER _UxGT("CAMBIA FILAMENTO") -#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("CAMBIA OPZIONI:") +#define MSG_FILAMENT_CHANGE_HEADER _UxGT("PRINT PAUSED") +#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("RESUME OPTIONS:") #define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("Estrusione") #define MSG_FILAMENT_CHANGE_OPTION_RESUME _UxGT("Riprendi stampa") #if ENABLED(DOGLCD) diff --git a/Marlin/language_kana.h b/Marlin/language_kana.h index da2e18a8a..40f60491a 100644 --- a/Marlin/language_kana.h +++ b/Marlin/language_kana.h @@ -285,8 +285,8 @@ #define MSG_DAC_PERCENT "DAC\xbc\xad\xc2\xd8\xae\xb8" // "DACシュツリョク" ("Driver %") #endif #define MSG_DAC_EEPROM_WRITE MSG_STORE_EPROM // "メモリヘカクノウ" ("DAC EEPROM Write") -#define MSG_FILAMENT_CHANGE_HEADER "\xcc\xa8\xd7\xd2\xdd\xc4\xba\xb3\xb6\xdd" // "フィラメントコウカン" ("CHANGE FILAMENT") -#define MSG_FILAMENT_CHANGE_OPTION_HEADER "\xc4\xde\xb3\xbb\xa6\xbe\xdd\xc0\xb8\xbc\xc3\xb8\xc0\xde\xbb\xb2" // "ドウサヲセンタクシテクダサイ" ("CHANGE OPTIONS:") +#define MSG_FILAMENT_CHANGE_HEADER "PRINT PAUSED" +#define MSG_FILAMENT_CHANGE_OPTION_HEADER "RESUME OPTIONS:" #define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE "\xbb\xd7\xc6\xb5\xbc\xc0\xde\xbd" // "サラニオシダス" ("Extrude more") #define MSG_FILAMENT_CHANGE_OPTION_RESUME "\xcc\xdf\xd8\xdd\xc4\xbb\xb2\xb6\xb2" // "プリントサイカイ" ("Resume print") diff --git a/Marlin/language_kana_utf8.h b/Marlin/language_kana_utf8.h index 01b393df7..470f51185 100644 --- a/Marlin/language_kana_utf8.h +++ b/Marlin/language_kana_utf8.h @@ -212,8 +212,8 @@ #define MSG_DRIVE_STRENGTH _UxGT("モータークドウリョク") // "Drive Strength" #define MSG_DAC_PERCENT _UxGT("DACシュツリョク %") // "Driver %" #define MSG_DAC_EEPROM_WRITE MSG_STORE_EPROM // "DAC EEPROM Write" -#define MSG_FILAMENT_CHANGE_HEADER _UxGT("フィラメントコウカン") // "CHANGE FILAMENT" -#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("ドウサヲセンタクシテクダサイ") // "CHANGE OPTIONS:" +#define MSG_FILAMENT_CHANGE_HEADER _UxGT("PRINT PAUSED") +#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("RESUME OPTIONS:") #define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("サラニオシダス") // "Extrude more" #define MSG_FILAMENT_CHANGE_OPTION_RESUME _UxGT("プリントサイカイ") // "Resume print" #define MSG_FILAMENT_CHANGE_INIT_1 _UxGT("コウカンヲカイシシマス") // "Wait for start" diff --git a/Marlin/language_nl.h b/Marlin/language_nl.h index 74dda87c0..7693b511c 100644 --- a/Marlin/language_nl.h +++ b/Marlin/language_nl.h @@ -224,8 +224,8 @@ #define MSG_DRIVE_STRENGTH _UxGT("Motorstroom") #define MSG_DAC_PERCENT _UxGT("Driver %") //accepted English term in Dutch #define MSG_DAC_EEPROM_WRITE _UxGT("DAC Opslaan") -#define MSG_FILAMENT_CHANGE_HEADER _UxGT("WISSEL FILAMENT") -#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("WISSEL OPTIES:") +#define MSG_FILAMENT_CHANGE_HEADER _UxGT("PRINT PAUSED") +#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("RESUME OPTIONS:") #define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("Extrudeer meer") #define MSG_FILAMENT_CHANGE_OPTION_RESUME _UxGT("Hervat print") #define MSG_FILAMENT_CHANGE_MINTEMP _UxGT("Minimum Temp is ") diff --git a/Marlin/language_pl.h b/Marlin/language_pl.h index dc3290e79..280cd5b2b 100644 --- a/Marlin/language_pl.h +++ b/Marlin/language_pl.h @@ -433,8 +433,8 @@ #define MSG_DAC_PERCENT _UxGT("Sila %") #define MSG_DAC_EEPROM_WRITE _UxGT("Zapisz DAC EEPROM") -#define MSG_FILAMENT_CHANGE_HEADER _UxGT("ZMIEN FILAMENT") -#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("ZMIEN OPCJE:") +#define MSG_FILAMENT_CHANGE_HEADER _UxGT("PRINT PAUSED") +#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("RESUME OPTIONS:") #define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("Ekstruduj wiecej") #define MSG_FILAMENT_CHANGE_OPTION_RESUME _UxGT("Wznow drukowanie") diff --git a/Marlin/language_tr.h b/Marlin/language_tr.h index 3dd7af19d..e6b0af98b 100644 --- a/Marlin/language_tr.h +++ b/Marlin/language_tr.h @@ -227,8 +227,8 @@ #define MSG_DRIVE_STRENGTH _UxGT("Sürücü Gücü") // Sürücü Gücü #define MSG_DAC_PERCENT _UxGT("Sürücü %") // Sürücü % -#define MSG_DAC_EEPROM_WRITE _UxGT("DAC'ı EEPROM'a Yaz") // DAC'ı EEPROM'a Yaz -#define MSG_FILAMENT_CHANGE_HEADER _UxGT("Filaman Değiştir") // Filaman Değiştir +#define MSG_FILAMENT_CHANGE_HEADER _UxGT("PRINT PAUSED") +#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("RESUME OPTIONS:") #define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("Seçenekler:") // Seçenekler: #define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("Daha Akıt") // Daha Akıt #define MSG_FILAMENT_CHANGE_OPTION_RESUME _UxGT("Baskıyı sürdür") // Baskıyı sürdür diff --git a/Marlin/language_uk.h b/Marlin/language_uk.h index 774ef2308..ffc302a64 100644 --- a/Marlin/language_uk.h +++ b/Marlin/language_uk.h @@ -203,8 +203,8 @@ #define MSG_DAC_PERCENT _UxGT("% мотору") #define MSG_DAC_EEPROM_WRITE _UxGT("Запис ЦАП на ПЗП") -#define MSG_FILAMENT_CHANGE_HEADER _UxGT("ЗАМІНА ВОЛОКНА") -#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("НАЛАШТ. ЗАМІНИ:") +#define MSG_FILAMENT_CHANGE_HEADER _UxGT("PRINT PAUSED") +#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("RESUME OPTIONS:") #define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("Екструдувати") #define MSG_FILAMENT_CHANGE_OPTION_RESUME _UxGT("Відновити друк") diff --git a/Marlin/language_zh_CN.h b/Marlin/language_zh_CN.h index ed9e5c984..58d845a35 100644 --- a/Marlin/language_zh_CN.h +++ b/Marlin/language_zh_CN.h @@ -199,8 +199,8 @@ #define MSG_INFO_MAX_TEMP _UxGT("最高温度") //"Max Temp" #define MSG_INFO_PSU _UxGT("电源供应") //"Power Supply" -#define MSG_FILAMENT_CHANGE_HEADER _UxGT("修改丝料") //"CHANGE FILAMENT" -#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("修改选项:") //"CHANGE OPTIONS:" +#define MSG_FILAMENT_CHANGE_HEADER _UxGT("PRINT PAUSED") +#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("RESUME OPTIONS:") #define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("挤出更多") //"Extrude more" #define MSG_FILAMENT_CHANGE_OPTION_RESUME _UxGT("恢复打印") //"Resume print" diff --git a/Marlin/language_zh_TW.h b/Marlin/language_zh_TW.h index 90aaa8200..89924732b 100644 --- a/Marlin/language_zh_TW.h +++ b/Marlin/language_zh_TW.h @@ -199,8 +199,8 @@ #define MSG_INFO_MAX_TEMP _UxGT("最高溫度") //"Max Temp" #define MSG_INFO_PSU _UxGT("電源供應") //"Power Supply" -#define MSG_FILAMENT_CHANGE_HEADER _UxGT("修改絲料") //"CHANGE FILAMENT" -#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("修改選項:") //"CHANGE OPTIONS:" +#define MSG_FILAMENT_CHANGE_HEADER _UxGT("PRINT PAUSED") +#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("RESUME OPTIONS:") #define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("擠出更多") //"Extrude more" #define MSG_FILAMENT_CHANGE_OPTION_RESUME _UxGT("恢複列印") //"Resume print" diff --git a/Marlin/temperature.cpp b/Marlin/temperature.cpp index f94d98b96..3cac779d3 100644 --- a/Marlin/temperature.cpp +++ b/Marlin/temperature.cpp @@ -202,9 +202,14 @@ uint8_t Temperature::soft_pwm_amount[HOTENDS], #if ENABLED(PROBING_HEATERS_OFF) bool Temperature::paused; - int16_t Temperature::paused_hotend_temp[HOTENDS]; +#endif + +#if ENABLED(ADVANCED_PAUSE_FEATURE) + millis_t Temperature::heater_idle_timeout_ms[HOTENDS] = { 0 }; + bool Temperature::heater_idle_timeout_exceeded[HOTENDS] = { false }; #if HAS_TEMP_BED - int16_t Temperature::paused_bed_temp; + millis_t Temperature::bed_idle_timeout_ms = 0; + bool Temperature::bed_idle_timeout_exceeded = false; #endif #endif @@ -554,11 +559,22 @@ float Temperature::get_pid_output(int e) { pid_error[HOTEND_INDEX] = target_temperature[HOTEND_INDEX] - current_temperature[HOTEND_INDEX]; dTerm[HOTEND_INDEX] = K2 * PID_PARAM(Kd, HOTEND_INDEX) * (current_temperature[HOTEND_INDEX] - temp_dState[HOTEND_INDEX]) + K1 * dTerm[HOTEND_INDEX]; temp_dState[HOTEND_INDEX] = current_temperature[HOTEND_INDEX]; + #if ENABLED(ADVANCED_PAUSE_FEATURE) + if (heater_idle_timeout_exceeded[HOTEND_INDEX]) { + pid_output = 0; + pid_reset[HOTEND_INDEX] = true; + } + else + #endif if (pid_error[HOTEND_INDEX] > PID_FUNCTIONAL_RANGE) { pid_output = BANG_MAX; pid_reset[HOTEND_INDEX] = true; } - else if (pid_error[HOTEND_INDEX] < -(PID_FUNCTIONAL_RANGE) || target_temperature[HOTEND_INDEX] == 0) { + else if (pid_error[HOTEND_INDEX] < -(PID_FUNCTIONAL_RANGE) || target_temperature[HOTEND_INDEX] == 0 + #if ENABLED(ADVANCED_PAUSE_FEATURE) + || heater_idle_timeout_exceeded[HOTEND_INDEX] + #endif + ) { pid_output = 0; pid_reset[HOTEND_INDEX] = true; } @@ -618,6 +634,11 @@ float Temperature::get_pid_output(int e) { #endif // PID_DEBUG #else /* PID off */ + #if ENABLED(ADVANCED_PAUSE_FEATURE) + if (heater_idle_timeout_exceeded[HOTEND_INDEX]) + pid_output = 0; + else + #endif pid_output = (current_temperature[HOTEND_INDEX] < target_temperature[HOTEND_INDEX]) ? PID_MAX : 0; #endif @@ -699,12 +720,17 @@ void Temperature::manage_heater() { if (current_temperature[0] < max(HEATER_0_MINTEMP, MAX6675_TMIN + .01)) min_temp_error(0); #endif - #if WATCH_HOTENDS || WATCH_THE_BED || DISABLED(PIDTEMPBED) || HAS_AUTO_FAN + #if WATCH_HOTENDS || WATCH_THE_BED || DISABLED(PIDTEMPBED) || HAS_AUTO_FAN || ENABLED(ADVANCED_PAUSE_FEATURE) millis_t ms = millis(); #endif HOTEND_LOOP() { + #if ENABLED(ADVANCED_PAUSE_FEATURE) + if (!heater_idle_timeout_exceeded[e] && heater_idle_timeout_ms[e] && ELAPSED(ms, heater_idle_timeout_ms[e])) + heater_idle_timeout_exceeded[e] = true; + #endif + #if ENABLED(THERMAL_PROTECTION_HOTENDS) // Check for thermal runaway thermal_runaway_protection(&thermal_runaway_state_machine[e], &thermal_runaway_timer[e], current_temperature[e], target_temperature[e], e, THERMAL_PROTECTION_PERIOD, THERMAL_PROTECTION_HYSTERESIS); @@ -722,16 +748,6 @@ void Temperature::manage_heater() { } #endif - #if WATCH_THE_BED - // Make sure temperature is increasing - if (watch_bed_next_ms && ELAPSED(ms, watch_bed_next_ms)) { // Time to check the bed? - if (degBed() < watch_target_bed_temp) // Failed to increase enough? - _temp_error(-1, PSTR(MSG_T_HEATING_FAILED), PSTR(MSG_HEATING_FAILED_LCD)); - else // Start again if the target is still far off - start_watching_bed(); - } - #endif - #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) // Make sure measured temperatures are close together if (fabs(current_temperature[0] - redundant_temperature) > MAX_REDUNDANT_TEMP_SENSOR_DIFF) @@ -761,43 +777,71 @@ void Temperature::manage_heater() { } #endif // FILAMENT_WIDTH_SENSOR + #if WATCH_THE_BED + // Make sure temperature is increasing + if (watch_bed_next_ms && ELAPSED(ms, watch_bed_next_ms)) { // Time to check the bed? + if (degBed() < watch_target_bed_temp) // Failed to increase enough? + _temp_error(-1, PSTR(MSG_T_HEATING_FAILED), PSTR(MSG_HEATING_FAILED_LCD)); + else // Start again if the target is still far off + start_watching_bed(); + } + #endif // WATCH_THE_BED + #if DISABLED(PIDTEMPBED) if (PENDING(ms, next_bed_check_ms)) return; next_bed_check_ms = ms + BED_CHECK_INTERVAL; #endif - #if TEMP_SENSOR_BED != 0 + #if HAS_TEMP_BED + + #if ENABLED(ADVANCED_PAUSE_FEATURE) + if (!bed_idle_timeout_exceeded && bed_idle_timeout_ms && ELAPSED(ms, bed_idle_timeout_ms)) + bed_idle_timeout_exceeded = true; + #endif #if HAS_THERMALLY_PROTECTED_BED thermal_runaway_protection(&thermal_runaway_bed_state_machine, &thermal_runaway_bed_timer, current_temperature_bed, target_temperature_bed, -1, THERMAL_PROTECTION_BED_PERIOD, THERMAL_PROTECTION_BED_HYSTERESIS); #endif - #if ENABLED(PIDTEMPBED) - soft_pwm_amount_bed = WITHIN(current_temperature_bed, BED_MINTEMP, BED_MAXTEMP) ? (int)get_pid_output_bed() >> 1 : 0; - - #elif ENABLED(BED_LIMIT_SWITCHING) - // Check if temperature is within the correct band - if (WITHIN(current_temperature_bed, BED_MINTEMP, BED_MAXTEMP)) { - if (current_temperature_bed >= target_temperature_bed + BED_HYSTERESIS) - soft_pwm_amount_bed = 0; - else if (current_temperature_bed <= target_temperature_bed - (BED_HYSTERESIS)) - soft_pwm_amount_bed = MAX_BED_POWER >> 1; - } - else { + #if ENABLED(ADVANCED_PAUSE_FEATURE) + if (bed_idle_timeout_exceeded) + { soft_pwm_amount_bed = 0; - WRITE_HEATER_BED(LOW); - } - #else // !PIDTEMPBED && !BED_LIMIT_SWITCHING - // Check if temperature is within the correct range - if (WITHIN(current_temperature_bed, BED_MINTEMP, BED_MAXTEMP)) { - soft_pwm_amount_bed = current_temperature_bed < target_temperature_bed ? MAX_BED_POWER >> 1 : 0; - } - else { - soft_pwm_amount_bed = 0; - WRITE_HEATER_BED(LOW); + + #if DISABLED(PIDTEMPBED) + WRITE_HEATER_BED(LOW); + #endif } + else #endif - #endif // TEMP_SENSOR_BED != 0 + { + #if ENABLED(PIDTEMPBED) + soft_pwm_amount_bed = WITHIN(current_temperature_bed, BED_MINTEMP, BED_MAXTEMP) ? (int)get_pid_output_bed() >> 1 : 0; + + #elif ENABLED(BED_LIMIT_SWITCHING) + // Check if temperature is within the correct band + if (WITHIN(current_temperature_bed, BED_MINTEMP, BED_MAXTEMP)) { + if (current_temperature_bed >= target_temperature_bed + BED_HYSTERESIS) + soft_pwm_amount_bed = 0; + else if (current_temperature_bed <= target_temperature_bed - (BED_HYSTERESIS)) + soft_pwm_amount_bed = MAX_BED_POWER >> 1; + } + else { + soft_pwm_amount_bed = 0; + WRITE_HEATER_BED(LOW); + } + #else // !PIDTEMPBED && !BED_LIMIT_SWITCHING + // Check if temperature is within the correct range + if (WITHIN(current_temperature_bed, BED_MINTEMP, BED_MAXTEMP)) { + soft_pwm_amount_bed = current_temperature_bed < target_temperature_bed ? MAX_BED_POWER >> 1 : 0; + } + else { + soft_pwm_amount_bed = 0; + WRITE_HEATER_BED(LOW); + } + #endif + } + #endif // HAS_TEMP_BED } #define PGM_RD_W(x) (short)pgm_read_word(&x) @@ -1180,10 +1224,6 @@ void Temperature::init() { #if ENABLED(PROBING_HEATERS_OFF) paused = false; - ZERO(paused_hotend_temp); - #if HAS_TEMP_BED - paused_bed_temp = 0; - #endif #endif } @@ -1246,11 +1286,29 @@ void Temperature::init() { SERIAL_ECHOPAIR(" ; Timer:", *timer); SERIAL_ECHOPAIR(" ; Temperature:", current); SERIAL_ECHOPAIR(" ; Target Temp:", target); + if (heater_id >= 0) + SERIAL_ECHOPAIR(" ; Idle Timeout:", heater_idle_timeout_exceeded[heater_id]); + else + SERIAL_ECHOPAIR(" ; Idle Timeout:", bed_idle_timeout_exceeded); SERIAL_EOL; */ int heater_index = heater_id >= 0 ? heater_id : HOTENDS; + #if ENABLED(ADVANCED_PAUSE_FEATURE) + // If the heater idle timeout expires, restart + if (heater_id >= 0 && heater_idle_timeout_exceeded[heater_id]) { + *state = TRInactive; + tr_target_temperature[heater_index] = 0; + } + #if HAS_TEMP_BED + else if (heater_id < 0 && bed_idle_timeout_exceeded) { + *state = TRInactive; + tr_target_temperature[heater_index] = 0; + } + #endif + else + #endif // If the target temperature changes, restart if (tr_target_temperature[heater_index] != target) { tr_target_temperature[heater_index] = target; @@ -1290,11 +1348,7 @@ void Temperature::disable_all_heaters() { // Unpause and reset everything #if ENABLED(PROBING_HEATERS_OFF) - paused = false; - ZERO(paused_hotend_temp); - #if HAS_TEMP_BED - paused_bed_temp = 0; - #endif + pause(false); #endif // If all heaters go down then for sure our print job has stopped @@ -1337,19 +1391,15 @@ void Temperature::disable_all_heaters() { if (p != paused) { paused = p; if (p) { - HOTEND_LOOP() { - paused_hotend_temp[e] = degTargetHotend(e); - setTargetHotend(0, e); - } + HOTEND_LOOP() start_heater_idle_timer(e, 0); // timeout immediately #if HAS_TEMP_BED - paused_bed_temp = degTargetBed(); - setTargetBed(0); + start_bed_idle_timer(0); // timeout immediately #endif } else { - HOTEND_LOOP() setTargetHotend(paused_hotend_temp[e], e); + HOTEND_LOOP() reset_heater_idle_timer(e); #if HAS_TEMP_BED - setTargetBed(paused_bed_temp); + reset_bed_idle_timer(); #endif } } diff --git a/Marlin/temperature.h b/Marlin/temperature.h index 9b85bbde1..0e911a70c 100644 --- a/Marlin/temperature.h +++ b/Marlin/temperature.h @@ -257,10 +257,14 @@ class Temperature { #if ENABLED(PROBING_HEATERS_OFF) static bool paused; - static int16_t paused_hotend_temp[HOTENDS]; + #endif + #if ENABLED(ADVANCED_PAUSE_FEATURE) + static millis_t heater_idle_timeout_ms[HOTENDS]; + static bool heater_idle_timeout_exceeded[HOTENDS]; #if HAS_TEMP_BED - static int16_t paused_bed_temp; + static millis_t bed_idle_timeout_ms; + static bool bed_idle_timeout_exceeded; #endif #endif @@ -458,6 +462,54 @@ class Temperature { #if ENABLED(PROBING_HEATERS_OFF) static void pause(const bool p); + static bool is_paused() { return paused; } + #endif + + #if ENABLED(ADVANCED_PAUSE_FEATURE) + static void start_heater_idle_timer(uint8_t e, millis_t timeout_ms) { + #if HOTENDS == 1 + UNUSED(e); + #endif + heater_idle_timeout_ms[HOTEND_INDEX] = millis() + timeout_ms; + heater_idle_timeout_exceeded[HOTEND_INDEX] = false; + } + + static void reset_heater_idle_timer(uint8_t e) { + #if HOTENDS == 1 + UNUSED(e); + #endif + heater_idle_timeout_ms[HOTEND_INDEX] = 0; + heater_idle_timeout_exceeded[HOTEND_INDEX] = false; + #if WATCH_HOTENDS + start_watching_heater(HOTEND_INDEX); + #endif + } + + static bool is_heater_idle(uint8_t e) { + #if HOTENDS == 1 + UNUSED(e); + #endif + return heater_idle_timeout_exceeded[HOTEND_INDEX]; + } + + #if HAS_TEMP_BED + static void start_bed_idle_timer(millis_t timeout_ms) { + bed_idle_timeout_ms = millis() + timeout_ms; + bed_idle_timeout_exceeded = false; + } + + static void reset_bed_idle_timer() { + bed_idle_timeout_ms = 0; + bed_idle_timeout_exceeded = false; + #if WATCH_THE_BED + start_watching_bed(); + #endif + } + + static bool is_bed_idle() { + return bed_idle_timeout_exceeded; + } + #endif #endif private: diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 54da69fc5..32d47419d 100755 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -126,16 +126,16 @@ uint16_t max_display_update_time = 0; void lcd_info_menu(); #endif // LCD_INFO_MENU - #if ENABLED(FILAMENT_CHANGE_FEATURE) - void lcd_filament_change_toocold_menu(); - void lcd_filament_change_option_menu(); - void lcd_filament_change_init_message(); - void lcd_filament_change_unload_message(); - void lcd_filament_change_insert_message(); - void lcd_filament_change_load_message(); - void lcd_filament_change_heat_nozzle(); - void lcd_filament_change_extrude_message(); - void lcd_filament_change_resume_message(); + #if ENABLED(ADVANCED_PAUSE_FEATURE) + void lcd_advanced_pause_toocold_menu(); + void lcd_advanced_pause_option_menu(); + void lcd_advanced_pause_init_message(); + void lcd_advanced_pause_unload_message(); + void lcd_advanced_pause_insert_message(); + void lcd_advanced_pause_load_message(); + void lcd_advanced_pause_heat_nozzle(); + void lcd_advanced_pause_extrude_message(); + void lcd_advanced_pause_resume_message(); #endif #if ENABLED(DAC_STEPPER_CURRENT) @@ -676,6 +676,7 @@ void kill_screen(const char* lcd_msg) { #if ENABLED(PARK_HEAD_ON_PAUSE) enqueue_and_echo_commands_P(PSTR("M125")); #endif + lcd_setstatuspgm(PSTR(MSG_PRINT_PAUSED), true); } void lcd_sdcard_resume() { @@ -685,6 +686,7 @@ void kill_screen(const char* lcd_msg) { card.startFileprint(); print_job_timer.start(); #endif + lcd_setstatuspgm(PSTR(""), true); } void lcd_sdcard_stop() { @@ -1006,15 +1008,15 @@ void kill_screen(const char* lcd_msg) { void watch_temp_callback_bed() { thermalManager.start_watching_bed(); } #endif - #if ENABLED(FILAMENT_CHANGE_FEATURE) + #if ENABLED(ADVANCED_PAUSE_FEATURE) void lcd_enqueue_filament_change() { if (!DEBUGGING(DRYRUN) && thermalManager.tooColdToExtrude(active_extruder)) { lcd_save_previous_screen(); - lcd_goto_screen(lcd_filament_change_toocold_menu); + lcd_goto_screen(lcd_advanced_pause_toocold_menu); return; } - lcd_filament_change_show_message(FILAMENT_CHANGE_MESSAGE_INIT); - enqueue_and_echo_commands_P(PSTR("M600")); + lcd_advanced_pause_show_message(ADVANCED_PAUSE_MESSAGE_INIT); + enqueue_and_echo_commands_P(PSTR("M600 B0")); } #endif @@ -1129,7 +1131,7 @@ void kill_screen(const char* lcd_msg) { // // Change filament // - #if ENABLED(FILAMENT_CHANGE_FEATURE) + #if ENABLED(ADVANCED_PAUSE_FEATURE) if (!thermalManager.tooColdToExtrude(active_extruder)) MENU_ITEM(function, MSG_FILAMENTCHANGE, lcd_enqueue_filament_change); #endif @@ -2043,7 +2045,7 @@ void kill_screen(const char* lcd_msg) { // // Change filament // - #if ENABLED(FILAMENT_CHANGE_FEATURE) + #if ENABLED(ADVANCED_PAUSE_FEATURE) if (!thermalManager.tooColdToExtrude(active_extruder)) MENU_ITEM(function, MSG_FILAMENTCHANGE, lcd_enqueue_filament_change); #endif @@ -3183,7 +3185,7 @@ void kill_screen(const char* lcd_msg) { * Filament Change Feature Screens * */ - #if ENABLED(FILAMENT_CHANGE_FEATURE) + #if ENABLED(ADVANCED_PAUSE_FEATURE) // Portions from STATIC_ITEM... #define HOTEND_STATUS_ITEM() do { \ @@ -3201,7 +3203,7 @@ void kill_screen(const char* lcd_msg) { ++_thisItemNr; \ } while(0) - void lcd_filament_change_toocold_menu() { + void lcd_advanced_pause_toocold_menu() { START_MENU(); STATIC_ITEM(MSG_HEATING_FAILED_LCD, true, true); STATIC_ITEM(MSG_FILAMENT_CHANGE_MINTEMP STRINGIFY(EXTRUDE_MINTEMP) ".", false, false); @@ -3213,25 +3215,25 @@ void kill_screen(const char* lcd_msg) { END_MENU(); } - void lcd_filament_change_resume_print() { - filament_change_menu_response = FILAMENT_CHANGE_RESPONSE_RESUME_PRINT; + void lcd_advanced_pause_resume_print() { + advanced_pause_menu_response = ADVANCED_PAUSE_RESPONSE_RESUME_PRINT; } - void lcd_filament_change_extrude_more() { - filament_change_menu_response = FILAMENT_CHANGE_RESPONSE_EXTRUDE_MORE; + void lcd_advanced_pause_extrude_more() { + advanced_pause_menu_response = ADVANCED_PAUSE_RESPONSE_EXTRUDE_MORE; } - void lcd_filament_change_option_menu() { + void lcd_advanced_pause_option_menu() { START_MENU(); #if LCD_HEIGHT > 2 STATIC_ITEM(MSG_FILAMENT_CHANGE_OPTION_HEADER, true, false); #endif - MENU_ITEM(function, MSG_FILAMENT_CHANGE_OPTION_RESUME, lcd_filament_change_resume_print); - MENU_ITEM(function, MSG_FILAMENT_CHANGE_OPTION_EXTRUDE, lcd_filament_change_extrude_more); + MENU_ITEM(function, MSG_FILAMENT_CHANGE_OPTION_RESUME, lcd_advanced_pause_resume_print); + MENU_ITEM(function, MSG_FILAMENT_CHANGE_OPTION_EXTRUDE, lcd_advanced_pause_extrude_more); END_MENU(); } - void lcd_filament_change_init_message() { + void lcd_advanced_pause_init_message() { START_SCREEN(); STATIC_ITEM(MSG_FILAMENT_CHANGE_HEADER, true, true); STATIC_ITEM(MSG_FILAMENT_CHANGE_INIT_1); @@ -3254,7 +3256,7 @@ void kill_screen(const char* lcd_msg) { END_SCREEN(); } - void lcd_filament_change_unload_message() { + void lcd_advanced_pause_unload_message() { START_SCREEN(); STATIC_ITEM(MSG_FILAMENT_CHANGE_HEADER, true, true); STATIC_ITEM(MSG_FILAMENT_CHANGE_UNLOAD_1); @@ -3277,7 +3279,7 @@ void kill_screen(const char* lcd_msg) { END_SCREEN(); } - void lcd_filament_change_wait_for_nozzles_to_heat() { + void lcd_advanced_pause_wait_for_nozzles_to_heat() { START_SCREEN(); STATIC_ITEM(MSG_FILAMENT_CHANGE_HEADER, true, true); STATIC_ITEM(MSG_FILAMENT_CHANGE_HEATING_1); @@ -3294,7 +3296,7 @@ void kill_screen(const char* lcd_msg) { END_SCREEN(); } - void lcd_filament_change_heat_nozzle() { + void lcd_advanced_pause_heat_nozzle() { START_SCREEN(); STATIC_ITEM(MSG_FILAMENT_CHANGE_HEADER, true, true); STATIC_ITEM(MSG_FILAMENT_CHANGE_HEAT_1); @@ -3311,7 +3313,7 @@ void kill_screen(const char* lcd_msg) { END_SCREEN(); } - void lcd_filament_change_insert_message() { + void lcd_advanced_pause_insert_message() { START_SCREEN(); STATIC_ITEM(MSG_FILAMENT_CHANGE_HEADER, true, true); STATIC_ITEM(MSG_FILAMENT_CHANGE_INSERT_1); @@ -3334,7 +3336,7 @@ void kill_screen(const char* lcd_msg) { END_SCREEN(); } - void lcd_filament_change_load_message() { + void lcd_advanced_pause_load_message() { START_SCREEN(); STATIC_ITEM(MSG_FILAMENT_CHANGE_HEADER, true, true); STATIC_ITEM(MSG_FILAMENT_CHANGE_LOAD_1); @@ -3357,7 +3359,7 @@ void kill_screen(const char* lcd_msg) { END_SCREEN(); } - void lcd_filament_change_extrude_message() { + void lcd_advanced_pause_extrude_message() { START_SCREEN(); STATIC_ITEM(MSG_FILAMENT_CHANGE_HEADER, true, true); STATIC_ITEM(MSG_FILAMENT_CHANGE_EXTRUDE_1); @@ -3380,7 +3382,7 @@ void kill_screen(const char* lcd_msg) { END_SCREEN(); } - void lcd_filament_change_resume_message() { + void lcd_advanced_pause_resume_message() { START_SCREEN(); STATIC_ITEM(MSG_FILAMENT_CHANGE_HEADER, true, true); STATIC_ITEM(MSG_FILAMENT_CHANGE_RESUME_1); @@ -3393,44 +3395,52 @@ void kill_screen(const char* lcd_msg) { END_SCREEN(); } - void lcd_filament_change_show_message(const FilamentChangeMessage message) { + void lcd_advanced_pause_show_message(const AdvancedPauseMessage message) { switch (message) { - case FILAMENT_CHANGE_MESSAGE_INIT: + case ADVANCED_PAUSE_MESSAGE_INIT: defer_return_to_status = true; - lcd_goto_screen(lcd_filament_change_init_message); + lcd_goto_screen(lcd_advanced_pause_init_message); break; - case FILAMENT_CHANGE_MESSAGE_UNLOAD: - lcd_goto_screen(lcd_filament_change_unload_message); + case ADVANCED_PAUSE_MESSAGE_UNLOAD: + defer_return_to_status = true; + lcd_goto_screen(lcd_advanced_pause_unload_message); break; - case FILAMENT_CHANGE_MESSAGE_INSERT: - lcd_goto_screen(lcd_filament_change_insert_message); + case ADVANCED_PAUSE_MESSAGE_INSERT: + defer_return_to_status = true; + lcd_goto_screen(lcd_advanced_pause_insert_message); break; - case FILAMENT_CHANGE_MESSAGE_LOAD: - lcd_goto_screen(lcd_filament_change_load_message); + case ADVANCED_PAUSE_MESSAGE_LOAD: + defer_return_to_status = true; + lcd_goto_screen(lcd_advanced_pause_load_message); break; - case FILAMENT_CHANGE_MESSAGE_EXTRUDE: - lcd_goto_screen(lcd_filament_change_extrude_message); + case ADVANCED_PAUSE_MESSAGE_EXTRUDE: + defer_return_to_status = true; + lcd_goto_screen(lcd_advanced_pause_extrude_message); break; - case FILAMENT_CHANGE_MESSAGE_CLICK_TO_HEAT_NOZZLE: - lcd_goto_screen(lcd_filament_change_heat_nozzle); + case ADVANCED_PAUSE_MESSAGE_CLICK_TO_HEAT_NOZZLE: + defer_return_to_status = true; + lcd_goto_screen(lcd_advanced_pause_heat_nozzle); break; - case FILAMENT_CHANGE_MESSAGE_WAIT_FOR_NOZZLES_TO_HEAT: - lcd_goto_screen(lcd_filament_change_wait_for_nozzles_to_heat); + case ADVANCED_PAUSE_MESSAGE_WAIT_FOR_NOZZLES_TO_HEAT: + defer_return_to_status = true; + lcd_goto_screen(lcd_advanced_pause_wait_for_nozzles_to_heat); break; - case FILAMENT_CHANGE_MESSAGE_OPTION: - filament_change_menu_response = FILAMENT_CHANGE_RESPONSE_WAIT_FOR; - lcd_goto_screen(lcd_filament_change_option_menu); + case ADVANCED_PAUSE_MESSAGE_OPTION: + defer_return_to_status = true; + advanced_pause_menu_response = ADVANCED_PAUSE_RESPONSE_WAIT_FOR; + lcd_goto_screen(lcd_advanced_pause_option_menu); break; - case FILAMENT_CHANGE_MESSAGE_RESUME: - lcd_goto_screen(lcd_filament_change_resume_message); + case ADVANCED_PAUSE_MESSAGE_RESUME: + defer_return_to_status = true; + lcd_goto_screen(lcd_advanced_pause_resume_message); break; - case FILAMENT_CHANGE_MESSAGE_STATUS: + case ADVANCED_PAUSE_MESSAGE_STATUS: lcd_return_to_status(); break; } } - #endif // FILAMENT_CHANGE_FEATURE + #endif // ADVANCED_PAUSE_FEATURE /** * diff --git a/Marlin/ultralcd.h b/Marlin/ultralcd.h index 1bce5a096..c6a11ee0b 100644 --- a/Marlin/ultralcd.h +++ b/Marlin/ultralcd.h @@ -83,9 +83,9 @@ void lcd_quick_feedback(); // Audible feedback for a button click - could also be visual void lcd_completion_feedback(const bool good=true); - #if ENABLED(FILAMENT_CHANGE_FEATURE) - void lcd_filament_change_show_message(const FilamentChangeMessage message); - #endif // FILAMENT_CHANGE_FEATURE + #if ENABLED(ADVANCED_PAUSE_FEATURE) + void lcd_advanced_pause_show_message(const AdvancedPauseMessage message); + #endif // ADVANCED_PAUSE_FEATURE #else diff --git a/Marlin/ultralcd_impl_DOGM.h b/Marlin/ultralcd_impl_DOGM.h index b4ee92c5f..c0049a4c7 100644 --- a/Marlin/ultralcd_impl_DOGM.h +++ b/Marlin/ultralcd_impl_DOGM.h @@ -340,15 +340,26 @@ FORCE_INLINE void _draw_centered_temp(const int temp, const uint8_t x, const uin lcd_printPGM(PSTR(LCD_STR_DEGREE " ")); } -FORCE_INLINE void _draw_heater_status(const uint8_t x, const int8_t heater) { +FORCE_INLINE void _draw_heater_status(const uint8_t x, const int8_t heater, const bool blink) { #if HAS_TEMP_BED bool isBed = heater < 0; #else const bool isBed = false; #endif - if (PAGE_UNDER(7)) - _draw_centered_temp((isBed ? thermalManager.degTargetBed() : thermalManager.degTargetHotend(heater)) + 0.5, x, 7); + if (PAGE_UNDER(7)) { + #if ENABLED(ADVANCED_PAUSE_FEATURE) + const bool is_idle = (!isBed ? thermalManager.is_heater_idle(heater) : + #if HAS_TEMP_BED + thermalManager.is_bed_idle() + #else + false + #endif + ); + + if (blink || !is_idle) + #endif + _draw_centered_temp((isBed ? thermalManager.degTargetBed() : thermalManager.degTargetHotend(heater)) + 0.5, x, 7); } if (PAGE_CONTAINS(21, 28)) _draw_centered_temp((isBed ? thermalManager.degBed() : thermalManager.degHotend(heater)) + 0.5, x, 28); @@ -415,11 +426,11 @@ static void lcd_implementation_status_screen() { if (PAGE_UNDER(28)) { // Extruders - HOTEND_LOOP() _draw_heater_status(5 + e * 25, e); + HOTEND_LOOP() _draw_heater_status(5 + e * 25, e, blink); // Heated bed #if HOTENDS < 4 && HAS_TEMP_BED - _draw_heater_status(81, -1); + _draw_heater_status(81, -1, blink); #endif #if HAS_FAN0 @@ -662,7 +673,7 @@ static void lcd_implementation_status_screen() { uint8_t row_y1, row_y2; uint8_t constexpr row_height = DOG_CHAR_HEIGHT + 2 * (TALL_FONT_CORRECTION); - #if ENABLED(FILAMENT_CHANGE_FEATURE) + #if ENABLED(ADVANCED_PAUSE_FEATURE) static void lcd_implementation_hotend_status(const uint8_t row) { row_y1 = row * row_height + 1; @@ -679,7 +690,7 @@ static void lcd_implementation_status_screen() { lcd_print(itostr3(thermalManager.degTargetHotend(active_extruder))); } - #endif // FILAMENT_CHANGE_FEATURE + #endif // ADVANCED_PAUSE_FEATURE // Set the colors for a menu item based on whether it is selected static void lcd_implementation_mark_as_selected(const uint8_t row, const bool isSelected) { diff --git a/Marlin/ultralcd_impl_HD44780.h b/Marlin/ultralcd_impl_HD44780.h index cbad9698e..1f7683387 100644 --- a/Marlin/ultralcd_impl_HD44780.h +++ b/Marlin/ultralcd_impl_HD44780.h @@ -573,6 +573,41 @@ FORCE_INLINE void _draw_axis_label(const AxisEnum axis, const char* const pstr, } } +FORCE_INLINE void _draw_heater_status(const int8_t heater, const char prefix, const bool blink) { + const bool isBed = heater < 0; + + const float t1 = (isBed ? thermalManager.degBed() : thermalManager.degHotend(heater)); + const float t2 = (isBed ? thermalManager.degTargetBed() : thermalManager.degTargetHotend(heater)); + + if (prefix >= 0) lcd.print(prefix); + + lcd.print(itostr3(t1 + 0.5)); + lcd.print('/'); + + #if ENABLED(ADVANCED_PAUSE_FEATURE) + const bool is_idle = (!isBed ? thermalManager.is_heater_idle(heater) : + #if HAS_TEMP_BED + thermalManager.is_bed_idle() + #else + false + #endif + ); + + if (!blink && is_idle) { + lcd.print(' '); + if (t2 >= 10) lcd.print(' '); + if (t2 >= 100) lcd.print(' '); + } + else + #endif + lcd.print(itostr3left(t2 + 0.5)); + + if (prefix >= 0) { + lcd_printPGM(PSTR(LCD_STR_DEGREE " ")); + if (t2 < 10) lcd.print(' '); + } +} + #if ENABLED(LCD_PROGRESS_BAR) inline void lcd_draw_progress_bar(const uint8_t percent) { @@ -616,17 +651,7 @@ Possible status screens: |01234567890123456789| */ static void lcd_implementation_status_screen() { - - #define LCD_TEMP_ONLY(T1,T2) \ - lcd.print(itostr3(T1 + 0.5)); \ - lcd.print('/'); \ - lcd.print(itostr3left(T2 + 0.5)) - - #define LCD_TEMP(T1,T2,PREFIX) \ - lcd.print(PREFIX); \ - LCD_TEMP_ONLY(T1,T2); \ - lcd_printPGM(PSTR(LCD_STR_DEGREE " ")); \ - if (T2 < 10) lcd.print(' ') + bool blink = lcd_blink(); // // Line 1 @@ -639,7 +664,7 @@ static void lcd_implementation_status_screen() { // // Hotend 0 Temperature // - LCD_TEMP_ONLY(thermalManager.degHotend(0), thermalManager.degTargetHotend(0)); + _draw_heater_status(0, -1, blink); // // Hotend 1 or Bed Temperature @@ -649,10 +674,10 @@ static void lcd_implementation_status_screen() { lcd.setCursor(8, 0); #if HOTENDS > 1 lcd.print(LCD_STR_THERMOMETER[0]); - LCD_TEMP_ONLY(thermalManager.degHotend(1), thermalManager.degTargetHotend(1)); + _draw_heater_status(1, -1, blink); #else lcd.print(LCD_STR_BEDTEMP[0]); - LCD_TEMP_ONLY(thermalManager.degBed(), thermalManager.degTargetBed()); + _draw_heater_status(-1, -1, blink); #endif #endif // HOTENDS > 1 || TEMP_SENSOR_BED != 0 @@ -662,7 +687,7 @@ static void lcd_implementation_status_screen() { // // Hotend 0 Temperature // - LCD_TEMP(thermalManager.degHotend(0), thermalManager.degTargetHotend(0), LCD_STR_THERMOMETER[0]); + _draw_heater_status(0, LCD_STR_THERMOMETER[0], blink); // // Hotend 1 or Bed Temperature @@ -670,9 +695,9 @@ static void lcd_implementation_status_screen() { #if HOTENDS > 1 || TEMP_SENSOR_BED != 0 lcd.setCursor(10, 0); #if HOTENDS > 1 - LCD_TEMP(thermalManager.degHotend(1), thermalManager.degTargetHotend(1), LCD_STR_THERMOMETER[0]); + _draw_heater_status(1, LCD_STR_THERMOMETER[0], blink); #else - LCD_TEMP(thermalManager.degBed(), thermalManager.degTargetBed(), LCD_STR_BEDTEMP[0]); + _draw_heater_status(-1, LCD_STR_BEDTEMP[0], blink); #endif #endif // HOTENDS > 1 || TEMP_SENSOR_BED != 0 @@ -685,8 +710,6 @@ static void lcd_implementation_status_screen() { #if LCD_HEIGHT > 2 - bool blink = lcd_blink(); - #if LCD_WIDTH < 20 #if ENABLED(SDSUPPORT) @@ -708,7 +731,7 @@ static void lcd_implementation_status_screen() { // If we both have a 2nd extruder and a heated bed, // show the heated bed temp on the left, // since the first line is filled with extruder temps - LCD_TEMP(thermalManager.degBed(), thermalManager.degTargetBed(), LCD_STR_BEDTEMP[0]); + _draw_heater_status(-1, LCD_STR_BEDTEMP[0], blink); #else // Before homing the axis letters are blinking 'X' <-> '?'. @@ -803,7 +826,7 @@ static void lcd_implementation_status_screen() { #if ENABLED(ULTIPANEL) - #if ENABLED(FILAMENT_CHANGE_FEATURE) + #if ENABLED(ADVANCED_PAUSE_FEATURE) static void lcd_implementation_hotend_status(const uint8_t row) { if (row < LCD_HEIGHT) { @@ -815,7 +838,7 @@ static void lcd_implementation_status_screen() { } } - #endif // FILAMENT_CHANGE_FEATURE + #endif // ADVANCED_PAUSE_FEATURE static void lcd_implementation_drawmenu_static(const uint8_t row, const char* pstr, const bool center=true, const bool invert=false, const char *valstr=NULL) { UNUSED(invert); From 868e7db4aed5099b4cc87c39b1c14ede22e17870 Mon Sep 17 00:00:00 2001 From: Bob-the-Kuhn Date: Fri, 26 May 2017 14:49:42 -0500 Subject: [PATCH 156/189] value check was looking at the code --- Marlin/gcode.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/gcode.h b/Marlin/gcode.h index 8348f5646..e836472ee 100644 --- a/Marlin/gcode.h +++ b/Marlin/gcode.h @@ -135,7 +135,7 @@ public: static bool seen(const char c) { char *p = strchr(command_args, c); const bool b = !!p; - if (b) value_ptr = DECIMAL_SIGNED(*p) ? p + 1 : NULL; + if (b) value_ptr = DECIMAL_SIGNED(*(p + 1)) ? p + 1 : NULL; return b; } From 55c700d537d50bb06b6ced7c2ca61ffcaba7735a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 26 May 2017 22:11:31 -0500 Subject: [PATCH 157/189] Tweak to gcode.h --- Marlin/gcode.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/gcode.h b/Marlin/gcode.h index e836472ee..26154a6bc 100644 --- a/Marlin/gcode.h +++ b/Marlin/gcode.h @@ -135,7 +135,7 @@ public: static bool seen(const char c) { char *p = strchr(command_args, c); const bool b = !!p; - if (b) value_ptr = DECIMAL_SIGNED(*(p + 1)) ? p + 1 : NULL; + if (b) value_ptr = DECIMAL_SIGNED(p[1]) ? &p[1] : NULL; return b; } From ac959b12ee3697964805b43c6d0767dca2d39e28 Mon Sep 17 00:00:00 2001 From: Ernesto Martinez Date: Sun, 28 May 2017 08:08:39 +0800 Subject: [PATCH 158/189] Updates to language_es.h based on latest updates. (#6871) Spanish language updates --- Marlin/language_es.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/language_es.h b/Marlin/language_es.h index 003caf8c3..035ffd2b5 100644 --- a/Marlin/language_es.h +++ b/Marlin/language_es.h @@ -161,7 +161,7 @@ #define MSG_BLTOUCH_SELFTEST _UxGT("BLTouch Auto-Prueba") #define MSG_BLTOUCH_RESET _UxGT("Reiniciar BLTouch") #define MSG_HOME _UxGT("Home") // Used as MSG_HOME " " MSG_X MSG_Y MSG_Z " " MSG_FIRST -#define MSG_FIRST _UxGT("first") +#define MSG_FIRST _UxGT("inic.") #define MSG_ZPROBE_ZOFFSET _UxGT("Desfase Z") #define MSG_BABYSTEP_X _UxGT("Micropaso X") #define MSG_BABYSTEP_Y _UxGT("Micropaso Y") @@ -169,7 +169,7 @@ #define MSG_ENDSTOP_ABORT _UxGT("Cancelado - Endstop") #define MSG_HEATING_FAILED_LCD _UxGT("Error: al calentar") #define MSG_ERR_REDUNDANT_TEMP _UxGT("Error: temperatura") -#define MSG_THERMAL_RUNAWAY _UxGT("Error de temperatura") +#define MSG_THERMAL_RUNAWAY _UxGT("Error: temperatura") #define MSG_ERR_MAXTEMP _UxGT("Error: Temp Maxima") #define MSG_ERR_MINTEMP _UxGT("Error: Temp Minima") #define MSG_ERR_MAXTEMP_BED _UxGT("Error: Temp Max Plat") @@ -221,8 +221,8 @@ #define MSG_DAC_PERCENT _UxGT("Driver %") #define MSG_DAC_EEPROM_WRITE _UxGT("Escribe DAC EEPROM") -#define MSG_FILAMENT_CHANGE_HEADER _UxGT("PRINT PAUSED") -#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("RESUME OPTIONS:") +#define MSG_FILAMENT_CHANGE_HEADER _UxGT("IMPR. PAUSADA") +#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("OPC. REINICIO:") #define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("Extruir mas") #define MSG_FILAMENT_CHANGE_OPTION_RESUME _UxGT("Resumir imp.") From 33279a1e029a04c06d2afbfe7ca5d30eabd6df39 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 27 May 2017 15:58:22 -0500 Subject: [PATCH 159/189] Code style tweak to gcode.h --- Marlin/gcode.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/gcode.h b/Marlin/gcode.h index 26154a6bc..d7f76cbcd 100644 --- a/Marlin/gcode.h +++ b/Marlin/gcode.h @@ -133,7 +133,7 @@ public: // Code is found in the string. If not found, value_ptr is unchanged. // This allows "if (seen('A')||seen('B'))" to use the last-found value. static bool seen(const char c) { - char *p = strchr(command_args, c); + const char *p = strchr(command_args, c); const bool b = !!p; if (b) value_ptr = DECIMAL_SIGNED(p[1]) ? &p[1] : NULL; return b; From f379a326cc3cf6a5a11e9bf5e70a493ecb5a68d4 Mon Sep 17 00:00:00 2001 From: christianh17 Date: Sun, 28 May 2017 15:33:28 +0200 Subject: [PATCH 160/189] enable DEACTIVATE_SERVOS_AFTER_MOVE with switching nozzle When using switching nozzle it should be possible to disable the servo after move. Do it only if you do not need the servo power to keep the position. --- Marlin/SanityCheck.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index f6c7245a2..bb3930c0b 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -407,10 +407,10 @@ #endif /** - * Servo deactivation depends on servo endstops + * Servo deactivation depends on servo endstops or switching nozzle */ -#if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE) && !HAS_Z_SERVO_ENDSTOP - #error "Z_ENDSTOP_SERVO_NR is required for DEACTIVATE_SERVOS_AFTER_MOVE." +#if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE) && !HAS_Z_SERVO_ENDSTOP && !defined(SWITCHING_NOZZLE_SERVO_NR) + #error "Z_ENDSTOP_SERVO_NR or switching nozzle is required for DEACTIVATE_SERVOS_AFTER_MOVE." #endif /** From 493f0b0c62c846708a8a4d2b4998467b21221c88 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 27 May 2017 16:42:56 -0500 Subject: [PATCH 161/189] Fix some compiler warnings --- Marlin/Marlin_main.cpp | 15 +++++++-------- 1 file changed, 7 insertions(+), 8 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 75edc0e6f..6a2a7500e 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -5746,9 +5746,9 @@ inline void gcode_M17() { static bool sd_print_paused = false; #endif - static void filament_change_beep(const int max_beep_count, const bool init=false) { + static void filament_change_beep(const int8_t max_beep_count, const bool init=false) { static millis_t next_buzz = 0; - static uint16_t runout_beep = 0; + static int8_t runout_beep = 0; if (init) next_buzz = runout_beep = 0; @@ -5762,8 +5762,9 @@ inline void gcode_M17() { } } - static bool pause_print(const float& retract, const float& z_lift, const float& x_pos, const float& y_pos, - const float& unload_length = 0 , int max_beep_count = 0, bool show_lcd = false) { + static bool pause_print(const float &retract, const float &z_lift, const float &x_pos, const float &y_pos, + const float &unload_length = 0 , int8_t max_beep_count = 0, bool show_lcd = false + ) { if (move_away_flag) return false; // already paused if (!DEBUGGING(DRYRUN) && thermalManager.tooColdToExtrude(active_extruder) && unload_length > 0) { @@ -5772,8 +5773,6 @@ inline void gcode_M17() { return false; } - const bool job_running = print_job_timer.isRunning(); - // Indicate that the printer is paused move_away_flag = true; @@ -5857,7 +5856,7 @@ inline void gcode_M17() { return true; } - static void wait_for_filament_reload(int max_beep_count = 0) { + static void wait_for_filament_reload(int8_t max_beep_count = 0) { bool nozzle_timed_out = false; // Wait for filament insert by user and press button @@ -5882,7 +5881,7 @@ inline void gcode_M17() { KEEPALIVE_STATE(IN_HANDLER); } - static void resume_print(const float& load_length = 0, const float& initial_extrude_length = 0, int max_beep_count = 0) { + static void resume_print(const float& load_length = 0, const float& initial_extrude_length = 0, int8_t max_beep_count = 0) { bool nozzle_timed_out = false; if (!move_away_flag) return; From b0eae68f57d25e27405ebc9db84c617d440b3db8 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 28 May 2017 11:11:17 -0500 Subject: [PATCH 162/189] Prevent bed temperature being set too high --- Marlin/temperature.cpp | 7 +++++-- Marlin/temperature.h | 25 ++++++++++++++++++++----- 2 files changed, 25 insertions(+), 7 deletions(-) diff --git a/Marlin/temperature.cpp b/Marlin/temperature.cpp index 3cac779d3..376740b9f 100644 --- a/Marlin/temperature.cpp +++ b/Marlin/temperature.cpp @@ -67,8 +67,11 @@ float Temperature::current_temperature[HOTENDS] = { 0.0 }, Temperature::current_temperature_bed = 0.0; int16_t Temperature::current_temperature_raw[HOTENDS] = { 0 }, Temperature::target_temperature[HOTENDS] = { 0 }, - Temperature::current_temperature_bed_raw = 0, - Temperature::target_temperature_bed = 0; + Temperature::current_temperature_bed_raw = 0; + +#if HAS_HEATER_BED + int16_t Temperature::target_temperature_bed = 0; +#endif #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) float Temperature::redundant_temperature = 0.0; diff --git a/Marlin/temperature.h b/Marlin/temperature.h index 0e911a70c..c75349681 100644 --- a/Marlin/temperature.h +++ b/Marlin/temperature.h @@ -92,6 +92,10 @@ enum ADCSensorState { #define ACTUAL_ADC_SAMPLES max(int(MIN_ADC_ISR_LOOPS), int(SensorsReady)) +#if !HAS_HEATER_BED + constexpr int16_t target_temperature_bed = 0; +#endif + class Temperature { public: @@ -100,8 +104,11 @@ class Temperature { current_temperature_bed; static int16_t current_temperature_raw[HOTENDS], target_temperature[HOTENDS], - current_temperature_bed_raw, - target_temperature_bed; + current_temperature_bed_raw; + + #if HAS_HEATER_BED + static int16_t target_temperature_bed; + #endif static volatile bool in_temp_isr; @@ -382,9 +389,17 @@ class Temperature { } static void setTargetBed(const int16_t celsius) { - target_temperature_bed = celsius; - #if WATCH_THE_BED - start_watching_bed(); + #if HAS_HEATER_BED + target_temperature_bed = + #ifdef BED_MAXTEMP + min(celsius, BED_MAXTEMP) + #else + celsius + #endif + ; + #if WATCH_THE_BED + start_watching_bed(); + #endif #endif } From 71367fd518acdf3257250cde7a21766b707424d2 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 28 May 2017 11:12:12 -0500 Subject: [PATCH 163/189] Scrolling status message option --- Marlin/Configuration_adv.h | 3 ++ .../Cartesio/Configuration_adv.h | 3 ++ .../Felix/Configuration_adv.h | 3 ++ .../FolgerTech-i3-2020/Configuration_adv.h | 3 ++ .../Hephestos/Configuration_adv.h | 3 ++ .../Hephestos_2/Configuration_adv.h | 3 ++ .../K8200/Configuration_adv.h | 3 ++ .../K8400/Configuration_adv.h | 3 ++ .../RigidBot/Configuration_adv.h | 3 ++ .../SCARA/Configuration_adv.h | 3 ++ .../TAZ4/Configuration_adv.h | 3 ++ .../TinyBoy2/Configuration_adv.h | 3 ++ .../WITBOX/Configuration_adv.h | 3 ++ .../FLSUN/auto_calibrate/Configuration_adv.h | 3 ++ .../FLSUN/kossel_mini/Configuration_adv.h | 3 ++ .../delta/generic/Configuration_adv.h | 3 ++ .../delta/kossel_mini/Configuration_adv.h | 3 ++ .../delta/kossel_pro/Configuration_adv.h | 3 ++ .../delta/kossel_xl/Configuration_adv.h | 3 ++ .../gCreate_gMax1.5+/Configuration_adv.h | 3 ++ .../makibox/Configuration_adv.h | 3 ++ .../tvrrug/Round2/Configuration_adv.h | 3 ++ .../wt150/Configuration_adv.h | 3 ++ Marlin/ultralcd.cpp | 40 +++++++++++----- Marlin/ultralcd_impl_DOGM.h | 47 +++++++++++++------ Marlin/ultralcd_impl_HD44780.h | 37 ++++++++++----- 26 files changed, 154 insertions(+), 39 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 36291de0d..d593ed095 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -442,6 +442,9 @@ // Include a page of printer information in the LCD Main Menu //#define LCD_INFO_MENU +// Scroll a longer status message into view +//#define STATUS_MESSAGE_SCROLLING + // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY diff --git a/Marlin/example_configurations/Cartesio/Configuration_adv.h b/Marlin/example_configurations/Cartesio/Configuration_adv.h index 5a1184c93..a8f4c3166 100644 --- a/Marlin/example_configurations/Cartesio/Configuration_adv.h +++ b/Marlin/example_configurations/Cartesio/Configuration_adv.h @@ -442,6 +442,9 @@ // Include a page of printer information in the LCD Main Menu //#define LCD_INFO_MENU +// Scroll a longer status message into view +//#define STATUS_MESSAGE_SCROLLING + // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY diff --git a/Marlin/example_configurations/Felix/Configuration_adv.h b/Marlin/example_configurations/Felix/Configuration_adv.h index a0daae4e6..3132bf9ff 100644 --- a/Marlin/example_configurations/Felix/Configuration_adv.h +++ b/Marlin/example_configurations/Felix/Configuration_adv.h @@ -442,6 +442,9 @@ // Include a page of printer information in the LCD Main Menu //#define LCD_INFO_MENU +// Scroll a longer status message into view +//#define STATUS_MESSAGE_SCROLLING + // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h index 14488300c..142cd1d24 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h @@ -442,6 +442,9 @@ // Include a page of printer information in the LCD Main Menu //#define LCD_INFO_MENU +// Scroll a longer status message into view +//#define STATUS_MESSAGE_SCROLLING + // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY diff --git a/Marlin/example_configurations/Hephestos/Configuration_adv.h b/Marlin/example_configurations/Hephestos/Configuration_adv.h index e165a7fc3..171ab3e4d 100644 --- a/Marlin/example_configurations/Hephestos/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos/Configuration_adv.h @@ -442,6 +442,9 @@ // Include a page of printer information in the LCD Main Menu //#define LCD_INFO_MENU +// Scroll a longer status message into view +//#define STATUS_MESSAGE_SCROLLING + // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY diff --git a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h index 7fe59aa6d..fb7869435 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h @@ -443,6 +443,9 @@ // Include a page of printer information in the LCD Main Menu #define LCD_INFO_MENU +// Scroll a longer status message into view +//#define STATUS_MESSAGE_SCROLLING + // On the Info Screen, display XY with one decimal place when possible #define LCD_DECIMAL_SMALL_XY diff --git a/Marlin/example_configurations/K8200/Configuration_adv.h b/Marlin/example_configurations/K8200/Configuration_adv.h index 2311850eb..44aae82fa 100644 --- a/Marlin/example_configurations/K8200/Configuration_adv.h +++ b/Marlin/example_configurations/K8200/Configuration_adv.h @@ -455,6 +455,9 @@ // Include a page of printer information in the LCD Main Menu //#define LCD_INFO_MENU +// Scroll a longer status message into view +//#define STATUS_MESSAGE_SCROLLING + // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY diff --git a/Marlin/example_configurations/K8400/Configuration_adv.h b/Marlin/example_configurations/K8400/Configuration_adv.h index 538c121d8..a04d83baf 100644 --- a/Marlin/example_configurations/K8400/Configuration_adv.h +++ b/Marlin/example_configurations/K8400/Configuration_adv.h @@ -442,6 +442,9 @@ // Include a page of printer information in the LCD Main Menu //#define LCD_INFO_MENU +// Scroll a longer status message into view +//#define STATUS_MESSAGE_SCROLLING + // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY diff --git a/Marlin/example_configurations/RigidBot/Configuration_adv.h b/Marlin/example_configurations/RigidBot/Configuration_adv.h index 0df6dfc18..3605da6a7 100644 --- a/Marlin/example_configurations/RigidBot/Configuration_adv.h +++ b/Marlin/example_configurations/RigidBot/Configuration_adv.h @@ -442,6 +442,9 @@ // Include a page of printer information in the LCD Main Menu //#define LCD_INFO_MENU +// Scroll a longer status message into view +//#define STATUS_MESSAGE_SCROLLING + // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY diff --git a/Marlin/example_configurations/SCARA/Configuration_adv.h b/Marlin/example_configurations/SCARA/Configuration_adv.h index 60b47073c..6bfee737d 100644 --- a/Marlin/example_configurations/SCARA/Configuration_adv.h +++ b/Marlin/example_configurations/SCARA/Configuration_adv.h @@ -442,6 +442,9 @@ // Include a page of printer information in the LCD Main Menu //#define LCD_INFO_MENU +// Scroll a longer status message into view +//#define STATUS_MESSAGE_SCROLLING + // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY diff --git a/Marlin/example_configurations/TAZ4/Configuration_adv.h b/Marlin/example_configurations/TAZ4/Configuration_adv.h index 7bc66c6d4..05caf958e 100644 --- a/Marlin/example_configurations/TAZ4/Configuration_adv.h +++ b/Marlin/example_configurations/TAZ4/Configuration_adv.h @@ -442,6 +442,9 @@ // Include a page of printer information in the LCD Main Menu //#define LCD_INFO_MENU +// Scroll a longer status message into view +//#define STATUS_MESSAGE_SCROLLING + // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY diff --git a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h index 36623187d..488da0e2b 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h @@ -442,6 +442,9 @@ // Include a page of printer information in the LCD Main Menu #define LCD_INFO_MENU +// Scroll a longer status message into view +//#define STATUS_MESSAGE_SCROLLING + // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY diff --git a/Marlin/example_configurations/WITBOX/Configuration_adv.h b/Marlin/example_configurations/WITBOX/Configuration_adv.h index e165a7fc3..171ab3e4d 100644 --- a/Marlin/example_configurations/WITBOX/Configuration_adv.h +++ b/Marlin/example_configurations/WITBOX/Configuration_adv.h @@ -442,6 +442,9 @@ // Include a page of printer information in the LCD Main Menu //#define LCD_INFO_MENU +// Scroll a longer status message into view +//#define STATUS_MESSAGE_SCROLLING + // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h index 62eaf358b..eb44f9e09 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h @@ -444,6 +444,9 @@ // Include a page of printer information in the LCD Main Menu //#define LCD_INFO_MENU +// Scroll a longer status message into view +//#define STATUS_MESSAGE_SCROLLING + // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h index 6ad9e985f..6eed64c6f 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h @@ -444,6 +444,9 @@ // Include a page of printer information in the LCD Main Menu //#define LCD_INFO_MENU +// Scroll a longer status message into view +//#define STATUS_MESSAGE_SCROLLING + // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY diff --git a/Marlin/example_configurations/delta/generic/Configuration_adv.h b/Marlin/example_configurations/delta/generic/Configuration_adv.h index 2664b31be..6f45736b6 100644 --- a/Marlin/example_configurations/delta/generic/Configuration_adv.h +++ b/Marlin/example_configurations/delta/generic/Configuration_adv.h @@ -444,6 +444,9 @@ // Include a page of printer information in the LCD Main Menu //#define LCD_INFO_MENU +// Scroll a longer status message into view +//#define STATUS_MESSAGE_SCROLLING + // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h index 2664b31be..6f45736b6 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h @@ -444,6 +444,9 @@ // Include a page of printer information in the LCD Main Menu //#define LCD_INFO_MENU +// Scroll a longer status message into view +//#define STATUS_MESSAGE_SCROLLING + // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h index e7142cf16..8f7ae5496 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h @@ -449,6 +449,9 @@ // Include a page of printer information in the LCD Main Menu //#define LCD_INFO_MENU +// Scroll a longer status message into view +//#define STATUS_MESSAGE_SCROLLING + // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h index e1fe86a0e..779dbe9a9 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h @@ -444,6 +444,9 @@ // Include a page of printer information in the LCD Main Menu //#define LCD_INFO_MENU +// Scroll a longer status message into view +//#define STATUS_MESSAGE_SCROLLING + // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h index 59b43ccb6..71a3d90e0 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h @@ -442,6 +442,9 @@ // Include a page of printer information in the LCD Main Menu //#define LCD_INFO_MENU +// Scroll a longer status message into view +//#define STATUS_MESSAGE_SCROLLING + // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY diff --git a/Marlin/example_configurations/makibox/Configuration_adv.h b/Marlin/example_configurations/makibox/Configuration_adv.h index 5483576d9..9aa560794 100644 --- a/Marlin/example_configurations/makibox/Configuration_adv.h +++ b/Marlin/example_configurations/makibox/Configuration_adv.h @@ -442,6 +442,9 @@ // Include a page of printer information in the LCD Main Menu //#define LCD_INFO_MENU +// Scroll a longer status message into view +//#define STATUS_MESSAGE_SCROLLING + // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h index 8dcc348ab..660d479b5 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h @@ -442,6 +442,9 @@ // Include a page of printer information in the LCD Main Menu //#define LCD_INFO_MENU +// Scroll a longer status message into view +//#define STATUS_MESSAGE_SCROLLING + // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY diff --git a/Marlin/example_configurations/wt150/Configuration_adv.h b/Marlin/example_configurations/wt150/Configuration_adv.h index 700c5227f..bf586bdba 100644 --- a/Marlin/example_configurations/wt150/Configuration_adv.h +++ b/Marlin/example_configurations/wt150/Configuration_adv.h @@ -442,6 +442,9 @@ // Include a page of printer information in the LCD Main Menu #define LCD_INFO_MENU +// Scroll a longer status message into view +//#define STATUS_MESSAGE_SCROLLING + // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 32d47419d..6cacb3ae6 100755 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -60,6 +60,9 @@ int lcd_preheat_hotend_temp[2], lcd_preheat_bed_temp[2], lcd_preheat_fan_speed[2 uint8_t lcd_status_message_level; char lcd_status_message[3 * (LCD_WIDTH) + 1] = WELCOME_MSG; // worst case is kana with up to 3*LCD_WIDTH+1 +#if ENABLED(STATUS_MESSAGE_SCROLLING) + uint8_t status_scroll_pos = 0; +#endif #if ENABLED(DOGLCD) #include "ultralcd_impl_DOGM.h" @@ -3961,22 +3964,29 @@ void lcd_update() { } // ELAPSED(ms, next_lcd_update_ms) } -void set_utf_strlen(char* s, uint8_t n) { - uint8_t i = 0, j = 0; - while (s[i] && (j < n)) { - #if ENABLED(MAPPER_NON) - j++; - #else - if ((s[i] & 0xC0u) != 0x80u) j++; - #endif - i++; +#if DISABLED(STATUS_MESSAGE_SCROLLING) + + void set_utf_strlen(char* s, uint8_t n) { + uint8_t i = 0, j = 0; + while (s[i] && (j < n)) { + #if ENABLED(MAPPER_NON) + j++; + #else + if ((s[i] & 0xC0u) != 0x80u) j++; + #endif + i++; + } + while (j++ < n) s[i++] = ' '; + s[i] = '\0'; } - while (j++ < n) s[i++] = ' '; - s[i] = '\0'; -} + +#endif // !STATUS_MESSAGE_SCROLLING void lcd_finishstatus(bool persist=false) { - set_utf_strlen(lcd_status_message, LCD_WIDTH); + #if DISABLED(STATUS_MESSAGE_SCROLLING) + set_utf_strlen(lcd_status_message, LCD_WIDTH); + #endif + #if !(ENABLED(LCD_PROGRESS_BAR) && (PROGRESS_MSG_EXPIRE > 0)) UNUSED(persist); #endif @@ -3992,6 +4002,10 @@ void lcd_finishstatus(bool persist=false) { #if ENABLED(FILAMENT_LCD_DISPLAY) && ENABLED(SDSUPPORT) previous_lcd_status_ms = millis(); //get status message to show up for a while #endif + + #if ENABLED(STATUS_MESSAGE_SCROLLING) + status_scroll_pos = 0; + #endif } #if ENABLED(LCD_PROGRESS_BAR) && PROGRESS_MSG_EXPIRE > 0 diff --git a/Marlin/ultralcd_impl_DOGM.h b/Marlin/ultralcd_impl_DOGM.h index c0049a4c7..ac6fedabb 100644 --- a/Marlin/ultralcd_impl_DOGM.h +++ b/Marlin/ultralcd_impl_DOGM.h @@ -234,13 +234,24 @@ char lcd_print_and_count(const char c) { else return charset_mapper(c); } -void lcd_print(const char* const str) { - for (uint8_t i = 0; char c = str[i]; ++i) lcd_print(c); +/** + * Core LCD printing functions + * On DOGM all strings go through a filter for utf + * But only use lcd_print_utf and lcd_printPGM_utf for translated text + */ +void lcd_print(const char* const str) { for (uint8_t i = 0; char c = str[i]; ++i) lcd_print(c); } +void lcd_printPGM(const char* str) { for (; char c = pgm_read_byte(str); ++str) lcd_print(c); } + +void lcd_print_utf(const char* const str, const uint8_t maxLength=LCD_WIDTH) { + char c; + for (uint8_t i = 0, n = maxLength; n && (c = str[i]); ++i) + n -= charset_mapper(c); } -/* Arduino < 1.0.0 is missing a function to print PROGMEM strings, so we need to implement our own */ -void lcd_printPGM(const char* str) { - for (; char c = pgm_read_byte(str); ++str) lcd_print(c); +void lcd_printPGM_utf(const char* str, const uint8_t maxLength=LCD_WIDTH) { + char c; + for (uint8_t i = 0, n = maxLength; n && (c = str[i]); ++i) + n -= charset_mapper(c); } // Initialize or re-initialize the LCD @@ -320,7 +331,7 @@ static void lcd_implementation_init() { void lcd_kill_screen() { lcd_setFont(FONT_MENU); u8g.setPrintPos(0, u8g.getHeight()/4*1); - lcd_print(lcd_status_message); + lcd_print_utf(lcd_status_message); u8g.setPrintPos(0, u8g.getHeight()/4*2); lcd_printPGM(PSTR(MSG_HALTED)); u8g.setPrintPos(0, u8g.getHeight()/4*3); @@ -395,6 +406,20 @@ FORCE_INLINE void _draw_axis_label(const AxisEnum axis, const char* const pstr, } } +inline void lcd_implementation_status_message() { + #if ENABLED(STATUS_MESSAGE_SCROLLING) + lcd_print_utf(lcd_status_message + status_scroll_pos); + const uint8_t slen = lcd_strlen(lcd_status_message); + if (slen > LCD_WIDTH) { + // Skip any non-printing bytes + while (!charset_mapper(lcd_status_message[status_scroll_pos])) ++status_scroll_pos; + if (++status_scroll_pos > slen - LCD_WIDTH) status_scroll_pos = 0; + } + #else + lcd_print_utf(lcd_status_message); + #endif +} + //#define DOGM_SD_PERCENT static void lcd_implementation_status_screen() { @@ -645,10 +670,7 @@ static void lcd_implementation_status_screen() { #if ENABLED(FILAMENT_LCD_DISPLAY) && ENABLED(SDSUPPORT) if (PENDING(millis(), previous_lcd_status_ms + 5000UL)) { //Display both Status message line and Filament display on the last line - const char *str = lcd_status_message; - uint8_t i = LCD_WIDTH; - char c; - while (i-- && (c = *str++)) lcd_print(c); + lcd_implementation_status_message(); } else { lcd_printPGM(PSTR(LCD_STR_FILAM_DIA)); @@ -660,10 +682,7 @@ static void lcd_implementation_status_screen() { u8g.print('%'); } #else - const char *str = lcd_status_message; - uint8_t i = LCD_WIDTH; - char c; - while (i-- && (c = *str++)) lcd_print(c); + lcd_implementation_status_message(); #endif } } diff --git a/Marlin/ultralcd_impl_HD44780.h b/Marlin/ultralcd_impl_HD44780.h index 1f7683387..b735baa8f 100644 --- a/Marlin/ultralcd_impl_HD44780.h +++ b/Marlin/ultralcd_impl_HD44780.h @@ -380,16 +380,22 @@ static void lcd_implementation_init( void lcd_implementation_clear() { lcd.clear(); } -/* Arduino < 1.0.0 is missing a function to print PROGMEM strings, so we need to implement our own */ -void lcd_printPGM(const char *str) { - for (; char c = pgm_read_byte(str); ++str) charset_mapper(c); -} +void lcd_print(const char c) { charset_mapper(c); } + +void lcd_print(const char * const str) { for (uint8_t i = 0; char c = str[i]; ++i) lcd.print(c); } +void lcd_printPGM(const char* str) { for (; char c = pgm_read_byte(str); ++str) lcd.print(c); } -void lcd_print(const char* const str) { - for (uint8_t i = 0; const char c = str[i]; ++i) charset_mapper(c); +void lcd_print_utf(const char * const str, const uint8_t maxLength=LCD_WIDTH) { + char c; + for (uint8_t i = 0, n = maxLength; n && (c = str[i]); ++i) + n -= charset_mapper(c); } -void lcd_print(const char c) { charset_mapper(c); } +void lcd_printPGM_utf(const char* str, const uint8_t maxLength=LCD_WIDTH) { + char c; + for (uint8_t i = 0, n = maxLength; n && (c = str[i]); ++i) + n -= charset_mapper(c); +} #if ENABLED(SHOW_BOOTSCREEN) @@ -545,7 +551,7 @@ void lcd_print(const char c) { charset_mapper(c); } void lcd_kill_screen() { lcd.setCursor(0, 0); - lcd_print(lcd_status_message); + lcd_print_utf(lcd_status_message); #if LCD_HEIGHT < 4 lcd.setCursor(0, 2); #else @@ -818,10 +824,17 @@ static void lcd_implementation_status_screen() { #endif // FILAMENT_LCD_DISPLAY && SDSUPPORT - const char *str = lcd_status_message; - uint8_t i = LCD_WIDTH; - char c; - while (i-- && (c = *str++)) lcd_print(c); + #if ENABLED(STATUS_MESSAGE_SCROLLING) + lcd_print_utf(lcd_status_message + status_scroll_pos); + const uint8_t slen = lcd_strlen(lcd_status_message); + if (slen > LCD_WIDTH) { + // Skip any non-printing bytes + while (!charset_mapper(lcd_status_message[status_scroll_pos])) ++status_scroll_pos; + if (++status_scroll_pos > slen - LCD_WIDTH) status_scroll_pos = 0; + } + #else + lcd_print_utf(lcd_status_message); + #endif } #if ENABLED(ULTIPANEL) From a3645ec9216290c1aa4f9c473a6b84a5c153969a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 28 May 2017 11:33:22 -0500 Subject: [PATCH 164/189] Reference op with variable name --- Marlin/Marlin_main.cpp | 2 +- Marlin/SdBaseFile.cpp | 2 +- Marlin/SdBaseFile.h | 4 ++-- Marlin/planner.cpp | 2 +- Marlin/ubl_motion.cpp | 4 ++-- Marlin/utility.cpp | 28 ++++++++++++++-------------- Marlin/utility.h | 32 ++++++++++++++++---------------- Marlin/vector_3.h | 2 +- 8 files changed, 38 insertions(+), 38 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 6a2a7500e..5b0f56c3e 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -5881,7 +5881,7 @@ inline void gcode_M17() { KEEPALIVE_STATE(IN_HANDLER); } - static void resume_print(const float& load_length = 0, const float& initial_extrude_length = 0, int8_t max_beep_count = 0) { + static void resume_print(const float &load_length = 0, const float &initial_extrude_length = 0, int8_t max_beep_count = 0) { bool nozzle_timed_out = false; if (!move_away_flag) return; diff --git a/Marlin/SdBaseFile.cpp b/Marlin/SdBaseFile.cpp index 298cdd114..97b4fa00f 100644 --- a/Marlin/SdBaseFile.cpp +++ b/Marlin/SdBaseFile.cpp @@ -1819,7 +1819,7 @@ fail: //------------------------------------------------------------------------------ // suppress cpplint warnings with NOLINT comment #if ALLOW_DEPRECATED_FUNCTIONS && !defined(DOXYGEN) - void (*SdBaseFile::oldDateTime_)(uint16_t& date, uint16_t& time) = 0; // NOLINT + void (*SdBaseFile::oldDateTime_)(uint16_t &date, uint16_t &time) = 0; // NOLINT #endif // ALLOW_DEPRECATED_FUNCTIONS diff --git a/Marlin/SdBaseFile.h b/Marlin/SdBaseFile.h index 2b912d2ed..02ab70543 100644 --- a/Marlin/SdBaseFile.h +++ b/Marlin/SdBaseFile.h @@ -402,7 +402,7 @@ class SdBaseFile { * \param[in] dateTime The user's call back function. */ static void dateTimeCallback( - void (*dateTime)(uint16_t& date, uint16_t& time)) { // NOLINT + void (*dateTime)(uint16_t &date, uint16_t &time)) { // NOLINT oldDateTime_ = dateTime; dateTime_ = dateTime ? oldToNew : 0; } @@ -477,7 +477,7 @@ class SdBaseFile { //------------------------------------------------------------------------------ // rest are private private: - static void (*oldDateTime_)(uint16_t& date, uint16_t& time); // NOLINT + static void (*oldDateTime_)(uint16_t &date, uint16_t &time); // NOLINT static void oldToNew(uint16_t* date, uint16_t* time) { uint16_t d; uint16_t t; diff --git a/Marlin/planner.cpp b/Marlin/planner.cpp index 44b1a36f4..4deeb83e8 100644 --- a/Marlin/planner.cpp +++ b/Marlin/planner.cpp @@ -1510,7 +1510,7 @@ void Planner::sync_from_steppers() { /** * Setters for planner position (also setting stepper position). */ -void Planner::set_position_mm(const AxisEnum axis, const float& v) { +void Planner::set_position_mm(const AxisEnum axis, const float &v) { #if ENABLED(DISTINCT_E_FACTORS) const uint8_t axis_index = axis + (axis == E_AXIS ? active_extruder : 0); last_extruder = active_extruder; diff --git a/Marlin/ubl_motion.cpp b/Marlin/ubl_motion.cpp index e733d75ca..5131315e1 100644 --- a/Marlin/ubl_motion.cpp +++ b/Marlin/ubl_motion.cpp @@ -585,8 +585,8 @@ float seg_dest[XYZE]; // per-segment destination, initialize to first segment LOOP_XYZE(i) seg_dest[i] = current_position[i] + segment_distance[i]; - const float& dx_seg = segment_distance[X_AXIS]; // alias for clarity - const float& dy_seg = segment_distance[Y_AXIS]; + const float &dx_seg = segment_distance[X_AXIS]; // alias for clarity + const float &dy_seg = segment_distance[Y_AXIS]; float rx = RAW_X_POSITION(seg_dest[X_AXIS]), // assume raw vs logical coordinates shifted but not scaled. ry = RAW_Y_POSITION(seg_dest[Y_AXIS]); diff --git a/Marlin/utility.cpp b/Marlin/utility.cpp index 15378fb62..ee1bef1c9 100644 --- a/Marlin/utility.cpp +++ b/Marlin/utility.cpp @@ -57,14 +57,14 @@ void safe_delay(millis_t ms) { #define MINUSOR(n, alt) (n >= 0 ? (alt) : (n = -n, '-')) // Convert unsigned int to string with 12 format - char* itostr2(const uint8_t& xx) { + char* itostr2(const uint8_t &xx) { conv[5] = DIGIMOD(xx, 10); conv[6] = DIGIMOD(xx, 1); return &conv[5]; } // Convert signed int to rj string with 123 or -12 format - char* itostr3(const int& x) { + char* itostr3(const int &x) { int xx = x; conv[4] = MINUSOR(xx, RJDIGIT(xx, 100)); conv[5] = RJDIGIT(xx, 10); @@ -73,7 +73,7 @@ void safe_delay(millis_t ms) { } // Convert unsigned int to lj string with 123 format - char* itostr3left(const int& xx) { + char* itostr3left(const int &xx) { char *str = &conv[6]; *str = DIGIMOD(xx, 1); if (xx >= 10) { @@ -85,7 +85,7 @@ void safe_delay(millis_t ms) { } // Convert signed int to rj string with 1234, _123, -123, _-12, or __-1 format - char *itostr4sign(const int& x) { + char *itostr4sign(const int &x) { const bool neg = x < 0; const int xx = neg ? -x : x; if (x >= 1000) { @@ -116,7 +116,7 @@ void safe_delay(millis_t ms) { } // Convert unsigned float to string with 1.23 format - char* ftostr12ns(const float& x) { + char* ftostr12ns(const float &x) { const long xx = (x < 0 ? -x : x) * 100; conv[3] = DIGIMOD(xx, 100); conv[4] = '.'; @@ -126,7 +126,7 @@ void safe_delay(millis_t ms) { } // Convert signed float to fixed-length string with 023.45 / -23.45 format - char *ftostr32(const float& x) { + char *ftostr32(const float &x) { long xx = x * 100; conv[1] = MINUSOR(xx, DIGIMOD(xx, 10000)); conv[2] = DIGIMOD(xx, 1000); @@ -140,7 +140,7 @@ void safe_delay(millis_t ms) { #if ENABLED(LCD_DECIMAL_SMALL_XY) // Convert float to rj string with 1234, _123, -123, _-12, 12.3, _1.2, or -1.2 format - char *ftostr4sign(const float& fx) { + char *ftostr4sign(const float &fx) { const int x = fx * 10; if (!WITHIN(x, -99, 999)) return itostr4sign((int)fx); const bool neg = x < 0; @@ -155,7 +155,7 @@ void safe_delay(millis_t ms) { #endif // LCD_DECIMAL_SMALL_XY // Convert float to fixed-length string with +123.4 / -123.4 format - char* ftostr41sign(const float& x) { + char* ftostr41sign(const float &x) { int xx = x * 10; conv[1] = MINUSOR(xx, '+'); conv[2] = DIGIMOD(xx, 1000); @@ -167,7 +167,7 @@ void safe_delay(millis_t ms) { } // Convert signed float to string (6 digit) with -1.234 / _0.000 / +1.234 format - char* ftostr43sign(const float& x, char plus/*=' '*/) { + char* ftostr43sign(const float &x, char plus/*=' '*/) { long xx = x * 1000; conv[1] = xx ? MINUSOR(xx, plus) : ' '; conv[2] = DIGIMOD(xx, 1000); @@ -179,7 +179,7 @@ void safe_delay(millis_t ms) { } // Convert unsigned float to rj string with 12345 format - char* ftostr5rj(const float& x) { + char* ftostr5rj(const float &x) { const long xx = x < 0 ? -x : x; conv[2] = RJDIGIT(xx, 10000); conv[3] = RJDIGIT(xx, 1000); @@ -190,7 +190,7 @@ void safe_delay(millis_t ms) { } // Convert signed float to string with +1234.5 format - char* ftostr51sign(const float& x) { + char* ftostr51sign(const float &x) { long xx = x * 10; conv[0] = MINUSOR(xx, '+'); conv[1] = DIGIMOD(xx, 10000); @@ -203,7 +203,7 @@ void safe_delay(millis_t ms) { } // Convert signed float to string with +123.45 format - char* ftostr52sign(const float& x) { + char* ftostr52sign(const float &x) { long xx = x * 100; conv[0] = MINUSOR(xx, '+'); conv[1] = DIGIMOD(xx, 10000); @@ -216,7 +216,7 @@ void safe_delay(millis_t ms) { } // Convert unsigned float to string with 1234.56 format omitting trailing zeros - char* ftostr62rj(const float& x) { + char* ftostr62rj(const float &x) { const long xx = (x < 0 ? -x : x) * 100; conv[0] = RJDIGIT(xx, 100000); conv[1] = RJDIGIT(xx, 10000); @@ -229,7 +229,7 @@ void safe_delay(millis_t ms) { } // Convert signed float to space-padded string with -_23.4_ format - char* ftostr52sp(const float& x) { + char* ftostr52sp(const float &x) { long xx = x * 100; uint8_t dig; conv[1] = MINUSOR(xx, RJDIGIT(xx, 10000)); diff --git a/Marlin/utility.h b/Marlin/utility.h index f14b272fb..779b788c7 100644 --- a/Marlin/utility.h +++ b/Marlin/utility.h @@ -32,53 +32,53 @@ void safe_delay(millis_t ms); #if ENABLED(ULTRA_LCD) // Convert unsigned int to string with 12 format - char* itostr2(const uint8_t& x); + char* itostr2(const uint8_t &x); // Convert signed int to rj string with 123 or -12 format - char* itostr3(const int& x); + char* itostr3(const int &x); // Convert unsigned int to lj string with 123 format - char* itostr3left(const int& xx); + char* itostr3left(const int &xx); // Convert signed int to rj string with _123, -123, _-12, or __-1 format - char *itostr4sign(const int& x); + char *itostr4sign(const int &x); // Convert unsigned float to string with 1.23 format - char* ftostr12ns(const float& x); + char* ftostr12ns(const float &x); // Convert signed float to fixed-length string with 023.45 / -23.45 format - char *ftostr32(const float& x); + char *ftostr32(const float &x); // Convert float to fixed-length string with +123.4 / -123.4 format - char* ftostr41sign(const float& x); + char* ftostr41sign(const float &x); // Convert signed float to string (6 digit) with -1.234 / _0.000 / +1.234 format - char* ftostr43sign(const float& x, char plus=' '); + char* ftostr43sign(const float &x, char plus=' '); // Convert unsigned float to rj string with 12345 format - char* ftostr5rj(const float& x); + char* ftostr5rj(const float &x); // Convert signed float to string with +1234.5 format - char* ftostr51sign(const float& x); + char* ftostr51sign(const float &x); // Convert signed float to space-padded string with -_23.4_ format - char* ftostr52sp(const float& x); + char* ftostr52sp(const float &x); // Convert signed float to string with +123.45 format - char* ftostr52sign(const float& x); + char* ftostr52sign(const float &x); // Convert unsigned float to string with 1234.56 format omitting trailing zeros - char* ftostr62rj(const float& x); + char* ftostr62rj(const float &x); // Convert float to rj string with 123 or -12 format - FORCE_INLINE char *ftostr3(const float& x) { return itostr3((int)x); } + FORCE_INLINE char *ftostr3(const float &x) { return itostr3((int)x); } #if ENABLED(LCD_DECIMAL_SMALL_XY) // Convert float to rj string with 1234, _123, 12.3, _1.2, -123, _-12, or -1.2 format - char *ftostr4sign(const float& fx); + char *ftostr4sign(const float &fx); #else // Convert float to rj string with 1234, _123, -123, __12, _-12, ___1, or __-1 format - FORCE_INLINE char *ftostr4sign(const float& x) { return itostr4sign((int)x); } + FORCE_INLINE char *ftostr4sign(const float &x) { return itostr4sign((int)x); } #endif #endif // ULTRA_LCD diff --git a/Marlin/vector_3.h b/Marlin/vector_3.h index 23ef745a1..19f6e3a3a 100644 --- a/Marlin/vector_3.h +++ b/Marlin/vector_3.h @@ -77,7 +77,7 @@ struct matrix_3x3 { }; -void apply_rotation_xyz(matrix_3x3 rotationMatrix, float& x, float& y, float& z); +void apply_rotation_xyz(matrix_3x3 rotationMatrix, float &x, float &y, float &z); #endif // HAS_ABL #endif // VECTOR_3_H From 0cbe448edff3420210d029ca001fb331f69e6034 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 28 May 2017 12:13:27 -0500 Subject: [PATCH 165/189] Split up Control > Motion submenu --- Marlin/language_an.h | 3 + Marlin/language_bg.h | 2 + Marlin/language_ca.h | 2 + Marlin/language_cn.h | 2 + Marlin/language_cz.h | 2 + Marlin/language_da.h | 2 + Marlin/language_de.h | 2 + Marlin/language_el-gr.h | 3 + Marlin/language_el.h | 3 + Marlin/language_en.h | 12 ++++ Marlin/language_es.h | 3 + Marlin/language_eu.h | 3 + Marlin/language_fi.h | 3 + Marlin/language_fr.h | 2 + Marlin/language_gl.h | 2 + Marlin/language_hr.h | 2 + Marlin/language_it.h | 2 + Marlin/language_kana.h | 2 + Marlin/language_kana_utf8.h | 11 +--- Marlin/language_nl.h | 2 + Marlin/language_pl.h | 6 ++ Marlin/language_pt-br.h | 2 + Marlin/language_pt-br_utf8.h | 2 + Marlin/language_pt.h | 2 + Marlin/language_pt_utf8.h | 2 + Marlin/language_ru.h | 2 + Marlin/language_tr.h | 2 + Marlin/language_uk.h | 2 + Marlin/language_zh_CN.h | 2 + Marlin/language_zh_TW.h | 2 + Marlin/ultralcd.cpp | 123 +++++++++++++++++++++++++---------- 31 files changed, 167 insertions(+), 45 deletions(-) diff --git a/Marlin/language_an.h b/Marlin/language_an.h index f8cecfbc3..af0981c44 100644 --- a/Marlin/language_an.h +++ b/Marlin/language_an.h @@ -94,6 +94,7 @@ #define MSG_PID_C _UxGT("PID-C") #define MSG_SELECT _UxGT("Trigar") #define MSG_ACC _UxGT("Aceleracion") +#define MSG_JERK _UxGT("Jerk") #define MSG_VX_JERK _UxGT("Vx-jerk") #define MSG_VY_JERK _UxGT("Vy-jerk") #define MSG_VZ_JERK _UxGT("Vz-jerk") @@ -101,9 +102,11 @@ #define MSG_VMAX _UxGT("Vmax") #define MSG_VMIN _UxGT("Vmin") #define MSG_VTRAV_MIN _UxGT("Vel. viache min") +#define MSG_ACCELERATION MSG_ACC #define MSG_AMAX _UxGT("Acel. max") #define MSG_A_RETRACT _UxGT("Acel. retrac.") #define MSG_A_TRAVEL _UxGT("Acel. Viaje") +#define MSG_STEPS_PER_MM _UxGT("Trangos/mm") #define MSG_XSTEPS _UxGT("X trangos/mm") #define MSG_YSTEPS _UxGT("Y trangos/mm") #define MSG_ZSTEPS _UxGT("Z trangos/mm") diff --git a/Marlin/language_bg.h b/Marlin/language_bg.h index 6b58a96e5..34d812eda 100644 --- a/Marlin/language_bg.h +++ b/Marlin/language_bg.h @@ -95,6 +95,7 @@ #define MSG_PID_C _UxGT("PID-C") #define MSG_SELECT _UxGT("Select") #define MSG_ACC _UxGT("Acc") +#define MSG_JERK _UxGT("Jerk") #define MSG_VX_JERK _UxGT("Vx-jerk") #define MSG_VY_JERK _UxGT("Vy-jerk") #define MSG_VZ_JERK _UxGT("Vz-jerk") @@ -105,6 +106,7 @@ #define MSG_AMAX _UxGT("Amax ") #define MSG_A_RETRACT _UxGT("A-откат") #define MSG_A_TRAVEL _UxGT("A-travel") +#define MSG_STEPS_PER_MM _UxGT("Стъпки/mm") #define MSG_XSTEPS _UxGT("X стъпки/mm") #define MSG_YSTEPS _UxGT("Y стъпки/mm") #define MSG_ZSTEPS _UxGT("Z стъпки/mm") diff --git a/Marlin/language_ca.h b/Marlin/language_ca.h index 7ed1de93f..4a713c63e 100644 --- a/Marlin/language_ca.h +++ b/Marlin/language_ca.h @@ -99,6 +99,7 @@ #define MSG_PID_C _UxGT("PID-C") #define MSG_SELECT _UxGT("Select") #define MSG_ACC _UxGT("Accel") +#define MSG_JERK _UxGT("Jerk") #define MSG_VX_JERK _UxGT("Vx-jerk") #define MSG_VY_JERK _UxGT("Vy-jerk") #define MSG_VZ_JERK _UxGT("Vz-jerk") @@ -109,6 +110,7 @@ #define MSG_AMAX _UxGT("Accel. max ") #define MSG_A_RETRACT _UxGT("Accel. retracc") #define MSG_A_TRAVEL _UxGT("Accel. Viatge") +#define MSG_STEPS_PER_MM _UxGT("Passos/mm") #define MSG_XSTEPS _UxGT("Xpassos/mm") #define MSG_YSTEPS _UxGT("Ypassos/mm") #define MSG_ZSTEPS _UxGT("Zpassos/mm") diff --git a/Marlin/language_cn.h b/Marlin/language_cn.h index 228044568..5b471a672 100644 --- a/Marlin/language_cn.h +++ b/Marlin/language_cn.h @@ -87,6 +87,7 @@ #define MSG_PID_D "PID-D" #define MSG_PID_C "PID-C" #define MSG_ACC "Accel" +#define MSG_JERK "Jerk" #define MSG_VX_JERK "Vx-jerk" #define MSG_VY_JERK "Vy-jerk" #define MSG_VZ_JERK "Vz-jerk" @@ -97,6 +98,7 @@ #define MSG_AMAX "Amax " #define MSG_A_RETRACT "A-retract" #define MSG_A_TRAVEL "A-travel" +#define MSG_STEPS_PER_MM "Steps/mm" #define MSG_XSTEPS "Xsteps/mm" #define MSG_YSTEPS "Ysteps/mm" #define MSG_ZSTEPS "Zsteps/mm" diff --git a/Marlin/language_cz.h b/Marlin/language_cz.h index 2372f68fb..25cad14b1 100644 --- a/Marlin/language_cz.h +++ b/Marlin/language_cz.h @@ -105,6 +105,7 @@ #define MSG_PID_C _UxGT("PID-C") #define MSG_SELECT _UxGT("Vybrat") #define MSG_ACC _UxGT("Zrychl") +#define MSG_JERK _UxGT("Jerk") #define MSG_VX_JERK _UxGT("Vx-jerk") #define MSG_VY_JERK _UxGT("Vy-jerk") #define MSG_VZ_JERK _UxGT("Vz-jerk") @@ -115,6 +116,7 @@ #define MSG_AMAX _UxGT("Amax ") #define MSG_A_RETRACT _UxGT("A-retrakt") #define MSG_A_TRAVEL _UxGT("A-prejezd") +#define MSG_STEPS_PER_MM _UxGT("Kroku/mm") #define MSG_XSTEPS _UxGT("Xkroku/mm") #define MSG_YSTEPS _UxGT("Ykroku/mm") #define MSG_ZSTEPS _UxGT("Zkroku/mm") diff --git a/Marlin/language_da.h b/Marlin/language_da.h index 69d196529..93fdfbd27 100644 --- a/Marlin/language_da.h +++ b/Marlin/language_da.h @@ -96,6 +96,7 @@ #define MSG_PID_C _UxGT("PID-C") #define MSG_SELECT _UxGT("Vælg") #define MSG_ACC _UxGT("Accel") +#define MSG_JERK _UxGT("Jerk") #define MSG_VX_JERK _UxGT("Vx-jerk") #define MSG_VY_JERK _UxGT("Vy-jerk") #define MSG_VZ_JERK _UxGT("Vz-jerk") @@ -106,6 +107,7 @@ #define MSG_AMAX _UxGT("Amax ") #define MSG_A_RETRACT _UxGT("A-retract") #define MSG_A_TRAVEL _UxGT("A-rejse") +#define MSG_STEPS_PER_MM _UxGT("Steps/mm") #define MSG_XSTEPS _UxGT("Xsteps/mm") #define MSG_YSTEPS _UxGT("Ysteps/mm") #define MSG_ZSTEPS _UxGT("Zsteps/mm") diff --git a/Marlin/language_de.h b/Marlin/language_de.h index 59b337027..01d8fdea4 100644 --- a/Marlin/language_de.h +++ b/Marlin/language_de.h @@ -102,6 +102,7 @@ #define MSG_PID_C _UxGT("PID C") #define MSG_SELECT _UxGT("Auswählen") #define MSG_ACC _UxGT("A") +#define MSG_JERK _UxGT("Jerk") #define MSG_VX_JERK _UxGT("V X Jerk") #define MSG_VY_JERK _UxGT("V Y Jerk") #define MSG_VZ_JERK _UxGT("V Z Jerk") @@ -112,6 +113,7 @@ #define MSG_AMAX _UxGT("A max ") // space by purpose #define MSG_A_RETRACT _UxGT("A Retract") #define MSG_A_TRAVEL _UxGT("A Leerfahrt") +#define MSG_STEPS_PER_MM _UxGT("Steps/mm") #define MSG_XSTEPS _UxGT("X Steps/mm") #define MSG_YSTEPS _UxGT("Y Steps/mm") #define MSG_ZSTEPS _UxGT("Z Steps/mm") diff --git a/Marlin/language_el-gr.h b/Marlin/language_el-gr.h index e26405a9d..3e55dd666 100644 --- a/Marlin/language_el-gr.h +++ b/Marlin/language_el-gr.h @@ -94,6 +94,7 @@ #define MSG_PID_D _UxGT("PID-D") #define MSG_PID_C _UxGT("PID-C") #define MSG_ACC _UxGT("Επιτάχυνση") +#define MSG_JERK _UxGT("Vαντίδραση") #define MSG_VX_JERK _UxGT("Vαντίδραση x") #define MSG_VY_JERK _UxGT("Vαντίδραση y") #define MSG_VZ_JERK _UxGT("Vαντίδραση z") @@ -101,9 +102,11 @@ #define MSG_VMAX _UxGT("Vμεγ ") #define MSG_VMIN _UxGT("Vελαχ") #define MSG_VTRAV_MIN _UxGT("Vελάχ. μετατόπιση") +#define MSG_ACCELERATION MSG_ACC #define MSG_AMAX _UxGT("Aμεγ ") #define MSG_A_RETRACT _UxGT("Α-ανάσυρση") #define MSG_A_TRAVEL _UxGT("Α-μετατόπιση") +#define MSG_STEPS_PER_MM _UxGT("Bήματα ανά μμ") #define MSG_XSTEPS _UxGT("Bήματα X ανά μμ") #define MSG_YSTEPS _UxGT("Bήματα Υ ανά μμ") #define MSG_ZSTEPS _UxGT("Bήματα Ζ ανά μμ") diff --git a/Marlin/language_el.h b/Marlin/language_el.h index ab915f14c..420363017 100644 --- a/Marlin/language_el.h +++ b/Marlin/language_el.h @@ -94,6 +94,7 @@ #define MSG_PID_D _UxGT("PID-D") #define MSG_PID_C _UxGT("PID-C") #define MSG_ACC _UxGT("Επιτάχυνση") +#define MSG_JERK _UxGT("Jerk") #define MSG_VX_JERK _UxGT("Vαντίδραση x") #define MSG_VY_JERK _UxGT("Vαντίδραση y") #define MSG_VZ_JERK _UxGT("Vαντίδραση z") @@ -101,9 +102,11 @@ #define MSG_VMAX _UxGT("V Μέγιστο") #define MSG_VMIN _UxGT("V Ελάχιστο") #define MSG_VTRAV_MIN _UxGT("Vελάχ. μετατόπιση") +#define MSG_ACCELERATION MSG_ACC #define MSG_AMAX _UxGT("Aμεγ ") #define MSG_A_RETRACT _UxGT("Α-ανάσυρση") #define MSG_A_TRAVEL _UxGT("Α-μετατόπιση") +#define MSG_STEPS_PER_MM _UxGT("Bήματα ανά μμ") #define MSG_XSTEPS _UxGT("Bήματα X ανά μμ") #define MSG_YSTEPS _UxGT("Bήματα Υ ανά μμ") #define MSG_ZSTEPS _UxGT("Bήματα Ζ ανά μμ") diff --git a/Marlin/language_en.h b/Marlin/language_en.h index d274ab84e..9099b0497 100644 --- a/Marlin/language_en.h +++ b/Marlin/language_en.h @@ -376,6 +376,9 @@ #ifndef MSG_ACC #define MSG_ACC _UxGT("Accel") #endif +#ifndef MSG_JERK + #define MSG_JERK _UxGT("Jerk") +#endif #ifndef MSG_VX_JERK #define MSG_VX_JERK _UxGT("Vx-jerk") #endif @@ -388,6 +391,9 @@ #ifndef MSG_VE_JERK #define MSG_VE_JERK _UxGT("Ve-jerk") #endif +#ifndef MSG_FEEDRATE + #define MSG_FEEDRATE _UxGT("Feedrate") +#endif #ifndef MSG_VMAX #define MSG_VMAX _UxGT("Vmax ") #endif @@ -397,6 +403,9 @@ #ifndef MSG_VTRAV_MIN #define MSG_VTRAV_MIN _UxGT("VTrav min") #endif +#ifndef MSG_ACCELERATION + #define MSG_ACCELERATION _UxGT("Acceleration") +#endif #ifndef MSG_AMAX #define MSG_AMAX _UxGT("Amax ") #endif @@ -406,6 +415,9 @@ #ifndef MSG_A_TRAVEL #define MSG_A_TRAVEL _UxGT("A-travel") #endif +#ifndef MSG_STEPS_PER_MM + #define MSG_STEPS_PER_MM _UxGT("Steps/mm") +#endif #ifndef MSG_XSTEPS #define MSG_XSTEPS _UxGT("Xsteps/mm") #endif diff --git a/Marlin/language_es.h b/Marlin/language_es.h index 035ffd2b5..97decb406 100644 --- a/Marlin/language_es.h +++ b/Marlin/language_es.h @@ -101,6 +101,7 @@ #define MSG_PID_C _UxGT("PID-C") #define MSG_SELECT _UxGT("Seleccionar") #define MSG_ACC _UxGT("Aceleracion") +#define MSG_JERK _UxGT("Jerk") #define MSG_VX_JERK _UxGT("Vx-jerk") #define MSG_VY_JERK _UxGT("Vy-jerk") #define MSG_VZ_JERK _UxGT("Vz-jerk") @@ -108,9 +109,11 @@ #define MSG_VMAX _UxGT("Vmax") #define MSG_VMIN _UxGT("Vmin") #define MSG_VTRAV_MIN _UxGT("Vel. viaje min") +#define MSG_ACCELERATION MSG_ACC #define MSG_AMAX _UxGT("Acel. max") #define MSG_A_RETRACT _UxGT("Acel. retrac.") #define MSG_A_TRAVEL _UxGT("Acel. Viaje") +#define MSG_STEPS_PER_MM _UxGT("Pasos/mm") #define MSG_XSTEPS _UxGT("X pasos/mm") #define MSG_YSTEPS _UxGT("Y pasos/mm") #define MSG_ZSTEPS _UxGT("Z pasos/mm") diff --git a/Marlin/language_eu.h b/Marlin/language_eu.h index dc6d51338..fbf6464d2 100644 --- a/Marlin/language_eu.h +++ b/Marlin/language_eu.h @@ -101,6 +101,7 @@ #define MSG_PID_C _UxGT("PID-C") #define MSG_SELECT _UxGT("Aukeratu") #define MSG_ACC _UxGT("Azelerazioa") +#define MSG_JERK _UxGT("Astindua") #define MSG_VX_JERK _UxGT("Vx-astindua") #define MSG_VY_JERK _UxGT("Vy-astindua") #define MSG_VZ_JERK _UxGT("Vz-astindua") @@ -108,9 +109,11 @@ #define MSG_VMAX _UxGT("Vmax ") #define MSG_VMIN _UxGT("Vmin") #define MSG_VTRAV_MIN _UxGT("VBidaia min") +#define MSG_ACCELERATION MSG_ACC #define MSG_AMAX _UxGT("Amax ") #define MSG_A_RETRACT _UxGT("A-retrakt") #define MSG_A_TRAVEL _UxGT("A-bidaia") +#define MSG_STEPS_PER_MM _UxGT("Pausoak/mm") #define MSG_XSTEPS _UxGT("X pausoak/mm") #define MSG_YSTEPS _UxGT("Y pausoak/mm") #define MSG_ZSTEPS _UxGT("Z pausoak/mm") diff --git a/Marlin/language_fi.h b/Marlin/language_fi.h index ad19a9b9f..cd78d80e7 100644 --- a/Marlin/language_fi.h +++ b/Marlin/language_fi.h @@ -87,6 +87,7 @@ #define MSG_PID_D _UxGT("PID-D") #define MSG_PID_C _UxGT("PID-C") #define MSG_ACC _UxGT("Kiihtyv") +#define MSG_JERK _UxGT("Jerk") #define MSG_VX_JERK _UxGT("Vx-jerk") #define MSG_VY_JERK _UxGT("Vy-jerk") #define MSG_VZ_JERK _UxGT("Vz-jerk") @@ -94,8 +95,10 @@ #define MSG_VMAX _UxGT("Vmax ") #define MSG_VMIN _UxGT("Vmin") #define MSG_VTRAV_MIN _UxGT("VLiike min") +#define MSG_ACCELERATION MSG_ACC #define MSG_AMAX _UxGT("Amax ") #define MSG_A_RETRACT _UxGT("A-peruuta") +#define MSG_STEPS_PER_MM _UxGT("Steps/mm") #define MSG_XSTEPS _UxGT("Xsteps/mm") #define MSG_YSTEPS _UxGT("Ysteps/mm") #define MSG_ZSTEPS _UxGT("Zsteps/mm") diff --git a/Marlin/language_fr.h b/Marlin/language_fr.h index c541dc9e3..84b0dd714 100644 --- a/Marlin/language_fr.h +++ b/Marlin/language_fr.h @@ -102,6 +102,7 @@ #define MSG_PID_C _UxGT("PID-C") #define MSG_SELECT _UxGT("Sélectionner") #define MSG_ACC _UxGT("Accélération") +#define MSG_JERK _UxGT("Jerk") #define MSG_VX_JERK _UxGT("Vx-jerk") #define MSG_VY_JERK _UxGT("Vy-jerk") #define MSG_VZ_JERK _UxGT("Vz-jerk") @@ -112,6 +113,7 @@ #define MSG_AMAX _UxGT("Amax ") #define MSG_A_RETRACT _UxGT("A-retract") #define MSG_A_TRAVEL _UxGT("A-Dépl.") +#define MSG_STEPS_PER_MM _UxGT("Pas/mm") #define MSG_XSTEPS _UxGT("Xpas/mm") #define MSG_YSTEPS _UxGT("Ypas/mm") #define MSG_ZSTEPS _UxGT("Zpas/mm") diff --git a/Marlin/language_gl.h b/Marlin/language_gl.h index 67ad89ffb..d82da020a 100644 --- a/Marlin/language_gl.h +++ b/Marlin/language_gl.h @@ -95,6 +95,7 @@ #define MSG_PID_C _UxGT("PID-C") #define MSG_SELECT _UxGT("Escolla") #define MSG_ACC _UxGT("Acel") +#define MSG_JERK _UxGT("Jerk") #define MSG_VX_JERK _UxGT("Vx-jerk") #define MSG_VY_JERK _UxGT("Vy-jerk") #define MSG_VZ_JERK _UxGT("Vz-jerk") @@ -105,6 +106,7 @@ #define MSG_AMAX _UxGT("Amax ") #define MSG_A_RETRACT _UxGT("A-retract") #define MSG_A_TRAVEL _UxGT("A-travel") +#define MSG_STEPS_PER_MM _UxGT("Pasos/mm") #define MSG_XSTEPS _UxGT("Xpasos/mm") #define MSG_YSTEPS _UxGT("Ypasos/mm") #define MSG_ZSTEPS _UxGT("Zpasos/mm") diff --git a/Marlin/language_hr.h b/Marlin/language_hr.h index 7ec0b0dbb..61308142d 100644 --- a/Marlin/language_hr.h +++ b/Marlin/language_hr.h @@ -94,6 +94,7 @@ #define MSG_PID_C _UxGT("PID-C") #define MSG_SELECT _UxGT("Odaberi") #define MSG_ACC _UxGT("Accel") +#define MSG_JERK _UxGT("Jerk") #define MSG_VX_JERK _UxGT("Vx-jerk") #define MSG_VY_JERK _UxGT("Vy-jerk") #define MSG_VZ_JERK _UxGT("Vz-jerk") @@ -104,6 +105,7 @@ #define MSG_AMAX _UxGT("Amax ") #define MSG_A_RETRACT _UxGT("A-retract") #define MSG_A_TRAVEL _UxGT("A-travel") +#define MSG_STEPS_PER_MM _UxGT("Steps/mm") #define MSG_XSTEPS _UxGT("Xsteps/mm") #define MSG_YSTEPS _UxGT("Ysteps/mm") #define MSG_ZSTEPS _UxGT("Zsteps/mm") diff --git a/Marlin/language_it.h b/Marlin/language_it.h index b1c5b6623..415ae507e 100644 --- a/Marlin/language_it.h +++ b/Marlin/language_it.h @@ -109,6 +109,7 @@ #define MSG_PID_C _UxGT("PID-C") #define MSG_SELECT _UxGT("Seleziona") #define MSG_ACC _UxGT("Accel") +#define MSG_JERK _UxGT("Jerk") #define MSG_VX_JERK _UxGT("Vx-jerk") #define MSG_VY_JERK _UxGT("Vy-jerk") #define MSG_VZ_JERK _UxGT("Vz-jerk") @@ -119,6 +120,7 @@ #define MSG_AMAX _UxGT("Amax ") #define MSG_A_RETRACT _UxGT("A-retract") #define MSG_A_TRAVEL _UxGT("A-Spostamento") +#define MSG_STEPS_PER_MM _UxGT("Passi/mm") #define MSG_XSTEPS _UxGT("Xpassi/mm") #define MSG_YSTEPS _UxGT("Ypassi/mm") #define MSG_ZSTEPS _UxGT("Zpassi/mm") diff --git a/Marlin/language_kana.h b/Marlin/language_kana.h index 40f60491a..077a277a7 100644 --- a/Marlin/language_kana.h +++ b/Marlin/language_kana.h @@ -129,6 +129,7 @@ #define MSG_A_RETRACT "\xcb\xb7\xba\xd0\xb6\xbf\xb8\xc4\xde" // "ヒキコミカソクド" ("A-retract") #define MSG_A_TRAVEL "\xb2\xc4\xde\xb3\xb6\xbf\xb8\xc4\xde" // "イドウカソクド" ("A-travel") #if LCD_WIDTH >= 20 + #define MSG_STEPS_PER_MM "Steps/mm" #define MSG_XSTEPS "Xsteps/mm" #define MSG_YSTEPS "Ysteps/mm" #define MSG_ZSTEPS "Zsteps/mm" @@ -139,6 +140,7 @@ #define MSG_E4STEPS "E4steps/mm" #define MSG_E5STEPS "E5steps/mm" #else + #define MSG_STEPS_PER_MM "Steps" #define MSG_XSTEPS "Xsteps" #define MSG_YSTEPS "Ysteps" #define MSG_ZSTEPS "Zsteps" diff --git a/Marlin/language_kana_utf8.h b/Marlin/language_kana_utf8.h index 470f51185..6ca860586 100644 --- a/Marlin/language_kana_utf8.h +++ b/Marlin/language_kana_utf8.h @@ -104,6 +104,7 @@ #define MSG_PID_C _UxGT("PID-C") #define MSG_SELECT _UxGT("センタク") // "Select" #define MSG_ACC _UxGT("カソクド mm/s2") // "Accel" +#define MSG_JERK _UxGT("ヤクド mm/s") // "Jerk" #define MSG_VX_JERK _UxGT("Xジク ヤクド mm/s") // "Vx-jerk" #define MSG_VY_JERK _UxGT("Yジク ヤクド mm/s") // "Vy-jerk" #define MSG_VZ_JERK _UxGT("Zジク ヤクド mm/s") // "Vz-jerk" @@ -111,18 +112,10 @@ #define MSG_VMAX _UxGT("サイダイオクリソクド ") // "Vmax " #define MSG_VMIN _UxGT("サイショウオクリソクド") // "Vmin" #define MSG_VTRAV_MIN _UxGT("サイショウイドウソクド") // "VTrav min" +#define MSG_ACCELERATION MSG_ACC #define MSG_AMAX _UxGT("サイダイカソクド ") // "Amax " #define MSG_A_RETRACT _UxGT("ヒキコミカソクド") // "A-retract" #define MSG_A_TRAVEL _UxGT("イドウカソクド") // "A-travel" -#define MSG_XSTEPS _UxGT("Xsteps/mm") -#define MSG_YSTEPS _UxGT("Ysteps/mm") -#define MSG_ZSTEPS _UxGT("Zsteps/mm") -#define MSG_ESTEPS _UxGT("Esteps/mm") -#define MSG_E1STEPS _UxGT("E1steps/mm") -#define MSG_E2STEPS _UxGT("E2steps/mm") -#define MSG_E3STEPS _UxGT("E3steps/mm") -#define MSG_E4STEPS _UxGT("E4steps/mm") -#define MSG_E5STEPS _UxGT("E5steps/mm") #define MSG_TEMPERATURE _UxGT("オンド") // "Temperature" #define MSG_MOTION _UxGT("ウゴキセッテイ") // "Motion" #define MSG_FILAMENT _UxGT("フィラメント") // "Filament" diff --git a/Marlin/language_nl.h b/Marlin/language_nl.h index 7693b511c..b041a3535 100644 --- a/Marlin/language_nl.h +++ b/Marlin/language_nl.h @@ -101,6 +101,7 @@ #define MSG_PID_C _UxGT("PID-C") #define MSG_SELECT _UxGT("Selecteer") #define MSG_ACC _UxGT("Versn") +#define MSG_JERK _UxGT("Jerk") #define MSG_VX_JERK _UxGT("Vx-jerk") #define MSG_VY_JERK _UxGT("Vy-jerk") #define MSG_VZ_JERK _UxGT("Vz-jerk") @@ -111,6 +112,7 @@ #define MSG_AMAX _UxGT("Amax ") #define MSG_A_RETRACT _UxGT("A-retract") #define MSG_A_TRAVEL _UxGT("A-travel") +#define MSG_STEPS_PER_MM _UxGT("Steps/mm") #define MSG_XSTEPS _UxGT("Xsteps/mm") #define MSG_YSTEPS _UxGT("Ysteps/mm") #define MSG_ZSTEPS _UxGT("Zsteps/mm") diff --git a/Marlin/language_pl.h b/Marlin/language_pl.h index 280cd5b2b..204d3123b 100644 --- a/Marlin/language_pl.h +++ b/Marlin/language_pl.h @@ -97,6 +97,7 @@ #define MSG_PID_C _UxGT("PID-C") #define MSG_SELECT _UxGT("Select") #define MSG_ACC _UxGT("Przyśpieszenie") +#define MSG_JERK _UxGT("Zryw") #define MSG_VX_JERK _UxGT("Zryw Vx") #define MSG_VY_JERK _UxGT("Zryw Vy") #define MSG_VZ_JERK _UxGT("Zryw Vz") @@ -104,9 +105,11 @@ #define MSG_VMAX _UxGT("Vmax ") #define MSG_VMIN _UxGT("Vmin") #define MSG_VTRAV_MIN _UxGT("Vskok min") +#define MSG_ACCELERATION MSG_ACC #define MSG_AMAX _UxGT("Amax") #define MSG_A_RETRACT _UxGT("A-wycofanie") #define MSG_A_TRAVEL _UxGT("A-przesuń.") +#define MSG_STEPS_PER_MM _UxGT("kroki/mm") #define MSG_XSTEPS _UxGT("krokiX/mm") #define MSG_YSTEPS _UxGT("krokiY/mm") #define MSG_ZSTEPS _UxGT("krokiZ/mm") @@ -312,6 +315,7 @@ #define MSG_PID_C _UxGT("PID-C") #define MSG_SELECT _UxGT("Select") #define MSG_ACC _UxGT("Przyspieszenie") +#define MSG_JERK _UxGT("Zryw") #define MSG_VX_JERK _UxGT("Zryw Vx") #define MSG_VY_JERK _UxGT("Zryw Vy") #define MSG_VZ_JERK _UxGT("Zryw Vz") @@ -319,9 +323,11 @@ #define MSG_VMAX _UxGT("Vmax ") #define MSG_VMIN _UxGT("Vmin") #define MSG_VTRAV_MIN _UxGT("Vskok min") +#define MSG_ACCELERATION MSG_ACC #define MSG_AMAX _UxGT("Amax") #define MSG_A_RETRACT _UxGT("A-wycofanie") #define MSG_A_TRAVEL _UxGT("A-przesun.") +#define MSG_STEPS_PER_MM _UxGT("kroki/mm") #define MSG_XSTEPS _UxGT("krokiX/mm") #define MSG_YSTEPS _UxGT("krokiY/mm") #define MSG_ZSTEPS _UxGT("krokiZ/mm") diff --git a/Marlin/language_pt-br.h b/Marlin/language_pt-br.h index f71bb92e1..05c91e0b9 100644 --- a/Marlin/language_pt-br.h +++ b/Marlin/language_pt-br.h @@ -87,6 +87,7 @@ #define MSG_PID_D "PID-D" #define MSG_PID_C "PID-C" #define MSG_ACC "Acc" +#define MSG_JERK "Jogo" #define MSG_VX_JERK "jogo VX" #define MSG_VY_JERK "jogo VY" #define MSG_VZ_JERK "jogo VZ" @@ -97,6 +98,7 @@ #define MSG_AMAX "Amax " #define MSG_A_RETRACT "Retrair A" #define MSG_A_TRAVEL "A-movimento" +#define MSG_STEPS_PER_MM "Passo/mm" #define MSG_XSTEPS "Passo X/mm" #define MSG_YSTEPS "Passo Y/mm" #define MSG_ZSTEPS "Passo Z/mm" diff --git a/Marlin/language_pt-br_utf8.h b/Marlin/language_pt-br_utf8.h index a2f6deaad..c9040fcdd 100644 --- a/Marlin/language_pt-br_utf8.h +++ b/Marlin/language_pt-br_utf8.h @@ -87,6 +87,7 @@ #define MSG_PID_D _UxGT("PID-D") #define MSG_PID_C _UxGT("PID-C") #define MSG_ACC _UxGT("Acc") +#define MSG_JERK _UxGT("Jogo") #define MSG_VX_JERK _UxGT("jogo VX") #define MSG_VY_JERK _UxGT("jogo VY") #define MSG_VZ_JERK _UxGT("jogo VZ") @@ -97,6 +98,7 @@ #define MSG_AMAX _UxGT("Amax ") #define MSG_A_RETRACT _UxGT("Retrair A") #define MSG_A_TRAVEL _UxGT("A-movimento") +#define MSG_STEPS_PER_MM _UxGT("Passo/mm") #define MSG_XSTEPS _UxGT("Passo X/mm") #define MSG_YSTEPS _UxGT("Passo Y/mm") #define MSG_ZSTEPS _UxGT("Passo Z/mm") diff --git a/Marlin/language_pt.h b/Marlin/language_pt.h index ba17986bf..4b8212432 100644 --- a/Marlin/language_pt.h +++ b/Marlin/language_pt.h @@ -91,6 +91,7 @@ #define MSG_PID_D "PID-D" #define MSG_PID_C "PID-C" #define MSG_ACC "Acc" +#define MSG_JERK _UxGT("Jerk") #define MSG_VX_JERK "Vx-jerk" #define MSG_VY_JERK "Vy-jerk" #define MSG_VZ_JERK "Vz-jerk" @@ -101,6 +102,7 @@ #define MSG_AMAX "Amax " #define MSG_A_RETRACT "A-retraccao" #define MSG_A_TRAVEL "A-movimento" +#define MSG_STEPS_PER_MM "Passo/mm" #define MSG_XSTEPS "X passo/mm" #define MSG_YSTEPS "Y passo/mm" #define MSG_ZSTEPS "Z passo/mm" diff --git a/Marlin/language_pt_utf8.h b/Marlin/language_pt_utf8.h index b62119b43..d9345a579 100644 --- a/Marlin/language_pt_utf8.h +++ b/Marlin/language_pt_utf8.h @@ -91,6 +91,7 @@ #define MSG_PID_D _UxGT("PID-D") #define MSG_PID_C _UxGT("PID-C") #define MSG_ACC _UxGT("Acc") +#define MSG_JERK _UxGT("Jerk") #define MSG_VX_JERK _UxGT("Vx-jerk") #define MSG_VY_JERK _UxGT("Vy-jerk") #define MSG_VZ_JERK _UxGT("Vz-jerk") @@ -101,6 +102,7 @@ #define MSG_AMAX _UxGT("Amax ") #define MSG_A_RETRACT _UxGT("A-retracção") #define MSG_A_TRAVEL _UxGT("A-movimento") +#define MSG_STEPS_PER_MM _UxGT("Passo/mm") #define MSG_XSTEPS _UxGT("X passo/mm") #define MSG_YSTEPS _UxGT("Y passo/mm") #define MSG_ZSTEPS _UxGT("Z passo/mm") diff --git a/Marlin/language_ru.h b/Marlin/language_ru.h index a4644928a..3b2936128 100644 --- a/Marlin/language_ru.h +++ b/Marlin/language_ru.h @@ -91,6 +91,7 @@ #define MSG_PID_D _UxGT("PID-D") #define MSG_PID_C _UxGT("PID-C") #define MSG_ACC _UxGT("Acc") +#define MSG_JERK _UxGT("Рывок") #define MSG_VX_JERK _UxGT("Vx-рывок") #define MSG_VY_JERK _UxGT("Vy-рывок") #define MSG_VZ_JERK _UxGT("Vz-рывок") @@ -101,6 +102,7 @@ #define MSG_AMAX _UxGT("Aмакс") #define MSG_A_RETRACT _UxGT("A-втягивание") #define MSG_A_TRAVEL _UxGT("A-путеш.") +#define MSG_STEPS_PER_MM _UxGT("Шаг/мм") #define MSG_XSTEPS _UxGT("X шаг/мм") #define MSG_YSTEPS _UxGT("Y шаг/мм") #define MSG_ZSTEPS _UxGT("Z шаг/мм") diff --git a/Marlin/language_tr.h b/Marlin/language_tr.h index e6b0af98b..d15fbfb6d 100644 --- a/Marlin/language_tr.h +++ b/Marlin/language_tr.h @@ -106,6 +106,7 @@ #define MSG_PID_C _UxGT("PID-C") // PID-C #define MSG_SELECT _UxGT("Seç") // Seç #define MSG_ACC _UxGT("İvme") // İvme +#define MSG_JERK _UxGT("Jerk") #define MSG_VX_JERK _UxGT("Vx-Jerk") // Vx-Jerk #define MSG_VY_JERK _UxGT("Vy-Jerk") // Vy-Jerk #define MSG_VZ_JERK _UxGT("Vz-jerk") // Vz-Jerk @@ -116,6 +117,7 @@ #define MSG_AMAX _UxGT("Amax ") // Amax #define MSG_A_RETRACT _UxGT("A-retract") // A-retract #define MSG_A_TRAVEL _UxGT("A-travel") // A-travel +#define MSG_STEPS_PER_MM _UxGT("Steps/mm") // Xsteps/mm #define MSG_XSTEPS _UxGT("Xsteps/mm") // Xsteps/mm #define MSG_YSTEPS _UxGT("Ysteps/mm") // Ysteps/mm #define MSG_ZSTEPS _UxGT("Zsteps/mm") // Zsteps/mm diff --git a/Marlin/language_uk.h b/Marlin/language_uk.h index ffc302a64..2773b24c3 100644 --- a/Marlin/language_uk.h +++ b/Marlin/language_uk.h @@ -95,6 +95,7 @@ #define MSG_PID_C _UxGT("PID-C") #define MSG_SELECT _UxGT("Вибрати") #define MSG_ACC _UxGT("Приск.") +#define MSG_JERK _UxGT("Ривок") #define MSG_VX_JERK _UxGT("Vx-ривок") #define MSG_VY_JERK _UxGT("Vy-ривок") #define MSG_VZ_JERK _UxGT("Vz-ривок") @@ -105,6 +106,7 @@ #define MSG_AMAX _UxGT("Aмакс ") #define MSG_A_RETRACT _UxGT("A-втягув.") #define MSG_A_TRAVEL _UxGT("A-руху") +#define MSG_STEPS_PER_MM _UxGT("Кроків/мм") #define MSG_XSTEPS _UxGT("Xкроків/мм") #define MSG_YSTEPS _UxGT("Yкроків/мм") #define MSG_ZSTEPS _UxGT("Zкроків/мм") diff --git a/Marlin/language_zh_CN.h b/Marlin/language_zh_CN.h index 58d845a35..c42ab6a4f 100644 --- a/Marlin/language_zh_CN.h +++ b/Marlin/language_zh_CN.h @@ -92,6 +92,7 @@ #define MSG_PID_C _UxGT("PID-C") //"PID-C" #define MSG_SELECT _UxGT("选择") //"Select" #define MSG_ACC _UxGT("加速度") //"Accel" acceleration +#define MSG_JERK _UxGT("抖动速率") // "Jerk" #define MSG_VX_JERK _UxGT("X轴抖动速率") //"Vx-jerk" #define MSG_VY_JERK _UxGT("Y轴抖动速率") //"Vy-jerk" #define MSG_VZ_JERK _UxGT("Z轴抖动速率") //"Vz-jerk" @@ -102,6 +103,7 @@ #define MSG_AMAX _UxGT("最大打印加速度") //"Amax " max_acceleration_mm_per_s2, acceleration in units/s^2 for print moves #define MSG_A_RETRACT _UxGT("收进加速度") //"A-retract" retract_acceleration, E acceleration in mm/s^2 for retracts #define MSG_A_TRAVEL _UxGT("非打印移动加速度") //"A-travel" travel_acceleration, X, Y, Z acceleration in mm/s^2 for travel (non printing) moves +#define MSG_STEPS_PER_MM _UxGT("轴步数/mm") //"Steps/mm" axis_steps_per_mm, axis steps-per-unit G92 #define MSG_XSTEPS _UxGT("X轴步数/mm") //"Xsteps/mm" axis_steps_per_mm, axis steps-per-unit G92 #define MSG_YSTEPS _UxGT("Y轴步数/mm") //"Ysteps/mm" #define MSG_ZSTEPS _UxGT("Z轴步数/mm") //"Zsteps/mm" diff --git a/Marlin/language_zh_TW.h b/Marlin/language_zh_TW.h index 89924732b..421f4e717 100644 --- a/Marlin/language_zh_TW.h +++ b/Marlin/language_zh_TW.h @@ -92,6 +92,7 @@ #define MSG_PID_C _UxGT("PID-C") //"PID-C" #define MSG_SELECT _UxGT("選擇") //"Select" #define MSG_ACC _UxGT("加速度") //"Accel" acceleration +#define MSG_JERK _UxGT("抖動速率") //"Jerk" #define MSG_VX_JERK _UxGT("X軸抖動速率") //"Vx-jerk" #define MSG_VY_JERK _UxGT("Y軸抖動速率") //"Vy-jerk" #define MSG_VZ_JERK _UxGT("Z軸抖動速率") //"Vz-jerk" @@ -102,6 +103,7 @@ #define MSG_AMAX _UxGT("最大列印加速度") //"Amax " max_acceleration_mm_per_s2, acceleration in units/s^2 for print moves #define MSG_A_RETRACT _UxGT("收進加速度") //"A-retract" retract_acceleration, E acceleration in mm/s^2 for retracts #define MSG_A_TRAVEL _UxGT("非列印移動加速度") //"A-travel" travel_acceleration, X, Y, Z acceleration in mm/s^2 for travel (non printing) moves +#define MSG_STEPS_PER_MM _UxGT("軸步數/mm") //"Steps/mm" axis_steps_per_mm, axis steps-per-unit G92 #define MSG_XSTEPS _UxGT("X軸步數/mm") //"Xsteps/mm" axis_steps_per_mm, axis steps-per-unit G92 #define MSG_YSTEPS _UxGT("Y軸步數/mm") //"Ysteps/mm" #define MSG_ZSTEPS _UxGT("Z軸步數/mm") //"Zsteps/mm" diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 32d47419d..e4b1a7463 100755 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -2746,6 +2746,13 @@ void kill_screen(const char* lcd_msg) { */ void lcd_control_temperature_preheat_material2_settings_menu() { _lcd_control_temperature_preheat_settings_menu(1); } + + /** + * + * "Control" > "Motion" submenu + * + */ + void _reset_acceleration_rates() { planner.reset_acceleration_rates(); } #if ENABLED(DISTINCT_E_FACTORS) void _reset_e_acceleration_rate(const uint8_t e) { if (e == active_extruder) _reset_acceleration_rates(); } @@ -2783,40 +2790,16 @@ void kill_screen(const char* lcd_msg) { #endif // E_STEPPERS > 2 #endif - /** - * - * "Control" > "Motion" submenu - * - */ #if HAS_BED_PROBE && DISABLED(BABYSTEP_ZPROBE_OFFSET) static void lcd_refresh_zprobe_zoffset() { refresh_zprobe_zoffset(); } #endif - void lcd_control_motion_menu() { + // M203 / M205 Feedrates + void lcd_control_motion_feedrate_menu() { START_MENU(); - MENU_BACK(MSG_CONTROL); - #if ENABLED(BABYSTEP_ZPROBE_OFFSET) - MENU_ITEM(submenu, MSG_ZPROBE_ZOFFSET, lcd_babystep_zoffset); - #elif HAS_BED_PROBE - MENU_ITEM_EDIT_CALLBACK(float32, MSG_ZPROBE_ZOFFSET, &zprobe_zoffset, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX, lcd_refresh_zprobe_zoffset); - #endif - // Manual bed leveling, Bed Z: - #if ENABLED(MESH_BED_LEVELING) && ENABLED(LCD_BED_LEVELING) - MENU_ITEM_EDIT(float43, MSG_BED_Z, &mbl.z_offset, -1, 1); - #endif - MENU_ITEM_EDIT(float5, MSG_ACC, &planner.acceleration, 10, 99000); - MENU_ITEM_EDIT(float3, MSG_VX_JERK, &planner.max_jerk[X_AXIS], 1, 990); - MENU_ITEM_EDIT(float3, MSG_VY_JERK, &planner.max_jerk[Y_AXIS], 1, 990); - #if ENABLED(DELTA) - MENU_ITEM_EDIT(float3, MSG_VZ_JERK, &planner.max_jerk[Z_AXIS], 1, 990); - #else - MENU_ITEM_EDIT(float52, MSG_VZ_JERK, &planner.max_jerk[Z_AXIS], 0.1, 990); - #endif - MENU_ITEM_EDIT(float3, MSG_VE_JERK, &planner.max_jerk[E_AXIS], 1, 990); + MENU_BACK(MSG_MOTION); - // - // M203 Settings - // + // M203 Max Feedrate MENU_ITEM_EDIT(float3, MSG_VMAX MSG_X, &planner.max_feedrate_mm_s[X_AXIS], 1, 999); MENU_ITEM_EDIT(float3, MSG_VMAX MSG_Y, &planner.max_feedrate_mm_s[Y_AXIS], 1, 999); MENU_ITEM_EDIT(float3, MSG_VMAX MSG_Z, &planner.max_feedrate_mm_s[Z_AXIS], 1, 999); @@ -2838,12 +2821,30 @@ void kill_screen(const char* lcd_msg) { MENU_ITEM_EDIT(float3, MSG_VMAX MSG_E, &planner.max_feedrate_mm_s[E_AXIS], 1, 999); #endif + // M205 S Min Feedrate MENU_ITEM_EDIT(float3, MSG_VMIN, &planner.min_feedrate_mm_s, 0, 999); + + // M205 T Min Travel Feedrate MENU_ITEM_EDIT(float3, MSG_VTRAV_MIN, &planner.min_travel_feedrate_mm_s, 0, 999); - // - // M201 Settings - // + END_MENU(); + } + + // M201 / M204 Accelerations + void lcd_control_motion_acceleration_menu() { + START_MENU(); + MENU_BACK(MSG_MOTION); + + // M204 P Acceleration + MENU_ITEM_EDIT(float5, MSG_ACC, &planner.acceleration, 10, 99000); + + // M204 R Retract Acceleration + MENU_ITEM_EDIT(float5, MSG_A_RETRACT, &planner.retract_acceleration, 100, 99000); + + // M204 T Travel Acceleration + MENU_ITEM_EDIT(float5, MSG_A_TRAVEL, &planner.travel_acceleration, 100, 99000); + + // M201 settings MENU_ITEM_EDIT_CALLBACK(long5, MSG_AMAX MSG_X, &planner.max_acceleration_mm_per_s2[X_AXIS], 100, 99000, _reset_acceleration_rates); MENU_ITEM_EDIT_CALLBACK(long5, MSG_AMAX MSG_Y, &planner.max_acceleration_mm_per_s2[Y_AXIS], 100, 99000, _reset_acceleration_rates); MENU_ITEM_EDIT_CALLBACK(long5, MSG_AMAX MSG_Z, &planner.max_acceleration_mm_per_s2[Z_AXIS], 10, 99000, _reset_acceleration_rates); @@ -2865,12 +2866,31 @@ void kill_screen(const char* lcd_msg) { MENU_ITEM_EDIT_CALLBACK(long5, MSG_AMAX MSG_E, &planner.max_acceleration_mm_per_s2[E_AXIS], 100, 99000, _reset_acceleration_rates); #endif - MENU_ITEM_EDIT(float5, MSG_A_RETRACT, &planner.retract_acceleration, 100, 99000); - MENU_ITEM_EDIT(float5, MSG_A_TRAVEL, &planner.travel_acceleration, 100, 99000); + END_MENU(); + } + + // M205 Jerk + void lcd_control_motion_jerk_menu() { + START_MENU(); + MENU_BACK(MSG_MOTION); + + MENU_ITEM_EDIT(float3, MSG_VX_JERK, &planner.max_jerk[X_AXIS], 1, 990); + MENU_ITEM_EDIT(float3, MSG_VY_JERK, &planner.max_jerk[Y_AXIS], 1, 990); + #if ENABLED(DELTA) + MENU_ITEM_EDIT(float3, MSG_VZ_JERK, &planner.max_jerk[Z_AXIS], 1, 990); + #else + MENU_ITEM_EDIT(float52, MSG_VZ_JERK, &planner.max_jerk[Z_AXIS], 0.1, 990); + #endif + MENU_ITEM_EDIT(float3, MSG_VE_JERK, &planner.max_jerk[E_AXIS], 1, 990); + + END_MENU(); + } + + // M92 Steps-per-mm + void lcd_control_motion_steps_per_mm_menu() { + START_MENU(); + MENU_BACK(MSG_MOTION); - // - // M92 Settings - // MENU_ITEM_EDIT_CALLBACK(float62, MSG_XSTEPS, &planner.axis_steps_per_mm[X_AXIS], 5, 9999, _planner_refresh_positioning); MENU_ITEM_EDIT_CALLBACK(float62, MSG_YSTEPS, &planner.axis_steps_per_mm[Y_AXIS], 5, 9999, _planner_refresh_positioning); MENU_ITEM_EDIT_CALLBACK(float62, MSG_ZSTEPS, &planner.axis_steps_per_mm[Z_AXIS], 5, 9999, _planner_refresh_positioning); @@ -2892,9 +2912,40 @@ void kill_screen(const char* lcd_msg) { MENU_ITEM_EDIT_CALLBACK(float62, MSG_ESTEPS, &planner.axis_steps_per_mm[E_AXIS], 5, 9999, _planner_refresh_positioning); #endif + END_MENU(); + } + + void lcd_control_motion_menu() { + START_MENU(); + MENU_BACK(MSG_CONTROL); + + #if ENABLED(BABYSTEP_ZPROBE_OFFSET) + MENU_ITEM(submenu, MSG_ZPROBE_ZOFFSET, lcd_babystep_zoffset); + #elif HAS_BED_PROBE + MENU_ITEM_EDIT_CALLBACK(float32, MSG_ZPROBE_ZOFFSET, &zprobe_zoffset, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX, lcd_refresh_zprobe_zoffset); + #endif + + // Manual bed leveling, Bed Z: + #if ENABLED(MESH_BED_LEVELING) && ENABLED(LCD_BED_LEVELING) + MENU_ITEM_EDIT(float43, MSG_BED_Z, &mbl.z_offset, -1, 1); + #endif + + // M203 / M205 Feedrate items + MENU_ITEM(submenu, MSG_FEEDRATE, lcd_control_motion_feedrate_menu); + + // M201 Acceleration items + MENU_ITEM(submenu, MSG_ACCELERATION, lcd_control_motion_acceleration_menu); + + // M205 Max Jerk + MENU_ITEM(submenu, MSG_JERK, lcd_control_motion_jerk_menu); + + // M92 Steps Per mm + MENU_ITEM(submenu, MSG_STEPS_PER_MM, lcd_control_motion_steps_per_mm_menu); + #if ENABLED(ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED) MENU_ITEM_EDIT(bool, MSG_ENDSTOP_ABORT, &stepper.abort_on_endstop_hit); #endif + END_MENU(); } From 01e7e234c601610d208277bf5990c0eb008097b7 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 27 May 2017 19:29:29 -0500 Subject: [PATCH 166/189] Add more options to the Bed Leveling menu --- Marlin/Marlin.h | 4 +- Marlin/Marlin_main.cpp | 140 +++++++++++++++++---------------- Marlin/configuration_store.cpp | 6 +- Marlin/language_an.h | 2 +- Marlin/language_bg.h | 2 +- Marlin/language_ca.h | 2 +- Marlin/language_cn.h | 2 +- Marlin/language_cz.h | 2 +- Marlin/language_da.h | 2 +- Marlin/language_de.h | 2 +- Marlin/language_el-gr.h | 2 +- Marlin/language_el.h | 2 +- Marlin/language_en.h | 7 +- Marlin/language_es.h | 2 +- Marlin/language_eu.h | 2 +- Marlin/language_fi.h | 1 - Marlin/language_fr.h | 2 +- Marlin/language_gl.h | 2 +- Marlin/language_hr.h | 2 +- Marlin/language_it.h | 2 +- Marlin/language_kana.h | 2 +- Marlin/language_kana_utf8.h | 2 +- Marlin/language_nl.h | 2 +- Marlin/language_pl.h | 4 +- Marlin/language_pt-br.h | 1 - Marlin/language_pt-br_utf8.h | 1 - Marlin/language_pt.h | 1 - Marlin/language_pt_utf8.h | 1 - Marlin/language_ru.h | 2 +- Marlin/language_tr.h | 2 +- Marlin/language_uk.h | 2 +- Marlin/language_zh_CN.h | 2 +- Marlin/language_zh_TW.h | 2 +- Marlin/ultralcd.cpp | 79 +++++++++++++------ 34 files changed, 165 insertions(+), 126 deletions(-) diff --git a/Marlin/Marlin.h b/Marlin/Marlin.h index dcc9d0443..c18f5db53 100644 --- a/Marlin/Marlin.h +++ b/Marlin/Marlin.h @@ -310,7 +310,6 @@ extern float soft_endstop_min[XYZ], soft_endstop_max[XYZ]; extern float bilinear_grid_factor[2], z_values[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y]; float bilinear_z_offset(const float logical[XYZ]); - void set_bed_leveling_enabled(bool enable=true); #endif #if ENABLED(AUTO_BED_LEVELING_UBL) @@ -319,6 +318,9 @@ extern float soft_endstop_min[XYZ], soft_endstop_max[XYZ]; #endif #if HAS_LEVELING + bool leveling_is_valid(); + bool leveling_is_active(); + void set_bed_leveling_enabled(const bool enable=true); void reset_bed_level(); #endif diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 75edc0e6f..d14dc93ff 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -815,7 +815,7 @@ static bool drain_injected_commands_P() { * Aborts the current queue, if any. * Note: drain_injected_commands_P() must be called repeatedly to drain the commands afterwards */ -void enqueue_and_echo_commands_P(const char* pgcode) { +void enqueue_and_echo_commands_P(const char * const pgcode) { injected_commands_P = pgcode; drain_injected_commands_P(); // first command executed asap (when possible) } @@ -2300,6 +2300,33 @@ static void clean_up_after_endstop_or_probe_move() { #endif // HAS_BED_PROBE #if HAS_LEVELING + + bool leveling_is_valid() { + return + #if ENABLED(MESH_BED_LEVELING) + mbl.has_mesh() + #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) + !!bilinear_grid_spacing[X_AXIS] + #elif ENABLED(AUTO_BED_LEVELING_UBL) + true + #else // 3POINT, LINEAR + true + #endif + ; + } + + bool leveling_is_active() { + return + #if ENABLED(MESH_BED_LEVELING) + mbl.active() + #elif ENABLED(AUTO_BED_LEVELING_UBL) + ubl.state.active + #else + planner.abl_enabled + #endif + ; + } + /** * Turn bed leveling on or off, fixing the current * position as-needed. @@ -2307,41 +2334,39 @@ static void clean_up_after_endstop_or_probe_move() { * Disable: Current position = physical position * Enable: Current position = "unleveled" physical position */ - void set_bed_leveling_enabled(bool enable/*=true*/) { - #if ENABLED(MESH_BED_LEVELING) + void set_bed_leveling_enabled(const bool enable/*=true*/) { + + #if ENABLED(AUTO_BED_LEVELING_BILINEAR) + const bool can_change = (!enable || leveling_is_valid()); + #else + constexpr bool can_change = true; + #endif - if (enable != mbl.active()) { + if (can_change && enable != leveling_is_active()) { + + #if ENABLED(MESH_BED_LEVELING) if (!enable) planner.apply_leveling(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS]); - mbl.set_active(enable && mbl.has_mesh()); + const bool enabling = enable && leveling_is_valid(); + mbl.set_active(enabling); + if (enabling) planner.unapply_leveling(current_position); - if (enable && mbl.has_mesh()) planner.unapply_leveling(current_position); - } + #elif ENABLED(AUTO_BED_LEVELING_UBL) - #elif ENABLED(AUTO_BED_LEVELING_UBL) + #if PLANNER_LEVELING - #if PLANNER_LEVELING - if (ubl.state.active != enable) { if (!enable) // leveling from on to off planner.apply_leveling(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS]); else planner.unapply_leveling(current_position); - } - #endif - - ubl.state.active = enable; - #else + #endif - #if ENABLED(AUTO_BED_LEVELING_BILINEAR) - const bool can_change = (!enable || (bilinear_grid_spacing[0] && bilinear_grid_spacing[1])); - #else - constexpr bool can_change = true; - #endif + ubl.state.active = enable; - if (can_change && enable != planner.abl_enabled) { + #else // ABL #if ENABLED(AUTO_BED_LEVELING_BILINEAR) // Force bilinear_z_offset to re-calculate next time @@ -2360,8 +2385,9 @@ static void clean_up_after_endstop_or_probe_move() { ); else planner.unapply_leveling(current_position); - } - #endif + + #endif + } } #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) @@ -2370,13 +2396,7 @@ static void clean_up_after_endstop_or_probe_move() { planner.z_fade_height = zfh; planner.inverse_z_fade_height = RECIPROCAL(zfh); - if ( - #if ENABLED(MESH_BED_LEVELING) - mbl.active() - #else - planner.abl_enabled - #endif - ) { + if (leveling_is_active()) set_current_from_steppers_for_axis( #if ABL_PLANAR ALL_AXES @@ -2384,7 +2404,6 @@ static void clean_up_after_endstop_or_probe_move() { Z_AXIS #endif ); - } } #endif // LEVELING_FADE_HEIGHT @@ -2395,7 +2414,7 @@ static void clean_up_after_endstop_or_probe_move() { void reset_bed_level() { set_bed_leveling_enabled(false); #if ENABLED(MESH_BED_LEVELING) - if (mbl.has_mesh()) { + if (leveling_is_valid()) { mbl.reset(); mbl.set_has_mesh(false); } @@ -3435,7 +3454,7 @@ inline void gcode_G4() { #elif ENABLED(AUTO_BED_LEVELING_UBL) SERIAL_ECHOPGM("UBL"); #endif - if (planner.abl_enabled) { + if (leveling_is_active()) { SERIAL_ECHOLNPGM(" (enabled)"); #if ABL_PLANAR float diff[XYZ] = { @@ -3466,7 +3485,7 @@ inline void gcode_G4() { #elif ENABLED(MESH_BED_LEVELING) SERIAL_ECHOPGM("Mesh Bed Leveling"); - if (mbl.active()) { + if (leveling_is_active()) { float lz = current_position[Z_AXIS]; planner.apply_leveling(current_position[X_AXIS], current_position[Y_AXIS], lz); SERIAL_ECHOLNPGM(" (enabled)"); @@ -3622,7 +3641,7 @@ inline void gcode_G28(const bool always_home_all) { // Disable the leveling matrix before homing #if HAS_LEVELING #if ENABLED(AUTO_BED_LEVELING_UBL) - const bool ubl_state_at_entry = ubl.state.active; + const bool ubl_state_at_entry = leveling_is_active(); #endif set_bed_leveling_enabled(false); #endif @@ -3898,8 +3917,8 @@ void home_all_axes() { gcode_G28(true); } switch (state) { case MeshReport: - if (mbl.has_mesh()) { - SERIAL_PROTOCOLLNPAIR("State: ", mbl.active() ? MSG_ON : MSG_OFF); + if (leveling_is_valid()) { + SERIAL_PROTOCOLLNPAIR("State: ", leveling_is_active() ? MSG_ON : MSG_OFF); mbl_mesh_report(); } else @@ -4201,12 +4220,12 @@ void home_all_axes() { gcode_G28(true); } abl_probe_index = -1; #endif - abl_should_enable = planner.abl_enabled; + abl_should_enable = leveling_is_active(); #if ENABLED(AUTO_BED_LEVELING_BILINEAR) if (parser.seen('W')) { - if (!bilinear_grid_spacing[X_AXIS]) { + if (!leveling_is_valid()) { SERIAL_ERROR_START; SERIAL_ERRORLNPGM("No bilinear grid"); return; @@ -4518,7 +4537,6 @@ void home_all_axes() { gcode_G28(true); } // Leveling done! Fall through to G29 finishing code below SERIAL_PROTOCOLLNPGM("Grid probing done."); - g29_in_progress = false; // Re-enable software endstops, if needed #if HAS_SOFTWARE_ENDSTOPS @@ -4542,7 +4560,6 @@ void home_all_axes() { gcode_G28(true); } else { SERIAL_PROTOCOLLNPGM("3-point probing done."); - g29_in_progress = false; // Re-enable software endstops, if needed #if HAS_SOFTWARE_ENDSTOPS @@ -4693,8 +4710,11 @@ void home_all_axes() { gcode_G28(true); } if (DEBUGGING(LEVELING)) DEBUG_POS("> probing complete", current_position); #endif - #if ENABLED(PROBE_MANUALLY) && ENABLED(LCD_BED_LEVELING) - lcd_wait_for_move = false; + #if ENABLED(PROBE_MANUALLY) + g29_in_progress = false; + #if ENABLED(LCD_BED_LEVELING) + lcd_wait_for_move = false; + #endif #endif // Calculate leveling, print reports, correct the position @@ -6591,15 +6611,7 @@ inline void gcode_M42() { // Disable bed level correction in M48 because we want the raw data when we probe #if HAS_LEVELING - const bool was_enabled = - #if ENABLED(AUTO_BED_LEVELING_UBL) - ubl.state.active - #elif ENABLED(MESH_BED_LEVELING) - mbl.active() - #else - planner.abl_enabled - #endif - ; + const bool was_enabled = leveling_is_active(); set_bed_leveling_enabled(false); #endif @@ -8727,14 +8739,14 @@ void quickstop_stepper() { #if ABL_PLANAR planner.bed_level_matrix.debug(PSTR("Bed Level Correction Matrix:")); #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) - if (bilinear_grid_spacing[X_AXIS]) { + if (leveling_is_valid()) { print_bilinear_leveling_grid(); #if ENABLED(ABL_BILINEAR_SUBDIVISION) bed_level_virt_print(); #endif } #elif ENABLED(MESH_BED_LEVELING) - if (mbl.has_mesh()) { + if (leveling_is_valid()) { SERIAL_ECHOLNPGM("Mesh Bed Level data:"); mbl_mesh_report(); } @@ -8760,15 +8772,7 @@ void quickstop_stepper() { if (parser.seen('Z')) set_z_fade_height(parser.value_linear_units()); #endif - const bool new_status = - #if ENABLED(MESH_BED_LEVELING) - mbl.active() - #elif ENABLED(AUTO_BED_LEVELING_UBL) - ubl.state.active - #else - planner.abl_enabled - #endif - ; + const bool new_status = leveling_is_active(); if (to_enable && !new_status) { SERIAL_ERROR_START; @@ -8987,7 +8991,7 @@ inline void gcode_M503() { #endif #if ENABLED(BABYSTEP_ZPROBE_OFFSET) - if (!no_babystep && planner.abl_enabled) + if (!no_babystep && leveling_is_active()) thermalManager.babystep_axis(Z_AXIS, -lround(diff * planner.axis_steps_per_mm[Z_AXIS])); #else UNUSED(no_babystep); @@ -9801,7 +9805,7 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool n #if ENABLED(MESH_BED_LEVELING) - if (mbl.active()) { + if (leveling_is_active()) { #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) SERIAL_ECHOPAIR("Z before MBL: ", current_position[Z_AXIS]); #endif @@ -11408,7 +11412,7 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) { inline bool prepare_move_to_destination_cartesian() { #if ENABLED(AUTO_BED_LEVELING_UBL) const float fr_scaled = MMS_SCALED(feedrate_mm_s); - if (ubl.state.active) { + if (ubl.state.active) { // direct use of ubl.state.active for speed ubl.line_to_destination_cartesian(fr_scaled, active_extruder); return true; } @@ -11421,13 +11425,13 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) { else { const float fr_scaled = MMS_SCALED(feedrate_mm_s); #if ENABLED(MESH_BED_LEVELING) - if (mbl.active()) { + if (mbl.active()) { // direct used of mbl.active() for speed mesh_line_to_destination(fr_scaled); return true; } else #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) - if (planner.abl_enabled) { + if (planner.abl_enabled) { // direct use of abl_enabled for speed bilinear_line_to_destination(fr_scaled); return true; } diff --git a/Marlin/configuration_store.cpp b/Marlin/configuration_store.cpp index c39508f50..0cef5c52a 100644 --- a/Marlin/configuration_store.cpp +++ b/Marlin/configuration_store.cpp @@ -1525,7 +1525,7 @@ void MarlinSettings::reset() { SERIAL_ECHOLNPGM("Mesh Bed Leveling:"); } CONFIG_ECHO_START; - SERIAL_ECHOPAIR(" M420 S", mbl.has_mesh() ? 1 : 0); + SERIAL_ECHOPAIR(" M420 S", leveling_is_valid() ? 1 : 0); #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) SERIAL_ECHOPAIR(" Z", LINEAR_UNIT(planner.z_fade_height)); #endif @@ -1549,7 +1549,7 @@ void MarlinSettings::reset() { SERIAL_ECHOLNPGM(":"); } CONFIG_ECHO_START; - SERIAL_ECHOPAIR(" M420 S", ubl.state.active ? 1 : 0); + SERIAL_ECHOPAIR(" M420 S", leveling_is_active() ? 1 : 0); #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) SERIAL_ECHOPAIR(" Z", planner.z_fade_height); #endif @@ -1576,7 +1576,7 @@ void MarlinSettings::reset() { SERIAL_ECHOLNPGM("Auto Bed Leveling:"); } CONFIG_ECHO_START; - SERIAL_ECHOPAIR(" M420 S", planner.abl_enabled ? 1 : 0); + SERIAL_ECHOPAIR(" M420 S", leveling_is_active() ? 1 : 0); #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) SERIAL_ECHOPAIR(" Z", LINEAR_UNIT(planner.z_fade_height)); #endif diff --git a/Marlin/language_an.h b/Marlin/language_an.h index af0981c44..2aa0a3929 100644 --- a/Marlin/language_an.h +++ b/Marlin/language_an.h @@ -47,7 +47,6 @@ #define MSG_LEVEL_BED_WAITING _UxGT("Encetar (pretar)") #define MSG_LEVEL_BED_NEXT_POINT _UxGT("Vinient punto") #define MSG_LEVEL_BED_DONE _UxGT("Nivelacion feita!") -#define MSG_LEVEL_BED_CANCEL _UxGT("Cancelar") #define MSG_SET_HOME_OFFSETS _UxGT("Achustar desfases") #define MSG_HOME_OFFSETS_APPLIED _UxGT("Desfase aplicau") #define MSG_SET_ORIGIN _UxGT("Establir orichen") @@ -67,6 +66,7 @@ #define MSG_EXTRUDE _UxGT("Extruir") #define MSG_RETRACT _UxGT("Retraer") #define MSG_MOVE_AXIS _UxGT("Mover Eixes") +#define MSG_BED_LEVELING _UxGT("Nivelar base") #define MSG_LEVEL_BED _UxGT("Nivelar base") #define MSG_MOVE_X _UxGT("Mover X") #define MSG_MOVE_Y _UxGT("Mover Y") diff --git a/Marlin/language_bg.h b/Marlin/language_bg.h index 34d812eda..2370ca5f5 100644 --- a/Marlin/language_bg.h +++ b/Marlin/language_bg.h @@ -48,7 +48,6 @@ #define MSG_LEVEL_BED_WAITING _UxGT("Click to Begin") #define MSG_LEVEL_BED_NEXT_POINT _UxGT("Next Point") #define MSG_LEVEL_BED_DONE _UxGT("Leveling Done!") -#define MSG_LEVEL_BED_CANCEL _UxGT("Cancel") #define MSG_SET_HOME_OFFSETS _UxGT("Задай Начало") #define MSG_HOME_OFFSETS_APPLIED _UxGT("Offsets applied") #define MSG_SET_ORIGIN _UxGT("Изходна точка") @@ -68,6 +67,7 @@ #define MSG_EXTRUDE _UxGT("Екструзия") #define MSG_RETRACT _UxGT("Откат") #define MSG_MOVE_AXIS _UxGT("Движение по ос") +#define MSG_BED_LEVELING _UxGT("Нивелиране") #define MSG_LEVEL_BED _UxGT("Нивелиране") #define MSG_MOVE_X _UxGT("Движение по X") #define MSG_MOVE_Y _UxGT("Движение по Y") diff --git a/Marlin/language_ca.h b/Marlin/language_ca.h index 4a713c63e..01a48d2b9 100644 --- a/Marlin/language_ca.h +++ b/Marlin/language_ca.h @@ -50,7 +50,6 @@ #define MSG_LEVEL_BED_WAITING _UxGT("Premeu per iniciar") #define MSG_LEVEL_BED_NEXT_POINT _UxGT("Següent punt") #define MSG_LEVEL_BED_DONE _UxGT("Anivellament fet!") -#define MSG_LEVEL_BED_CANCEL _UxGT("Cancel.la") #define MSG_SET_HOME_OFFSETS _UxGT("Ajusta decalatge") #define MSG_HOME_OFFSETS_APPLIED _UxGT("Decalatge aplicat") #define MSG_SET_ORIGIN _UxGT("Estableix origen") @@ -70,6 +69,7 @@ #define MSG_EXTRUDE _UxGT("Extrudeix") #define MSG_RETRACT _UxGT("Retreu") #define MSG_MOVE_AXIS _UxGT("Mou eixos") +#define MSG_BED_LEVELING _UxGT("Anivella llit") #define MSG_LEVEL_BED _UxGT("Anivella llit") #define MSG_MOVING _UxGT("Movent..") #define MSG_FREE_XY _UxGT("XY lliures") diff --git a/Marlin/language_cn.h b/Marlin/language_cn.h index 5b471a672..41efcf098 100644 --- a/Marlin/language_cn.h +++ b/Marlin/language_cn.h @@ -42,7 +42,6 @@ #define MSG_LEVEL_BED_HOMING "Homing XYZ" #define MSG_LEVEL_BED_WAITING "Click to Begin" #define MSG_LEVEL_BED_DONE "Leveling Done!" -#define MSG_LEVEL_BED_CANCEL "Cancel" #define MSG_SET_HOME_OFFSETS "\xbe\xbf\xbb\xbc\xbd\xc0\xc1" #define MSG_HOME_OFFSETS_APPLIED "Offsets applied" #define MSG_SET_ORIGIN "\xbe\xbf\xbc\xbd" @@ -62,6 +61,7 @@ #define MSG_EXTRUDE "\xcc\xad" #define MSG_RETRACT "\xbb\xcd" #define MSG_MOVE_AXIS "\xc1\xb2\xce" +#define MSG_BED_LEVELING "\xcf\xe0\xc4\xc7" #define MSG_LEVEL_BED "\xcf\xe0\xc4\xc7" #define MSG_MOVE_X "\xc1\xb2 X" #define MSG_MOVE_Y "\xc1\xb2 Y" diff --git a/Marlin/language_cz.h b/Marlin/language_cz.h index 25cad14b1..2ee3310bc 100644 --- a/Marlin/language_cz.h +++ b/Marlin/language_cz.h @@ -54,7 +54,6 @@ #define MSG_LEVEL_BED_WAITING _UxGT("Kliknutim spustte") #define MSG_LEVEL_BED_NEXT_POINT _UxGT("Dalsi bod") #define MSG_LEVEL_BED_DONE _UxGT("Mereni hotovo!") -#define MSG_LEVEL_BED_CANCEL _UxGT("Storno") #define MSG_SET_HOME_OFFSETS _UxGT("Nastavit ofsety") #define MSG_HOME_OFFSETS_APPLIED _UxGT("Ofsety nastaveny") #define MSG_SET_ORIGIN _UxGT("Nastavit pocatek") @@ -76,6 +75,7 @@ #define MSG_EXTRUDE _UxGT("Vytlacit (extr.)") #define MSG_RETRACT _UxGT("Zatlacit (retr.)") #define MSG_MOVE_AXIS _UxGT("Posunout osy") +#define MSG_BED_LEVELING _UxGT("Vyrovnat podlozku") #define MSG_LEVEL_BED _UxGT("Vyrovnat podlozku") #define MSG_MOVING _UxGT("Posunování...") #define MSG_FREE_XY _UxGT("Uvolnit XY") diff --git a/Marlin/language_da.h b/Marlin/language_da.h index 93fdfbd27..52391feef 100644 --- a/Marlin/language_da.h +++ b/Marlin/language_da.h @@ -48,7 +48,6 @@ #define MSG_LEVEL_BED_WAITING _UxGT("Klik når du er klar") #define MSG_LEVEL_BED_NEXT_POINT _UxGT("Næste punkt") #define MSG_LEVEL_BED_DONE _UxGT("Bed level er færdig!") -#define MSG_LEVEL_BED_CANCEL _UxGT("Annuller bed level") #define MSG_SET_HOME_OFFSETS _UxGT("Sæt forsk. af home") #define MSG_HOME_OFFSETS_APPLIED _UxGT("Forsk. er nu aktiv") #define MSG_SET_ORIGIN _UxGT("Sæt origin") @@ -68,6 +67,7 @@ #define MSG_EXTRUDE _UxGT("Extruder") #define MSG_RETRACT _UxGT("Retract") #define MSG_MOVE_AXIS _UxGT("Flyt akser") +#define MSG_BED_LEVELING _UxGT("Juster bed") #define MSG_LEVEL_BED _UxGT("Juster bed") #define MSG_MOVE_X _UxGT("Flyt X") #define MSG_MOVE_Y _UxGT("Flyt Y") diff --git a/Marlin/language_de.h b/Marlin/language_de.h index 01d8fdea4..e5216d005 100644 --- a/Marlin/language_de.h +++ b/Marlin/language_de.h @@ -51,7 +51,6 @@ #define MSG_LEVEL_BED_WAITING _UxGT("Klick für Start") #define MSG_LEVEL_BED_NEXT_POINT _UxGT("Nächste Koordinate") #define MSG_LEVEL_BED_DONE _UxGT("Fertig") -#define MSG_LEVEL_BED_CANCEL _UxGT("Abbruch") #define MSG_SET_HOME_OFFSETS _UxGT("Setze Homeversatz") #define MSG_HOME_OFFSETS_APPLIED _UxGT("Homeversatz aktiv") #define MSG_SET_ORIGIN _UxGT("Setze Nullpunkt") //"G92 X0 Y0 Z0" commented out in ultralcd.cpp @@ -73,6 +72,7 @@ #define MSG_EXTRUDE _UxGT("Extrudieren") #define MSG_RETRACT _UxGT("Retract") #define MSG_MOVE_AXIS _UxGT("Bewegen") +#define MSG_BED_LEVELING _UxGT("Bett nivellieren") #define MSG_LEVEL_BED _UxGT("Bett nivellieren") #define MSG_MOVING _UxGT("In Bewegung...") #define MSG_FREE_XY _UxGT("Abstand XY") diff --git a/Marlin/language_el-gr.h b/Marlin/language_el-gr.h index 3e55dd666..4104a1daf 100644 --- a/Marlin/language_el-gr.h +++ b/Marlin/language_el-gr.h @@ -48,7 +48,6 @@ #define MSG_LEVEL_BED_WAITING _UxGT("Κάντε κλικ για να ξεκινήσετε") #define MSG_LEVEL_BED_NEXT_POINT _UxGT("Επόμενο σημείο") #define MSG_LEVEL_BED_DONE _UxGT("Ολοκλήρωση επιπεδοποίησης!") -#define MSG_LEVEL_BED_CANCEL _UxGT("Ακύρωση") #define MSG_SET_HOME_OFFSETS _UxGT("Ορισμός βασικών μετατοπίσεων") #define MSG_HOME_OFFSETS_APPLIED _UxGT("Εφαρμόστηκαν οι μετατοπίσεις") #define MSG_SET_ORIGIN _UxGT("Ορισμός προέλευσης") @@ -68,6 +67,7 @@ #define MSG_EXTRUDE _UxGT("Εξώθηση") #define MSG_RETRACT _UxGT("Ανάσυρση") #define MSG_MOVE_AXIS _UxGT("Μετακίνηση άξονα") +#define MSG_BED_LEVELING _UxGT("Επιπεδοποίηση κλίνης") #define MSG_LEVEL_BED _UxGT("Επιπεδοποίηση κλίνης") #define MSG_MOVE_X _UxGT("Μετακίνηση X") #define MSG_MOVE_Y _UxGT("Μετακίνηση Y") diff --git a/Marlin/language_el.h b/Marlin/language_el.h index 420363017..af23ede57 100644 --- a/Marlin/language_el.h +++ b/Marlin/language_el.h @@ -48,7 +48,6 @@ #define MSG_LEVEL_BED_WAITING _UxGT("Επιπεδοποίηση επ. Εκτύπωσης περιμενει") //SHORTEN #define MSG_LEVEL_BED_NEXT_POINT _UxGT("Επόμενο σημείο") #define MSG_LEVEL_BED_DONE _UxGT("Ολοκλήρωση επιπεδοποίησης!") //SHORTEN -#define MSG_LEVEL_BED_CANCEL _UxGT("Ακύρωση") #define MSG_SET_HOME_OFFSETS _UxGT("Ορισμός βασικών μετατοπίσεων") //SHORTEN #define MSG_HOME_OFFSETS_APPLIED _UxGT("Εφαρμόστηκαν οι μετατοπίσεις") //SHORTEN #define MSG_SET_ORIGIN _UxGT("Ορισμός προέλευσης") @@ -68,6 +67,7 @@ #define MSG_EXTRUDE _UxGT("Εξώθηση") #define MSG_RETRACT _UxGT("Ανάσυρση") #define MSG_MOVE_AXIS _UxGT("Μετακίνηση άξονα") +#define MSG_BED_LEVELING _UxGT("Επιπεδοποίηση Επ. Εκτύπωσης") //SHORTEN #define MSG_LEVEL_BED _UxGT("Επιπεδοποίηση Επ. Εκτύπωσης") //SHORTEN #define MSG_MOVE_X _UxGT("Μετακίνηση X") #define MSG_MOVE_Y _UxGT("Μετακίνηση Y") diff --git a/Marlin/language_en.h b/Marlin/language_en.h index 9099b0497..9d0958d3a 100644 --- a/Marlin/language_en.h +++ b/Marlin/language_en.h @@ -84,8 +84,8 @@ #ifndef MSG_LEVEL_BED_DONE #define MSG_LEVEL_BED_DONE _UxGT("Leveling Done!") #endif -#ifndef MSG_LEVEL_BED_CANCEL - #define MSG_LEVEL_BED_CANCEL _UxGT("Cancel") +#ifndef MSG_Z_FADE_HEIGHT + #define MSG_Z_FADE_HEIGHT _UxGT("Fade Height") #endif #ifndef MSG_SET_HOME_OFFSETS #define MSG_SET_HOME_OFFSETS _UxGT("Set home offsets") @@ -150,6 +150,9 @@ #ifndef MSG_MOVE_AXIS #define MSG_MOVE_AXIS _UxGT("Move axis") #endif +#ifndef MSG_BED_LEVELING + #define MSG_BED_LEVELING _UxGT("Bed Leveling") +#endif #ifndef MSG_LEVEL_BED #define MSG_LEVEL_BED _UxGT("Level bed") #endif diff --git a/Marlin/language_es.h b/Marlin/language_es.h index 97decb406..30ebb1e21 100644 --- a/Marlin/language_es.h +++ b/Marlin/language_es.h @@ -50,7 +50,6 @@ #define MSG_LEVEL_BED_WAITING _UxGT("Iniciar (Presione)") #define MSG_LEVEL_BED_NEXT_POINT _UxGT("Siguiente punto") #define MSG_LEVEL_BED_DONE _UxGT("Nivelacion lista!") -#define MSG_LEVEL_BED_CANCEL _UxGT("Cancelar") #define MSG_SET_HOME_OFFSETS _UxGT("Ajustar desfases") #define MSG_HOME_OFFSETS_APPLIED _UxGT("Desfase aplicado") #define MSG_SET_ORIGIN _UxGT("Establecer origen") @@ -72,6 +71,7 @@ #define MSG_EXTRUDE _UxGT("Extruir") #define MSG_RETRACT _UxGT("Retraer") #define MSG_MOVE_AXIS _UxGT("Mover ejes") +#define MSG_BED_LEVELING _UxGT("Nivelar plataforma") #define MSG_LEVEL_BED _UxGT("Nivelar plataforma") #define MSG_MOVING _UxGT("Moviendo...") #define MSG_FREE_XY _UxGT("Libre XY") diff --git a/Marlin/language_eu.h b/Marlin/language_eu.h index fbf6464d2..64dbd5cae 100644 --- a/Marlin/language_eu.h +++ b/Marlin/language_eu.h @@ -50,7 +50,6 @@ #define MSG_LEVEL_BED_WAITING _UxGT("Klik egin hasteko") #define MSG_LEVEL_BED_NEXT_POINT _UxGT("Hurrengo Puntua") #define MSG_LEVEL_BED_DONE _UxGT("Berdintzea eginda") -#define MSG_LEVEL_BED_CANCEL _UxGT("Ezeztatu") #define MSG_SET_HOME_OFFSETS _UxGT("Etxe. offset eza.") #define MSG_HOME_OFFSETS_APPLIED _UxGT("Offsetak ezarrita") #define MSG_SET_ORIGIN _UxGT("Hasiera ipini") @@ -72,6 +71,7 @@ #define MSG_EXTRUDE _UxGT("Estruitu") #define MSG_RETRACT _UxGT("Atzera eragin") #define MSG_MOVE_AXIS _UxGT("Ardatzak mugitu") +#define MSG_BED_LEVELING _UxGT("Ohea Berdindu") #define MSG_LEVEL_BED _UxGT("Ohea Berdindu") #define MSG_MOVING _UxGT("Mugitzen...") #define MSG_FREE_XY _UxGT("Askatu XY") diff --git a/Marlin/language_fi.h b/Marlin/language_fi.h index cd78d80e7..4bb723617 100644 --- a/Marlin/language_fi.h +++ b/Marlin/language_fi.h @@ -43,7 +43,6 @@ #define MSG_LEVEL_BED_HOMING _UxGT("Homing XYZ") #define MSG_LEVEL_BED_WAITING _UxGT("Click to Begin") #define MSG_LEVEL_BED_DONE _UxGT("Leveling Done!") -#define MSG_LEVEL_BED_CANCEL _UxGT("Cancel") #define MSG_SET_HOME_OFFSETS _UxGT("Set home offsets") #define MSG_HOME_OFFSETS_APPLIED _UxGT("Offsets applied") #define MSG_SET_ORIGIN _UxGT("Aseta origo") diff --git a/Marlin/language_fr.h b/Marlin/language_fr.h index 84b0dd714..116f5d8b1 100644 --- a/Marlin/language_fr.h +++ b/Marlin/language_fr.h @@ -51,7 +51,6 @@ #define MSG_LEVEL_BED_WAITING _UxGT("Clic pour commencer") #define MSG_LEVEL_BED_NEXT_POINT _UxGT("Point suivant") #define MSG_LEVEL_BED_DONE _UxGT("Mise à niveau OK!") -#define MSG_LEVEL_BED_CANCEL _UxGT("Annuler") #define MSG_SET_HOME_OFFSETS _UxGT("Regl. décal. origine") #define MSG_HOME_OFFSETS_APPLIED _UxGT("Décalages appliqués") #define MSG_SET_ORIGIN _UxGT("Régler origine") @@ -73,6 +72,7 @@ #define MSG_EXTRUDE _UxGT("Éxtrusion") #define MSG_RETRACT _UxGT("Rétraction") #define MSG_MOVE_AXIS _UxGT("Déplacer un axe") +#define MSG_BED_LEVELING _UxGT("Règl. Niv. lit") #define MSG_LEVEL_BED _UxGT("Règl. Niv. lit") #define MSG_MOVING _UxGT("Déplacement...") #define MSG_FREE_XY _UxGT("Débloquer XY") diff --git a/Marlin/language_gl.h b/Marlin/language_gl.h index d82da020a..d6234e5d3 100644 --- a/Marlin/language_gl.h +++ b/Marlin/language_gl.h @@ -48,7 +48,6 @@ #define MSG_LEVEL_BED_WAITING _UxGT("Prema pulsador") #define MSG_LEVEL_BED_NEXT_POINT _UxGT("Seguinte punto") #define MSG_LEVEL_BED_DONE _UxGT("Nivelado feito") -#define MSG_LEVEL_BED_CANCEL _UxGT("Cancelar") #define MSG_SET_HOME_OFFSETS _UxGT("Offsets na orixe") #define MSG_HOME_OFFSETS_APPLIED _UxGT("Offsets fixados") #define MSG_SET_ORIGIN _UxGT("Fixar orixe") @@ -68,6 +67,7 @@ #define MSG_EXTRUDE _UxGT("Extrudir") #define MSG_RETRACT _UxGT("Retraer") #define MSG_MOVE_AXIS _UxGT("Mover eixe") +#define MSG_BED_LEVELING _UxGT("Nivelar cama") #define MSG_LEVEL_BED _UxGT("Nivelar cama") #define MSG_MOVE_X _UxGT("Mover X") #define MSG_MOVE_Y _UxGT("Mover Y") diff --git a/Marlin/language_hr.h b/Marlin/language_hr.h index 61308142d..72a4fd0c3 100644 --- a/Marlin/language_hr.h +++ b/Marlin/language_hr.h @@ -47,7 +47,6 @@ #define MSG_LEVEL_BED_WAITING _UxGT("Klikni za početak") #define MSG_LEVEL_BED_NEXT_POINT _UxGT("Sljedeća točka") #define MSG_LEVEL_BED_DONE _UxGT("Niveliranje gotovo!") -#define MSG_LEVEL_BED_CANCEL _UxGT("Otkaži") #define MSG_SET_HOME_OFFSETS _UxGT("Postavi home offsete") #define MSG_HOME_OFFSETS_APPLIED _UxGT("Offsets postavljeni") #define MSG_SET_ORIGIN _UxGT("Postavi ishodište") @@ -67,6 +66,7 @@ #define MSG_EXTRUDE _UxGT("Extrude") #define MSG_RETRACT _UxGT("Retract") #define MSG_MOVE_AXIS _UxGT("Miči os") +#define MSG_BED_LEVELING _UxGT("Niveliraj bed") #define MSG_LEVEL_BED _UxGT("Niveliraj bed") #define MSG_MOVE_X _UxGT("Miči X") #define MSG_MOVE_Y _UxGT("Miči Y") diff --git a/Marlin/language_it.h b/Marlin/language_it.h index 415ae507e..6ff2337fd 100644 --- a/Marlin/language_it.h +++ b/Marlin/language_it.h @@ -50,7 +50,6 @@ #define MSG_LEVEL_BED_WAITING _UxGT("Premi per iniziare") #define MSG_LEVEL_BED_NEXT_POINT _UxGT("Punto successivo") #define MSG_LEVEL_BED_DONE _UxGT("Livel. terminato!") -#define MSG_LEVEL_BED_CANCEL _UxGT("Annulla") #define MSG_SET_HOME_OFFSETS _UxGT("Imp. offset home") #define MSG_HOME_OFFSETS_APPLIED _UxGT("Offset applicato") #define MSG_SET_ORIGIN _UxGT("Imposta Origine") @@ -72,6 +71,7 @@ #define MSG_EXTRUDE _UxGT("Estrudi") #define MSG_RETRACT _UxGT("Ritrai") #define MSG_MOVE_AXIS _UxGT("Muovi Asse") +#define MSG_BED_LEVELING _UxGT("Livella piano") #define MSG_LEVEL_BED _UxGT("Livella piano") #define MSG_MOVING _UxGT("In movimento...") #define MSG_FREE_XY _UxGT("XY liberi") diff --git a/Marlin/language_kana.h b/Marlin/language_kana.h index 077a277a7..c8169a265 100644 --- a/Marlin/language_kana.h +++ b/Marlin/language_kana.h @@ -53,7 +53,6 @@ #define MSG_LEVEL_BED_WAITING "\xda\xcd\xde\xd8\xdd\xb8\xde\xb6\xb2\xbc" // "レベリングカイシ" ("Click to Begin") #define MSG_LEVEL_BED_NEXT_POINT "\xc2\xb7\xde\xc9\xbf\xb8\xc3\xb2\xc3\xdd\xcd" // "ツギノソクテイテンヘ" ("Next Point") #define MSG_LEVEL_BED_DONE "\xda\xcd\xde\xd8\xdd\xb8\xde\xb6\xdd\xd8\xae\xb3" // "レベリングカンリョウ" ("Leveling Done!") -#define MSG_LEVEL_BED_CANCEL "\xc4\xd8\xd4\xd2" // "トリヤメ" ("Cancel") #define MSG_SET_HOME_OFFSETS "\xb7\xbc\xde\xad\xdd\xb5\xcc\xbe\xaf\xc4\xbe\xaf\xc3\xb2" // "キジュンオフセットセッテイ" ("Set home offsets") #define MSG_HOME_OFFSETS_APPLIED "\xb5\xcc\xbe\xaf\xc4\xb6\xde\xc3\xb7\xd6\xb3\xbb\xda\xcf\xbc\xc0" // "オフセットガテキヨウサレマシタ" ("Offsets applied") #define MSG_SET_ORIGIN "\xb7\xbc\xde\xad\xdd\xbe\xaf\xc4" // "キジュンセット" ("Set origin") @@ -73,6 +72,7 @@ #define MSG_EXTRUDE "\xb5\xbc\xc0\xde\xbc" // "オシダシ" ("Extrude") #define MSG_RETRACT "\xcb\xb7\xba\xd0\xbe\xaf\xc3\xb2" // "ヒキコミセッテイ" ("Retract") #define MSG_MOVE_AXIS "\xbc\xde\xb8\xb2\xc4\xde\xb3" // "ジクイドウ" ("Move axis") +#define MSG_BED_LEVELING "\xcd\xde\xaf\xc4\xde\xda\xcd\xde\xd8\xdd\xb8\xde" // "ベッドレベリング" ("Bed Leveling") #define MSG_LEVEL_BED "\xcd\xde\xaf\xc4\xde\xda\xcd\xde\xd8\xdd\xb8\xde" // "ベッドレベリング" ("Level bed") #define MSG_MOVING "\xb2\xc4\xde\xb3\xc1\xad\xb3" // "イドウチュウ" ("Moving...") #define MSG_FREE_XY "XY\xbc\xde\xb8\x20\xb6\xb2\xce\xb3" // "XYジク カイホウ" ("Free XY") diff --git a/Marlin/language_kana_utf8.h b/Marlin/language_kana_utf8.h index 6ca860586..874647ad5 100644 --- a/Marlin/language_kana_utf8.h +++ b/Marlin/language_kana_utf8.h @@ -55,7 +55,6 @@ #define MSG_LEVEL_BED_WAITING _UxGT("レベリングカイシ") // "Click to Begin" #define MSG_LEVEL_BED_NEXT_POINT _UxGT("ツギノソクテイテンヘ") // "Next Point" #define MSG_LEVEL_BED_DONE _UxGT("レベリングカンリョウ") // "Leveling Done!" -#define MSG_LEVEL_BED_CANCEL _UxGT("トリヤメ") // "Cancel" #define MSG_SET_HOME_OFFSETS _UxGT("キジュンオフセットセッテイ") // "Set home offsets" #define MSG_HOME_OFFSETS_APPLIED _UxGT("オフセットガテキヨウサレマシタ") // "Offsets applied" #define MSG_SET_ORIGIN _UxGT("キジュンセット") // "Set origin" @@ -75,6 +74,7 @@ #define MSG_EXTRUDE _UxGT("オシダシ") // "Extrude" #define MSG_RETRACT _UxGT("ヒキコミセッテイ") // "Retract" #define MSG_MOVE_AXIS _UxGT("ジクイドウ") // "Move axis" +#define MSG_BED_LEVELING _UxGT("ベッドレベリング") // "Bed leveling" #define MSG_LEVEL_BED _UxGT("ベッドレベリング") // "Level bed" #define MSG_MOVING _UxGT("イドウチュウ") // "Moving..." #define MSG_FREE_XY _UxGT("XYジク カイホウ") // "Free XY" diff --git a/Marlin/language_nl.h b/Marlin/language_nl.h index b041a3535..ffb71f69d 100644 --- a/Marlin/language_nl.h +++ b/Marlin/language_nl.h @@ -50,7 +50,6 @@ #define MSG_LEVEL_BED_WAITING _UxGT("Klik voor begin") #define MSG_LEVEL_BED_NEXT_POINT _UxGT("Volgende Plaats") #define MSG_LEVEL_BED_DONE _UxGT("Bed level kompl.") -#define MSG_LEVEL_BED_CANCEL _UxGT("Bed level afbr.") #define MSG_SET_HOME_OFFSETS _UxGT("Zet home offsets") #define MSG_HOME_OFFSETS_APPLIED _UxGT("H offset toegep.") #define MSG_SET_ORIGIN _UxGT("Nulpunt instellen") @@ -72,6 +71,7 @@ #define MSG_EXTRUDE _UxGT("Extrude") #define MSG_RETRACT _UxGT("Retract") #define MSG_MOVE_AXIS _UxGT("As verplaatsen") +#define MSG_BED_LEVELING _UxGT("Bed Leveling") #define MSG_LEVEL_BED _UxGT("Level bed") #define MSG_MOVING _UxGT("Verplaatsen...") #define MSG_FREE_XY _UxGT("Vrij XY") diff --git a/Marlin/language_pl.h b/Marlin/language_pl.h index 204d3123b..2794a1723 100644 --- a/Marlin/language_pl.h +++ b/Marlin/language_pl.h @@ -50,7 +50,6 @@ #define MSG_LEVEL_BED_WAITING _UxGT("Kliknij by rozp.") #define MSG_LEVEL_BED_NEXT_POINT _UxGT("Następny punkt") #define MSG_LEVEL_BED_DONE _UxGT("Wypoziomowano!") -#define MSG_LEVEL_BED_CANCEL _UxGT("Anuluj") #define MSG_SET_HOME_OFFSETS _UxGT("Ust. poz. zer.") #define MSG_HOME_OFFSETS_APPLIED _UxGT("Poz. zerowa ust.") #define MSG_SET_ORIGIN _UxGT("Ustaw punkt zero") @@ -70,6 +69,7 @@ #define MSG_EXTRUDE _UxGT("Ekstruzja") #define MSG_RETRACT _UxGT("Wycofanie") #define MSG_MOVE_AXIS _UxGT("Ruch osi") +#define MSG_BED_LEVELING _UxGT("Poziom. stołu") #define MSG_LEVEL_BED _UxGT("Poziom. stołu") #define MSG_MOVE_X _UxGT("Przesuń w X") #define MSG_MOVE_Y _UxGT("Przesuń w Y") @@ -268,7 +268,6 @@ #define MSG_LEVEL_BED_WAITING _UxGT("Kliknij by rozp.") #define MSG_LEVEL_BED_NEXT_POINT _UxGT("Nastepny punkt") #define MSG_LEVEL_BED_DONE _UxGT("Wypoziomowano!") -#define MSG_LEVEL_BED_CANCEL _UxGT("Anuluj") #define MSG_SET_HOME_OFFSETS _UxGT("Ust. poz. zer.") #define MSG_HOME_OFFSETS_APPLIED _UxGT("Poz. zerowa ust.") #define MSG_SET_ORIGIN _UxGT("Ustaw punkt zero") @@ -288,6 +287,7 @@ #define MSG_EXTRUDE _UxGT("Ekstruzja") #define MSG_RETRACT _UxGT("Wycofanie") #define MSG_MOVE_AXIS _UxGT("Ruch osi") +#define MSG_BED_LEVELING _UxGT("Poziom. stolu") #define MSG_LEVEL_BED _UxGT("Poziom. stolu") #define MSG_MOVE_X _UxGT("Przesun w X") #define MSG_MOVE_Y _UxGT("Przesun w Y") diff --git a/Marlin/language_pt-br.h b/Marlin/language_pt-br.h index 05c91e0b9..03e683c5e 100644 --- a/Marlin/language_pt-br.h +++ b/Marlin/language_pt-br.h @@ -42,7 +42,6 @@ #define MSG_LEVEL_BED_HOMING "Homing XYZ" #define MSG_LEVEL_BED_WAITING "Click to Begin" #define MSG_LEVEL_BED_DONE "Leveling Done!" -#define MSG_LEVEL_BED_CANCEL "Cancel" #define MSG_SET_HOME_OFFSETS "Ajustar Jogo" #define MSG_HOME_OFFSETS_APPLIED "Offsets applied" #define MSG_SET_ORIGIN "Ajustar orig." diff --git a/Marlin/language_pt-br_utf8.h b/Marlin/language_pt-br_utf8.h index c9040fcdd..e2d9ced5e 100644 --- a/Marlin/language_pt-br_utf8.h +++ b/Marlin/language_pt-br_utf8.h @@ -42,7 +42,6 @@ #define MSG_LEVEL_BED_HOMING _UxGT("Indo para origem") #define MSG_LEVEL_BED_WAITING _UxGT("Click to Begin") #define MSG_LEVEL_BED_DONE _UxGT("Leveling Done!") -#define MSG_LEVEL_BED_CANCEL _UxGT("Cancel") #define MSG_SET_HOME_OFFSETS _UxGT("Ajustar Jogo") #define MSG_HOME_OFFSETS_APPLIED _UxGT("Offsets applied") #define MSG_SET_ORIGIN _UxGT("Ajustar orig.") diff --git a/Marlin/language_pt.h b/Marlin/language_pt.h index 4b8212432..17d7c21f5 100644 --- a/Marlin/language_pt.h +++ b/Marlin/language_pt.h @@ -46,7 +46,6 @@ #define MSG_LEVEL_BED_WAITING "Click para iniciar" #define MSG_LEVEL_BED_NEXT_POINT "Proximo ponto" #define MSG_LEVEL_BED_DONE "Pronto !" -#define MSG_LEVEL_BED_CANCEL "Cancelar" #define MSG_SET_HOME_OFFSETS "Definir desvio" #define MSG_HOME_OFFSETS_APPLIED "Offsets applied" #define MSG_SET_ORIGIN "Definir origem" diff --git a/Marlin/language_pt_utf8.h b/Marlin/language_pt_utf8.h index d9345a579..e939c4d0c 100644 --- a/Marlin/language_pt_utf8.h +++ b/Marlin/language_pt_utf8.h @@ -46,7 +46,6 @@ #define MSG_LEVEL_BED_WAITING _UxGT("Click para iniciar") #define MSG_LEVEL_BED_NEXT_POINT _UxGT("Próximo ponto") #define MSG_LEVEL_BED_DONE _UxGT("Pronto !") -#define MSG_LEVEL_BED_CANCEL _UxGT("Cancelar") #define MSG_SET_HOME_OFFSETS _UxGT("Definir desvio") #define MSG_HOME_OFFSETS_APPLIED _UxGT("Offsets aplicados") #define MSG_SET_ORIGIN _UxGT("Definir origem") diff --git a/Marlin/language_ru.h b/Marlin/language_ru.h index 3b2936128..1c82986cb 100644 --- a/Marlin/language_ru.h +++ b/Marlin/language_ru.h @@ -45,7 +45,6 @@ #define MSG_LEVEL_BED_WAITING _UxGT("Нажмите начать") #define MSG_LEVEL_BED_NEXT_POINT _UxGT("Следующая точка") #define MSG_LEVEL_BED_DONE _UxGT("Уровень!") -#define MSG_LEVEL_BED_CANCEL _UxGT("Отменить") #define MSG_SET_HOME_OFFSETS _UxGT("Запомнить парковку") #define MSG_HOME_OFFSETS_APPLIED _UxGT("Коррекции примен") #define MSG_SET_ORIGIN _UxGT("Запомнить ноль") @@ -65,6 +64,7 @@ #define MSG_EXTRUDE _UxGT("Экструзия") #define MSG_RETRACT _UxGT("Втягивание") #define MSG_MOVE_AXIS _UxGT("Движение по осям") +#define MSG_BED_LEVELING _UxGT("Калибровать стол") #define MSG_LEVEL_BED _UxGT("Калибровать стол") #define MSG_MOVE_X _UxGT("Движение по X") #define MSG_MOVE_Y _UxGT("Движение по Y") diff --git a/Marlin/language_tr.h b/Marlin/language_tr.h index d15fbfb6d..edbea97d7 100644 --- a/Marlin/language_tr.h +++ b/Marlin/language_tr.h @@ -55,7 +55,6 @@ #define MSG_LEVEL_BED_WAITING _UxGT("Başlatmak için tıkla") // Başlatmak için tıkla #define MSG_LEVEL_BED_NEXT_POINT _UxGT("Sıradaki Nokta") // Sıradaki Nokta #define MSG_LEVEL_BED_DONE _UxGT("Seviyeleme Tamam!") // Seviyeleme Tamam! -#define MSG_LEVEL_BED_CANCEL _UxGT("İptal") // İptal #define MSG_SET_HOME_OFFSETS _UxGT("Offset Ayarla") // Offset Ayarla #define MSG_HOME_OFFSETS_APPLIED _UxGT("Offset Tamam") // Offset Tamam #define MSG_SET_ORIGIN _UxGT("Sıfır Belirle") // Sıfır Belirle @@ -77,6 +76,7 @@ #define MSG_EXTRUDE _UxGT("Extrude") // Extrude #define MSG_RETRACT _UxGT("Geri Çek") // Geri Çek #define MSG_MOVE_AXIS _UxGT("Eksen Yönet") // Eksenleri Yönet +#define MSG_BED_LEVELING _UxGT("Tabla Seviyele") // Tabla Seviyele #define MSG_LEVEL_BED _UxGT("Tabla Seviyele") // Tabla Seviyele #define MSG_MOVING _UxGT("Konumlanıyor...") // Konumlanıyor... #define MSG_FREE_XY _UxGT("Durdur XY") // Durdur XY diff --git a/Marlin/language_uk.h b/Marlin/language_uk.h index 2773b24c3..638961e93 100644 --- a/Marlin/language_uk.h +++ b/Marlin/language_uk.h @@ -48,7 +48,6 @@ #define MSG_LEVEL_BED_WAITING _UxGT("Почати") #define MSG_LEVEL_BED_NEXT_POINT _UxGT("Слідуюча Точка") #define MSG_LEVEL_BED_DONE _UxGT("Завершено!") -#define MSG_LEVEL_BED_CANCEL _UxGT("Відміна") #define MSG_SET_HOME_OFFSETS _UxGT("Зберегти паркув.") #define MSG_HOME_OFFSETS_APPLIED _UxGT("Зміщення застос.") #define MSG_SET_ORIGIN _UxGT("Встанов. початок") @@ -68,6 +67,7 @@ #define MSG_EXTRUDE _UxGT("Екструзія") #define MSG_RETRACT _UxGT("Втягування") #define MSG_MOVE_AXIS _UxGT("Рух по осям") +#define MSG_BED_LEVELING _UxGT("Нівелювання столу") #define MSG_LEVEL_BED _UxGT("Нівелювання столу") #define MSG_MOVE_X _UxGT("Рух по X") #define MSG_MOVE_Y _UxGT("Рух по Y") diff --git a/Marlin/language_zh_CN.h b/Marlin/language_zh_CN.h index c42ab6a4f..deefcf6c5 100644 --- a/Marlin/language_zh_CN.h +++ b/Marlin/language_zh_CN.h @@ -45,7 +45,6 @@ #define MSG_LEVEL_BED_WAITING _UxGT("单击开始热床调平") //"Click to Begin" #define MSG_LEVEL_BED_NEXT_POINT _UxGT("下个热床调平点") //"Next Point" #define MSG_LEVEL_BED_DONE _UxGT("完成热床调平") //"Leveling Done!" -#define MSG_LEVEL_BED_CANCEL _UxGT("取消热床调平") //"Cancel" #define MSG_SET_HOME_OFFSETS _UxGT("设置原点偏移") //"Set home offsets" #define MSG_HOME_OFFSETS_APPLIED _UxGT("偏移已启用") //"Offsets applied" #define MSG_SET_ORIGIN _UxGT("设置原点") //"Set origin" @@ -65,6 +64,7 @@ #define MSG_EXTRUDE _UxGT("挤出") //"Extrude" #define MSG_RETRACT _UxGT("回抽") //"Retract" #define MSG_MOVE_AXIS _UxGT("移动轴") //"Move axis" +#define MSG_BED_LEVELING _UxGT("调平热床") //"Bed leveling" #define MSG_LEVEL_BED _UxGT("调平热床") //"Level bed" #define MSG_MOVE_X _UxGT("移动X") //"Move X" #define MSG_MOVE_Y _UxGT("移动Y") //"Move Y" diff --git a/Marlin/language_zh_TW.h b/Marlin/language_zh_TW.h index 421f4e717..c7563e786 100644 --- a/Marlin/language_zh_TW.h +++ b/Marlin/language_zh_TW.h @@ -45,7 +45,6 @@ #define MSG_LEVEL_BED_WAITING _UxGT("單擊開始熱床調平") //"Click to Begin" #define MSG_LEVEL_BED_NEXT_POINT _UxGT("下個熱床調平點") //"Next Point" #define MSG_LEVEL_BED_DONE _UxGT("完成熱床調平") //"Leveling Done!" -#define MSG_LEVEL_BED_CANCEL _UxGT("取消熱床調平") //"Cancel" #define MSG_SET_HOME_OFFSETS _UxGT("設置原點偏移") //"Set home offsets" #define MSG_HOME_OFFSETS_APPLIED _UxGT("偏移已啟用") //"Offsets applied" #define MSG_SET_ORIGIN _UxGT("設置原點") //"Set origin" @@ -65,6 +64,7 @@ #define MSG_EXTRUDE _UxGT("擠出") //"Extrude" #define MSG_RETRACT _UxGT("回抽") //"Retract" #define MSG_MOVE_AXIS _UxGT("移動軸") //"Move axis" +#define MSG_BED_LEVELING _UxGT("調平熱床") //"Bed leveling" #define MSG_LEVEL_BED _UxGT("調平熱床") //"Level bed" #define MSG_MOVE_X _UxGT("移動X") //"Move X" #define MSG_MOVE_Y _UxGT("移動Y") //"Move Y" diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index e4b1a7463..686ce255e 100755 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -478,9 +478,10 @@ uint16_t max_display_update_time = 0; /** * Show "Moving..." till moves are done, then revert to previous display. */ - inline void lcd_synchronize() { + inline void lcd_synchronize(const char * const msg=NULL) { static bool no_reentry = false; - lcd_implementation_drawmenu_static(LCD_HEIGHT >= 4 ? 1 : 0, PSTR(MSG_MOVING)); + const static char moving[] PROGMEM = MSG_MOVING; + lcd_implementation_drawmenu_static(LCD_HEIGHT >= 4 ? 1 : 0, msg ? msg : moving); if (no_reentry) return; // Make this the current handler till all moves are done @@ -1403,6 +1404,11 @@ void kill_screen(const char* lcd_msg) { #endif + #if ENABLED(EEPROM_SETTINGS) + static void lcd_store_settings() { lcd_completion_feedback(settings.save()); } + static void lcd_load_settings() { lcd_completion_feedback(settings.load()); } + #endif + #if ENABLED(LCD_BED_LEVELING) /** @@ -1467,7 +1473,7 @@ void kill_screen(const char* lcd_msg) { // The last G29 will record but not move if (manual_probe_index == total_probe_points - 1) - enqueue_and_echo_commands_P("G29 V1"); + enqueue_and_echo_commands_P(PSTR("G29 V1")); #endif @@ -1481,13 +1487,15 @@ void kill_screen(const char* lcd_msg) { #if MANUAL_PROBE_HEIGHT > 0 current_position[Z_AXIS] = LOGICAL_Z_POSITION(Z_MIN_POS) + MANUAL_PROBE_HEIGHT; line_to_current(Z_AXIS); - lcd_synchronize(); + #endif + + #if MANUAL_PROBE_HEIGHT > 0 || ENABLED(MESH_BED_LEVELING) + lcd_synchronize(PSTR(MSG_LEVEL_BED_DONE)); #endif // Enable leveling, if needed #if ENABLED(MESH_BED_LEVELING) - lcd_synchronize(); mbl.set_has_mesh(true); mesh_probing_done(); @@ -1607,19 +1615,56 @@ void kill_screen(const char* lcd_msg) { * Step 2: Continue Bed Leveling... */ void _lcd_level_bed_continue() { - defer_return_to_status = true; - axis_homed[X_AXIS] = axis_homed[Y_AXIS] = axis_homed[Z_AXIS] = false; - lcd_goto_screen(_lcd_level_bed_homing); - enqueue_and_echo_commands_P(PSTR("G28")); + defer_return_to_status = true; + axis_homed[X_AXIS] = axis_homed[Y_AXIS] = axis_homed[Z_AXIS] = false; + lcd_goto_screen(_lcd_level_bed_homing); + enqueue_and_echo_commands_P(PSTR("G28")); } + static bool _level_state; + void _lcd_toggle_bed_leveling() { set_bed_leveling_enabled(_level_state); } + void _lcd_set_z_fade_height() { set_z_fade_height(planner.z_fade_height); } + /** - * Step 1: Bed Level entry-point: "Cancel" or "Level Bed" + * Step 1: Bed Level entry-point + * - Cancel + * - Level Bed > + * - Leveling On/Off (if there is leveling data) + * - Fade Height (Req: ENABLE_LEVELING_FADE_HEIGHT) + * - Mesh Z Offset (Req: MESH_BED_LEVELING) + * - Z Probe Offset (Req: HAS_BED_PROBE, Opt: BABYSTEP_ZPROBE_OFFSET) + * - Load Settings (Req: EEPROM_SETTINGS) + * - Save Settings (Req: EEPROM_SETTINGS) */ void lcd_level_bed() { START_MENU(); - MENU_BACK(MSG_LEVEL_BED_CANCEL); + MENU_BACK(MSG_PREPARE); MENU_ITEM(submenu, MSG_LEVEL_BED, _lcd_level_bed_continue); + if (leveling_is_valid()) { // Leveling data exists? Show more options. + _level_state = leveling_is_active(); + MENU_ITEM_EDIT_CALLBACK(bool, MSG_BED_LEVELING, &_level_state, _lcd_toggle_bed_leveling); + } + + #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) + set_z_fade_height(planner.z_fade_height); + MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float62, MSG_Z_FADE_HEIGHT, &planner.z_fade_height, 0.0, 100.0, _lcd_set_z_fade_height); + #endif + + // Manual bed leveling, Bed Z: + #if ENABLED(MESH_BED_LEVELING) + MENU_ITEM_EDIT(float43, MSG_BED_Z, &mbl.z_offset, -1, 1); + #endif + + #if ENABLED(BABYSTEP_ZPROBE_OFFSET) + MENU_ITEM(submenu, MSG_ZPROBE_ZOFFSET, lcd_babystep_zoffset); + #elif HAS_BED_PROBE + MENU_ITEM_EDIT_CALLBACK(float32, MSG_ZPROBE_ZOFFSET, &zprobe_zoffset, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX, lcd_refresh_zprobe_zoffset); + #endif + + #if ENABLED(EEPROM_SETTINGS) + MENU_ITEM(function, MSG_LOAD_EEPROM, lcd_load_settings); + MENU_ITEM(function, MSG_STORE_EEPROM, lcd_store_settings); + #endif END_MENU(); } @@ -2026,7 +2071,7 @@ void kill_screen(const char* lcd_msg) { #if ENABLED(PROBE_MANUALLY) if (!g29_in_progress) #endif - MENU_ITEM(submenu, MSG_LEVEL_BED, lcd_level_bed); + MENU_ITEM(submenu, MSG_BED_LEVELING, lcd_level_bed); #endif #if HAS_M206_COMMAND @@ -2444,11 +2489,6 @@ void kill_screen(const char* lcd_msg) { #endif // HAS_LCD_CONTRAST - #if ENABLED(EEPROM_SETTINGS) - static void lcd_store_settings() { lcd_completion_feedback(settings.save()); } - static void lcd_load_settings() { lcd_completion_feedback(settings.load()); } - #endif - static void lcd_factory_settings() { settings.reset(); lcd_completion_feedback(); @@ -2925,11 +2965,6 @@ void kill_screen(const char* lcd_msg) { MENU_ITEM_EDIT_CALLBACK(float32, MSG_ZPROBE_ZOFFSET, &zprobe_zoffset, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX, lcd_refresh_zprobe_zoffset); #endif - // Manual bed leveling, Bed Z: - #if ENABLED(MESH_BED_LEVELING) && ENABLED(LCD_BED_LEVELING) - MENU_ITEM_EDIT(float43, MSG_BED_Z, &mbl.z_offset, -1, 1); - #endif - // M203 / M205 Feedrate items MENU_ITEM(submenu, MSG_FEEDRATE, lcd_control_motion_feedrate_menu); From 3fe333143cdb2483759aa805a27f0682e539c4fe Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 25 May 2017 20:55:00 -0500 Subject: [PATCH 167/189] Case light as a toggle menu item --- Marlin/language_an.h | 3 +- Marlin/language_bg.h | 109 --------- Marlin/language_ca.h | 3 +- Marlin/language_cz.h | 5 +- Marlin/language_de.h | 4 +- Marlin/language_en.h | 7 +- Marlin/language_es.h | 5 +- Marlin/language_eu.h | 4 +- Marlin/language_fr.h | 3 +- Marlin/language_gl.h | 3 +- Marlin/language_hr.h | 3 +- Marlin/language_it.h | 4 +- Marlin/language_kana.h | 3 +- Marlin/language_kana_utf8.h | 3 +- Marlin/language_nl.h | 3 +- Marlin/language_pl-DOGM.h | 240 +++++++++++++++++++ Marlin/language_pl-HD44780.h | 265 +++++++++++++++++++++ Marlin/language_pl.h | 438 +---------------------------------- Marlin/language_tr.h | 3 +- Marlin/language_uk.h | 3 +- Marlin/ultralcd.cpp | 23 +- 21 files changed, 540 insertions(+), 594 deletions(-) create mode 100644 Marlin/language_pl-DOGM.h create mode 100644 Marlin/language_pl-HD44780.h diff --git a/Marlin/language_an.h b/Marlin/language_an.h index 2aa0a3929..f8b4b468d 100644 --- a/Marlin/language_an.h +++ b/Marlin/language_an.h @@ -193,8 +193,7 @@ #define MSG_INFO_EXTRUDERS _UxGT("Extrusors") #define MSG_INFO_BAUDRATE _UxGT("Baudios") #define MSG_INFO_PROTOCOL _UxGT("Protocolo") -#define MSG_LIGHTS_ON _UxGT("Enchegar luz") -#define MSG_LIGHTS_OFF _UxGT("Desenchegar luz") +#define MSG_CASE_LIGHT _UxGT("Luz") #if LCD_WIDTH >= 20 #define MSG_INFO_PRINT_COUNT _UxGT("Conteo de impresion") diff --git a/Marlin/language_bg.h b/Marlin/language_bg.h index 2370ca5f5..4ab01cb4a 100644 --- a/Marlin/language_bg.h +++ b/Marlin/language_bg.h @@ -36,20 +36,11 @@ #define WELCOME_MSG MACHINE_NAME _UxGT(" Готов.") #define MSG_SD_INSERTED _UxGT("Картата е поставена") #define MSG_SD_REMOVED _UxGT("Картата е извадена") -#define MSG_LCD_ENDSTOPS _UxGT("Endstops") // Max length 8 characters #define MSG_MAIN _UxGT("Меню") #define MSG_AUTOSTART _UxGT("Автостарт") #define MSG_DISABLE_STEPPERS _UxGT("Изкл. двигатели") #define MSG_AUTO_HOME _UxGT("Паркиране") -#define MSG_AUTO_HOME_X _UxGT("Home X") -#define MSG_AUTO_HOME_Y _UxGT("Home Y") -#define MSG_AUTO_HOME_Z _UxGT("Home Z") -#define MSG_LEVEL_BED_HOMING _UxGT("Homing XYZ") -#define MSG_LEVEL_BED_WAITING _UxGT("Click to Begin") -#define MSG_LEVEL_BED_NEXT_POINT _UxGT("Next Point") -#define MSG_LEVEL_BED_DONE _UxGT("Leveling Done!") #define MSG_SET_HOME_OFFSETS _UxGT("Задай Начало") -#define MSG_HOME_OFFSETS_APPLIED _UxGT("Offsets applied") #define MSG_SET_ORIGIN _UxGT("Изходна точка") #define MSG_PREHEAT_1 _UxGT("Подгряване PLA") #define MSG_PREHEAT_1_N _UxGT("Подгряване PLA") @@ -89,21 +80,6 @@ #define MSG_AUTOTEMP _UxGT("Авто-темп.") #define MSG_ON _UxGT("Вкл. ") #define MSG_OFF _UxGT("Изкл. ") -#define MSG_PID_P _UxGT("PID-P") -#define MSG_PID_I _UxGT("PID-I") -#define MSG_PID_D _UxGT("PID-D") -#define MSG_PID_C _UxGT("PID-C") -#define MSG_SELECT _UxGT("Select") -#define MSG_ACC _UxGT("Acc") -#define MSG_JERK _UxGT("Jerk") -#define MSG_VX_JERK _UxGT("Vx-jerk") -#define MSG_VY_JERK _UxGT("Vy-jerk") -#define MSG_VZ_JERK _UxGT("Vz-jerk") -#define MSG_VE_JERK _UxGT("Ve-jerk") -#define MSG_VMAX _UxGT("Vmax ") -#define MSG_VMIN _UxGT("Vmin") -#define MSG_VTRAV_MIN _UxGT("VTrav min") -#define MSG_AMAX _UxGT("Amax ") #define MSG_A_RETRACT _UxGT("A-откат") #define MSG_A_TRAVEL _UxGT("A-travel") #define MSG_STEPS_PER_MM _UxGT("Стъпки/mm") @@ -153,100 +129,15 @@ #define MSG_INIT_SDCARD _UxGT("Иниц. SD-Карта") #define MSG_CNG_SDCARD _UxGT("Смяна SD-Карта") #define MSG_ZPROBE_OUT _UxGT("Z-сондата е извадена") -#define MSG_BLTOUCH_SELFTEST _UxGT("BLTouch Self-Test") -#define MSG_BLTOUCH_RESET _UxGT("Reset BLTouch") -#define MSG_HOME _UxGT("Home") // Used as MSG_HOME " " MSG_X MSG_Y MSG_Z " " MSG_FIRST -#define MSG_FIRST _UxGT("first") #define MSG_ZPROBE_ZOFFSET _UxGT("Z Отстояние") #define MSG_BABYSTEP_X _UxGT("Министъпка X") #define MSG_BABYSTEP_Y _UxGT("Министъпка Y") #define MSG_BABYSTEP_Z _UxGT("Министъпка Z") #define MSG_ENDSTOP_ABORT _UxGT("Стоп Кр.Изключватели") -#define MSG_HEATING_FAILED_LCD _UxGT("Heating failed") -#define MSG_ERR_REDUNDANT_TEMP _UxGT("Err: REDUNDANT TEMP") -#define MSG_THERMAL_RUNAWAY _UxGT("THERMAL RUNAWAY") -#define MSG_ERR_MAXTEMP _UxGT("Err: MAXTEMP") -#define MSG_ERR_MINTEMP _UxGT("Err: MINTEMP") -#define MSG_ERR_MAXTEMP_BED _UxGT("Err: MAXTEMP BED") -#define MSG_ERR_MINTEMP_BED _UxGT("Err: MINTEMP BED") -#define MSG_ERR_Z_HOMING _UxGT("G28 Z Forbidden") -#define MSG_HALTED _UxGT("PRINTER HALTED") -#define MSG_PLEASE_RESET _UxGT("Please reset") -#define MSG_SHORT_DAY _UxGT("d") // One character only -#define MSG_SHORT_HOUR _UxGT("h") // One character only -#define MSG_SHORT_MINUTE _UxGT("m") // One character only -#define MSG_HEATING _UxGT("Heating...") -#define MSG_HEATING_COMPLETE _UxGT("Heating done.") -#define MSG_BED_HEATING _UxGT("Bed Heating.") -#define MSG_BED_DONE _UxGT("Bed done.") #define MSG_DELTA_CALIBRATE _UxGT("Делта Калибровка") #define MSG_DELTA_CALIBRATE_X _UxGT("Калибровка X") #define MSG_DELTA_CALIBRATE_Y _UxGT("Калибровка Y") #define MSG_DELTA_CALIBRATE_Z _UxGT("Калибровка Z") #define MSG_DELTA_CALIBRATE_CENTER _UxGT("Калибровка Център") -#define MSG_INFO_MENU _UxGT("About Printer") -#define MSG_INFO_PRINTER_MENU _UxGT("Printer Info") -#define MSG_INFO_STATS_MENU _UxGT("Printer Stats") -#define MSG_INFO_BOARD_MENU _UxGT("Board Info") -#define MSG_INFO_THERMISTOR_MENU _UxGT("Thermistors") -#define MSG_INFO_EXTRUDERS _UxGT("Extruders") -#define MSG_INFO_BAUDRATE _UxGT("Baud") -#define MSG_INFO_PROTOCOL _UxGT("Protocol") -#define MSG_LIGHTS_ON _UxGT("Case light on") -#define MSG_LIGHTS_OFF _UxGT("Case light off") - -#if LCD_WIDTH >= 20 - #define MSG_INFO_PRINT_COUNT _UxGT("Print Count") - #define MSG_INFO_COMPLETED_PRINTS _UxGT("Completed") - #define MSG_INFO_PRINT_TIME _UxGT("Total print time") - #define MSG_INFO_PRINT_LONGEST _UxGT("Longest job time") - #define MSG_INFO_PRINT_FILAMENT _UxGT("Extruded total") -#else - #define MSG_INFO_PRINT_COUNT _UxGT("Prints") - #define MSG_INFO_COMPLETED_PRINTS _UxGT("Completed") - #define MSG_INFO_PRINT_TIME _UxGT("Total") - #define MSG_INFO_PRINT_LONGEST _UxGT("Longest") - #define MSG_INFO_PRINT_FILAMENT _UxGT("Extruded") -#endif - -#define MSG_INFO_MIN_TEMP _UxGT("Min Temp") -#define MSG_INFO_MAX_TEMP _UxGT("Max Temp") -#define MSG_INFO_PSU _UxGT("Power Supply") - -#define MSG_DRIVE_STRENGTH _UxGT("Drive Strength") -#define MSG_DAC_PERCENT _UxGT("Driver %") -#define MSG_DAC_EEPROM_WRITE _UxGT("DAC EEPROM Write") - -#define MSG_FILAMENT_CHANGE_HEADER _UxGT("PRINT PAUSED") -#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("RESUME OPTIONS:") -#define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("Extrude more") -#define MSG_FILAMENT_CHANGE_OPTION_RESUME _UxGT("Resume print") - -#if LCD_HEIGHT >= 4 - // Up to 3 lines allowed - #define MSG_FILAMENT_CHANGE_INIT_1 _UxGT("Wait for start") - #define MSG_FILAMENT_CHANGE_INIT_2 _UxGT("of the filament") - #define MSG_FILAMENT_CHANGE_INIT_3 _UxGT("change") - #define MSG_FILAMENT_CHANGE_UNLOAD_1 _UxGT("Wait for") - #define MSG_FILAMENT_CHANGE_UNLOAD_2 _UxGT("filament unload") - #define MSG_FILAMENT_CHANGE_INSERT_1 _UxGT("Insert filament") - #define MSG_FILAMENT_CHANGE_INSERT_2 _UxGT("and press button") - #define MSG_FILAMENT_CHANGE_INSERT_3 _UxGT("to continue...") - #define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Wait for") - #define MSG_FILAMENT_CHANGE_LOAD_2 _UxGT("filament load") - #define MSG_FILAMENT_CHANGE_EXTRUDE_1 _UxGT("Wait for") - #define MSG_FILAMENT_CHANGE_EXTRUDE_2 _UxGT("filament extrude") - #define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Wait for print") - #define MSG_FILAMENT_CHANGE_RESUME_2 _UxGT("to resume") -#else // LCD_HEIGHT < 4 - // Up to 2 lines allowed - #define MSG_FILAMENT_CHANGE_INIT_1 _UxGT("Please wait...") - #define MSG_FILAMENT_CHANGE_UNLOAD_1 _UxGT("Ejecting...") - #define MSG_FILAMENT_CHANGE_INSERT_1 _UxGT("Insert and Click") - #define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Loading...") - #define MSG_FILAMENT_CHANGE_EXTRUDE_1 _UxGT("Extruding...") - #define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Resuming...") -#endif // LCD_HEIGHT < 4 - #endif // LANGUAGE_BG_H diff --git a/Marlin/language_ca.h b/Marlin/language_ca.h index 01a48d2b9..9d5991ec0 100644 --- a/Marlin/language_ca.h +++ b/Marlin/language_ca.h @@ -196,8 +196,7 @@ #define MSG_INFO_EXTRUDERS _UxGT("Extrusors") #define MSG_INFO_BAUDRATE _UxGT("Baud") #define MSG_INFO_PROTOCOL _UxGT("Protocol") -#define MSG_LIGHTS_ON _UxGT("Encen el llum") -#define MSG_LIGHTS_OFF _UxGT("Apaga el llum") +#define MSG_CASE_LIGHT _UxGT("Llum") #if LCD_WIDTH >= 20 #define MSG_INFO_PRINT_COUNT _UxGT("Total impressions") diff --git a/Marlin/language_cz.h b/Marlin/language_cz.h index 2ee3310bc..93fd47550 100644 --- a/Marlin/language_cz.h +++ b/Marlin/language_cz.h @@ -205,8 +205,8 @@ #define MSG_INFO_EXTRUDERS _UxGT("Extrudery") #define MSG_INFO_BAUDRATE _UxGT("Rychlost") #define MSG_INFO_PROTOCOL _UxGT("Protokol") -#define MSG_LIGHTS_ON _UxGT("Osvetleni Zap") -#define MSG_LIGHTS_OFF _UxGT("Osvetleni Vyp") +#define MSG_CASE_LIGHT _UxGT("Osvetleni") + #if LCD_WIDTH >= 20 #define MSG_INFO_PRINT_COUNT _UxGT("Pocet tisku") #define MSG_INFO_COMPLETED_PRINTS _UxGT("Dokonceno") @@ -220,6 +220,7 @@ #define MSG_INFO_PRINT_LONGEST _UxGT("Nejdelsi") #define MSG_INFO_PRINT_FILAMENT _UxGT("Vytlaceno") #endif + #define MSG_INFO_MIN_TEMP _UxGT("Teplota min") #define MSG_INFO_MAX_TEMP _UxGT("Teplota max") #define MSG_INFO_PSU _UxGT("Nap. zdroj") diff --git a/Marlin/language_de.h b/Marlin/language_de.h index e5216d005..1a6cb71f4 100644 --- a/Marlin/language_de.h +++ b/Marlin/language_de.h @@ -205,8 +205,7 @@ #define MSG_INFO_EXTRUDERS _UxGT("Extruder") #define MSG_INFO_BAUDRATE _UxGT("Baud") #define MSG_INFO_PROTOCOL _UxGT("Protokoll") -#define MSG_LIGHTS_ON _UxGT("Gehäuse Licht an") -#define MSG_LIGHTS_OFF _UxGT("Gehäuse Licht aus") +#define MSG_CASE_LIGHT _UxGT("Licht") #if LCD_WIDTH >= 20 #define MSG_INFO_PRINT_COUNT _UxGT("Gesamte Drucke") @@ -221,6 +220,7 @@ #define MSG_INFO_PRINT_LONGEST _UxGT("Längster") #define MSG_INFO_PRINT_FILAMENT _UxGT("Extrud.") #endif + #define MSG_INFO_MIN_TEMP _UxGT("Min Temp") #define MSG_INFO_MAX_TEMP _UxGT("Max Temp") #define MSG_INFO_PSU _UxGT("Stromversorgung") diff --git a/Marlin/language_en.h b/Marlin/language_en.h index 9d0958d3a..32690ebde 100644 --- a/Marlin/language_en.h +++ b/Marlin/language_en.h @@ -700,11 +700,8 @@ #ifndef MSG_INFO_PROTOCOL #define MSG_INFO_PROTOCOL _UxGT("Protocol") #endif -#ifndef MSG_LIGHTS_ON - #define MSG_LIGHTS_ON _UxGT("Case light on") -#endif -#ifndef MSG_LIGHTS_OFF - #define MSG_LIGHTS_OFF _UxGT("Case light off") +#ifndef MSG_CASE_LIGHT + #define MSG_CASE_LIGHT _UxGT("Case light") #endif #if LCD_WIDTH >= 20 diff --git a/Marlin/language_es.h b/Marlin/language_es.h index 30ebb1e21..2ea296acd 100644 --- a/Marlin/language_es.h +++ b/Marlin/language_es.h @@ -202,8 +202,8 @@ #define MSG_INFO_EXTRUDERS _UxGT("Extrusores") #define MSG_INFO_BAUDRATE _UxGT("Baudios") #define MSG_INFO_PROTOCOL _UxGT("Protocolo") -#define MSG_LIGHTS_ON _UxGT("Luz cabina ON") -#define MSG_LIGHTS_OFF _UxGT("Luz cabina OFF") +#define MSG_CASE_LIGHT _UxGT("Luz cabina") + #if LCD_WIDTH > 19 #define MSG_INFO_PRINT_COUNT _UxGT("Conteo de impresion") #define MSG_INFO_COMPLETED_PRINTS _UxGT("Completadas") @@ -217,6 +217,7 @@ #define MSG_INFO_PRINT_LONGEST _UxGT("Mas larga") #define MSG_INFO_PRINT_FILAMENT _UxGT("Extrusion") #endif + #define MSG_INFO_MIN_TEMP _UxGT("Temperatura minima") #define MSG_INFO_MAX_TEMP _UxGT("Temperatura maxima") #define MSG_INFO_PSU _UxGT("Fuente de poder") diff --git a/Marlin/language_eu.h b/Marlin/language_eu.h index 64dbd5cae..329621026 100644 --- a/Marlin/language_eu.h +++ b/Marlin/language_eu.h @@ -202,8 +202,8 @@ #define MSG_INFO_EXTRUDERS _UxGT("Estrusoreak") #define MSG_INFO_BAUDRATE _UxGT("Baudioak") #define MSG_INFO_PROTOCOL _UxGT("Protokoloa") -#define MSG_LIGHTS_ON _UxGT("Kabina Argia ON") -#define MSG_LIGHTS_OFF _UxGT("Kabina Argia OFF") +#define MSG_CASE_LIGHT _UxGT("Kabina Argia") + #if LCD_WIDTH > 19 #define MSG_INFO_PRINT_COUNT _UxGT("Inprim. Zenbaketa") #define MSG_INFO_COMPLETED_PRINTS _UxGT("Burututa") diff --git a/Marlin/language_fr.h b/Marlin/language_fr.h index 116f5d8b1..a919eb9b0 100644 --- a/Marlin/language_fr.h +++ b/Marlin/language_fr.h @@ -207,8 +207,7 @@ #define MSG_INFO_EXTRUDERS _UxGT("Extrudeurs") #define MSG_INFO_BAUDRATE _UxGT("Baud") #define MSG_INFO_PROTOCOL _UxGT("Protocole") -#define MSG_LIGHTS_ON _UxGT("Allumer boîtier") -#define MSG_LIGHTS_OFF _UxGT("Eteindre boîtier") +#define MSG_CASE_LIGHT _UxGT("Lumière") #if LCD_WIDTH >= 20 #define MSG_INFO_PRINT_COUNT _UxGT("Nbre impressions") diff --git a/Marlin/language_gl.h b/Marlin/language_gl.h index d6234e5d3..6c86f1183 100644 --- a/Marlin/language_gl.h +++ b/Marlin/language_gl.h @@ -192,8 +192,7 @@ #define MSG_INFO_EXTRUDERS _UxGT("Extrusores") #define MSG_INFO_BAUDRATE _UxGT("Baudios") #define MSG_INFO_PROTOCOL _UxGT("Protocolo") -#define MSG_LIGHTS_ON _UxGT("Acender a luz") -#define MSG_LIGHTS_OFF _UxGT("Apagar a luz") +#define MSG_CASE_LIGHT _UxGT("Luz") #if LCD_WIDTH >= 20 #define MSG_INFO_PRINT_COUNT _UxGT("Total traballos") #define MSG_INFO_COMPLETED_PRINTS _UxGT("Total completos") diff --git a/Marlin/language_hr.h b/Marlin/language_hr.h index 72a4fd0c3..d50b67713 100644 --- a/Marlin/language_hr.h +++ b/Marlin/language_hr.h @@ -191,8 +191,7 @@ #define MSG_INFO_EXTRUDERS _UxGT("Extruderi") #define MSG_INFO_BAUDRATE _UxGT("Baud") #define MSG_INFO_PROTOCOL _UxGT("Protokol") -#define MSG_LIGHTS_ON _UxGT("Upali osvjetljenje") -#define MSG_LIGHTS_OFF _UxGT("Ugasi osvjetljenje") +#define MSG_CASE_LIGHT _UxGT("Osvjetljenje") #if LCD_WIDTH >= 20 #define MSG_INFO_PRINT_COUNT _UxGT("Broj printova") diff --git a/Marlin/language_it.h b/Marlin/language_it.h index 6ff2337fd..b0e8cc9fb 100644 --- a/Marlin/language_it.h +++ b/Marlin/language_it.h @@ -209,8 +209,8 @@ #define MSG_INFO_EXTRUDERS _UxGT("Estrusori") #define MSG_INFO_BAUDRATE _UxGT("Baud") #define MSG_INFO_PROTOCOL _UxGT("Protocollo") -#define MSG_LIGHTS_ON _UxGT("Luci Case on") -#define MSG_LIGHTS_OFF _UxGT("Luci Case off") +#define MSG_CASE_LIGHT _UxGT("Luci Case") + #if LCD_WIDTH >= 20 #define MSG_INFO_PRINT_COUNT _UxGT("Contat. stampa") #define MSG_INFO_COMPLETED_PRINTS _UxGT("Completati") diff --git a/Marlin/language_kana.h b/Marlin/language_kana.h index c8169a265..0d7f37c0a 100644 --- a/Marlin/language_kana.h +++ b/Marlin/language_kana.h @@ -262,8 +262,7 @@ #define MSG_INFO_EXTRUDERS "\xb4\xb8\xbd\xc4\xd9\xb0\xc0\xde\xb0\xbd\xb3" // "エクストルーダースウ" ("Extruders") #define MSG_INFO_BAUDRATE "\xce\xde\xb0\xda\xb0\xc4" // "ボーレート" ("Baud") #define MSG_INFO_PROTOCOL "\xcc\xdf\xdb\xc4\xba\xd9" // "プロトコル" ("Protocol") -#define MSG_LIGHTS_ON "\xb7\xae\xb3\xc0\xb2\xc5\xb2\xbc\xae\xb3\xd2\xb2\x20\xb5\xdd" // "キョウタイナイショウメイ オン" ("Case light on") -#define MSG_LIGHTS_OFF "\xb7\xae\xb3\xc0\xb2\xc5\xb2\xbc\xae\xb3\xd2\xb2\x20\xb5\xcc" // "キョウタイナイショウメイ オフ" ("Case light off") +#define MSG_CASE_LIGHT "\xb7\xae\xb3\xc0\xb2\xc5\xb2\xbc\xae\xb3\xd2\xb2" // "キョウタイナイショウメイ" ("Case light") #define MSG_INFO_PRINT_COUNT "\xcc\xdf\xd8\xdd\xc4\xbd\xb3" // "プリントスウ" ("Print Count") #define MSG_INFO_COMPLETED_PRINTS "\xb6\xdd\xd8\xae\xb3\xbd\xb3" // "カンリョウスウ" ("Completed") #define MSG_INFO_PRINT_TIME "\xcc\xdf\xd8\xdd\xc4\xbc\xde\xb6\xdd\xd9\xb2\xb9\xb2" // "プリントジカンルイケイ" ("Total print time") diff --git a/Marlin/language_kana_utf8.h b/Marlin/language_kana_utf8.h index 874647ad5..5a0378bb9 100644 --- a/Marlin/language_kana_utf8.h +++ b/Marlin/language_kana_utf8.h @@ -192,8 +192,7 @@ #define MSG_INFO_EXTRUDERS _UxGT("エクストルーダースウ") // "Extruders" #define MSG_INFO_BAUDRATE _UxGT("ボーレート") // "Baud" #define MSG_INFO_PROTOCOL _UxGT("プロトコル") // "Protocol" -#define MSG_LIGHTS_ON _UxGT("キョウタイナイショウメイ オン") // "Case light on" -#define MSG_LIGHTS_OFF _UxGT("キョウタイナイショウメイ オフ") // "Case light off" +#define MSG_CASE_LIGHT _UxGT("キョウタイナイショウメイ") // "Case light" #define MSG_INFO_PRINT_COUNT _UxGT("プリントスウ ") // "Print Count" #define MSG_INFO_COMPLETED_PRINTS _UxGT("カンリョウスウ") // "Completed" #define MSG_INFO_PRINT_TIME _UxGT("プリントジカンルイケイ") // "Total print time" diff --git a/Marlin/language_nl.h b/Marlin/language_nl.h index ffb71f69d..27274aaca 100644 --- a/Marlin/language_nl.h +++ b/Marlin/language_nl.h @@ -202,8 +202,7 @@ #define MSG_INFO_MENU _UxGT("Over Printer") #define MSG_INFO_PRINTER_MENU _UxGT("Printer Info") #define MSG_INFO_PROTOCOL _UxGT("Protocol") -#define MSG_LIGHTS_ON _UxGT("Case licht aan") -#define MSG_LIGHTS_OFF _UxGT("Case licht uit") +#define MSG_CASE_LIGHT _UxGT("Case licht") #if LCD_WIDTH >= 20 #define MSG_INFO_PRINT_COUNT _UxGT("Printed Aantal") diff --git a/Marlin/language_pl-DOGM.h b/Marlin/language_pl-DOGM.h new file mode 100644 index 000000000..d93cfa454 --- /dev/null +++ b/Marlin/language_pl-DOGM.h @@ -0,0 +1,240 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (C) 2016 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 . + * + */ + +/** + * Polish for DOGM display - includes accented characters + */ + +#define WELCOME_MSG MACHINE_NAME _UxGT(" gotowy.") +#define MSG_SD_INSERTED _UxGT("Karta włożona") +#define MSG_SD_REMOVED _UxGT("Karta usunięta") +#define MSG_LCD_ENDSTOPS _UxGT("Kranców.") // Max length 8 characters +#define MSG_MAIN _UxGT("Menu główne") +#define MSG_AUTOSTART _UxGT("Autostart") +#define MSG_DISABLE_STEPPERS _UxGT("Wyłącz silniki") +#define MSG_AUTO_HOME _UxGT("Pozycja zerowa") +#define MSG_AUTO_HOME_X _UxGT("Zeruj X") +#define MSG_AUTO_HOME_Y _UxGT("Zeruj Y") +#define MSG_AUTO_HOME_Z _UxGT("Zeruj Z") +#define MSG_LEVEL_BED _UxGT("Poziom. stołu") +#define MSG_LEVEL_BED_HOMING _UxGT("Pozycja zerowa") +#define MSG_LEVEL_BED_WAITING _UxGT("Kliknij by rozp.") +#define MSG_LEVEL_BED_NEXT_POINT _UxGT("Następny punkt") +#define MSG_LEVEL_BED_DONE _UxGT("Wypoziomowano!") +#define MSG_SET_HOME_OFFSETS _UxGT("Ust. poz. zer.") +#define MSG_HOME_OFFSETS_APPLIED _UxGT("Poz. zerowa ust.") +#define MSG_SET_ORIGIN _UxGT("Ustaw punkt zero") +#define MSG_PREHEAT_1 _UxGT("Rozgrzej PLA") +#define MSG_PREHEAT_1_N MSG_PREHEAT_1 _UxGT(" ") +#define MSG_PREHEAT_1_ALL MSG_PREHEAT_1 _UxGT(" wsz.") +#define MSG_PREHEAT_1_BEDONLY _UxGT("Rozgrzej stół PLA") +#define MSG_PREHEAT_1_SETTINGS _UxGT("Ustaw. rozg. PLA") +#define MSG_PREHEAT_2 _UxGT("Rozgrzej ABS") +#define MSG_PREHEAT_2_N MSG_PREHEAT_2 _UxGT(" ") +#define MSG_PREHEAT_2_ALL MSG_PREHEAT_2 _UxGT(" wsz.") +#define MSG_PREHEAT_2_BEDONLY _UxGT("Rozgrzej stół ABS") +#define MSG_PREHEAT_2_SETTINGS _UxGT("Ustaw. rozg. ABS") +#define MSG_COOLDOWN _UxGT("Chłodzenie") +#define MSG_SWITCH_PS_ON _UxGT("Włącz zasilacz") +#define MSG_SWITCH_PS_OFF _UxGT("Wyłącz zasilacz") +#define MSG_EXTRUDE _UxGT("Ekstruzja") +#define MSG_RETRACT _UxGT("Wycofanie") +#define MSG_MOVE_AXIS _UxGT("Ruch osi") +#define MSG_BED_LEVELING _UxGT("Poziom. stołu") +#define MSG_MOVE_X _UxGT("Przesuń w X") +#define MSG_MOVE_Y _UxGT("Przesuń w Y") +#define MSG_MOVE_Z _UxGT("Przesuń w Z") +#define MSG_MOVE_E _UxGT("Ekstruzja (os E)") +#define MSG_MOVE_01MM _UxGT("Przesuń co .1mm") +#define MSG_MOVE_1MM _UxGT("Przesuń co 1mm") +#define MSG_MOVE_10MM _UxGT("Przesuń co 10mm") +#define MSG_SPEED _UxGT("Predkość") +#define MSG_BED_Z _UxGT("Stół Z") +#define MSG_NOZZLE _UxGT("Dysza") +#define MSG_BED _UxGT("Stół") +#define MSG_FAN_SPEED _UxGT("Obroty wiatraka") +#define MSG_FLOW _UxGT("Przepływ") +#define MSG_CONTROL _UxGT("Ustawienia") +#define MSG_MIN LCD_STR_THERMOMETER _UxGT(" Min") +#define MSG_MAX LCD_STR_THERMOMETER _UxGT(" Max") +#define MSG_FACTOR LCD_STR_THERMOMETER _UxGT(" Mnożnik") +#define MSG_AUTOTEMP _UxGT("Auto. temperatura") +#define MSG_ON _UxGT("Wł. ") +#define MSG_OFF _UxGT("Wył.") +#define MSG_PID_P _UxGT("PID-P") +#define MSG_PID_I _UxGT("PID-I") +#define MSG_PID_D _UxGT("PID-D") +#define MSG_PID_C _UxGT("PID-C") +#define MSG_SELECT _UxGT("Select") +#define MSG_ACC _UxGT("Przyśpieszenie") +#define MSG_JERK _UxGT("Zryw") +#define MSG_VX_JERK _UxGT("Zryw Vx") +#define MSG_VY_JERK _UxGT("Zryw Vy") +#define MSG_VZ_JERK _UxGT("Zryw Vz") +#define MSG_VE_JERK _UxGT("Zryw Ve") +#define MSG_VMAX _UxGT("Vmax ") +#define MSG_VMIN _UxGT("Vmin") +#define MSG_VTRAV_MIN _UxGT("Vskok min") +#define MSG_ACCELERATION MSG_ACC +#define MSG_AMAX _UxGT("Amax") +#define MSG_A_RETRACT _UxGT("A-wycofanie") +#define MSG_A_TRAVEL _UxGT("A-przesuń.") +#define MSG_STEPS_PER_MM _UxGT("kroki/mm") +#define MSG_XSTEPS _UxGT("krokiX/mm") +#define MSG_YSTEPS _UxGT("krokiY/mm") +#define MSG_ZSTEPS _UxGT("krokiZ/mm") +#define MSG_ESTEPS _UxGT("krokiE/mm") +#define MSG_E1STEPS _UxGT("krokiE1/mm") +#define MSG_E2STEPS _UxGT("krokiE2/mm") +#define MSG_E3STEPS _UxGT("krokiE3/mm") +#define MSG_E4STEPS _UxGT("krokiE4/mm") +#define MSG_E5STEPS _UxGT("krokiE5/mm") +#define MSG_TEMPERATURE _UxGT("Temperatura") +#define MSG_MOTION _UxGT("Ruch") +#define MSG_FILAMENT _UxGT("Filament") +#define MSG_VOLUMETRIC_ENABLED _UxGT("E w mm3") +#define MSG_FILAMENT_DIAM _UxGT("Śr. fil.") +#define MSG_CONTRAST _UxGT("Kontrast LCD") +#define MSG_STORE_EEPROM _UxGT("Zapisz w pamięci") +#define MSG_LOAD_EEPROM _UxGT("Wczytaj z pamięci") +#define MSG_RESTORE_FAILSAFE _UxGT("Ustaw. fabryczne") +#define MSG_REFRESH _UxGT("Odswież") +#define MSG_WATCH _UxGT("Ekran główny") +#define MSG_PREPARE _UxGT("Przygotuj") +#define MSG_TUNE _UxGT("Strojenie") +#define MSG_PAUSE_PRINT _UxGT("Pauza") +#define MSG_RESUME_PRINT _UxGT("Wznowienie") +#define MSG_STOP_PRINT _UxGT("Stop") +#define MSG_CARD_MENU _UxGT("Karta SD") +#define MSG_NO_CARD _UxGT("Brak karty") +#define MSG_DWELL _UxGT("Uśpij...") +#define MSG_USERWAIT _UxGT("Oczekiwanie...") +#define MSG_RESUMING _UxGT("Wznawianie druku") +#define MSG_PRINT_ABORTED _UxGT("Druk przerwany") +#define MSG_NO_MOVE _UxGT("Brak ruchu") +#define MSG_KILLED _UxGT("Ubity. ") +#define MSG_STOPPED _UxGT("Zatrzymany. ") +#define MSG_CONTROL_RETRACT _UxGT("Wycofaj mm") +#define MSG_CONTROL_RETRACT_SWAP _UxGT("Z Wycof. mm") +#define MSG_CONTROL_RETRACTF _UxGT("Wycofaj V") +#define MSG_CONTROL_RETRACT_ZLIFT _UxGT("Skok Z mm") +#define MSG_CONTROL_RETRACT_RECOVER _UxGT("Cof. wycof. mm") +#define MSG_CONTROL_RETRACT_RECOVER_SWAP _UxGT("Z Cof. wyc. mm") +#define MSG_CONTROL_RETRACT_RECOVERF _UxGT("Cof. wycof. V") +#define MSG_AUTORETRACT _UxGT("Auto. wycofanie") +#define MSG_FILAMENTCHANGE _UxGT("Zmień filament") +#define MSG_INIT_SDCARD _UxGT("Inicjal. karty SD") +#define MSG_CNG_SDCARD _UxGT("Zmiana karty SD") +#define MSG_ZPROBE_OUT _UxGT("Sonda Z za stołem") +#define MSG_BLTOUCH_SELFTEST _UxGT("BLTouch Self-Test") +#define MSG_BLTOUCH_RESET _UxGT("Reset BLTouch") +#define MSG_HOME _UxGT("Home") // Used as MSG_HOME " " MSG_X MSG_Y MSG_Z " " MSG_FIRST +#define MSG_FIRST _UxGT("first") +#define MSG_ZPROBE_ZOFFSET _UxGT("Offset Z") +#define MSG_BABYSTEP_X _UxGT("Babystep X") +#define MSG_BABYSTEP_Y _UxGT("Babystep Y") +#define MSG_BABYSTEP_Z _UxGT("Babystep Z") +#define MSG_ENDSTOP_ABORT _UxGT("Błąd krańcówki") +#define MSG_HEATING_FAILED_LCD _UxGT("Rozgrz. nieudane") +#define MSG_ERR_REDUNDANT_TEMP _UxGT("Błąd temperatury") +#define MSG_THERMAL_RUNAWAY _UxGT("Zanik temp.") +#define MSG_ERR_MAXTEMP _UxGT("Err max temp") +#define MSG_ERR_MINTEMP _UxGT("Err min temp") +#define MSG_ERR_MAXTEMP_BED _UxGT("Err max temp stołu") +#define MSG_ERR_MINTEMP_BED _UxGT("Err min temp stołu") +#define MSG_ERR_Z_HOMING _UxGT("G28 Z Forbidden") +#define MSG_HALTED _UxGT("Drukarka zatrzym.") +#define MSG_PLEASE_RESET _UxGT("Proszę zresetować") +#define MSG_SHORT_DAY _UxGT("d") // One character only +#define MSG_SHORT_HOUR _UxGT("g") // One character only +#define MSG_SHORT_MINUTE _UxGT("m") // One character only +#define MSG_HEATING _UxGT("Rozgrzewanie...") +#define MSG_HEATING_COMPLETE _UxGT("Rozgrzano") +#define MSG_BED_HEATING _UxGT("Rozgrzewanie stołu...") +#define MSG_BED_DONE _UxGT("Rozgrzano stół") +#define MSG_DELTA_CALIBRATE _UxGT("Kalibrowanie Delty") +#define MSG_DELTA_CALIBRATE_X _UxGT("Kalibruj X") +#define MSG_DELTA_CALIBRATE_Y _UxGT("Kalibruj Y") +#define MSG_DELTA_CALIBRATE_Z _UxGT("Kalibruj Z") +#define MSG_DELTA_CALIBRATE_CENTER _UxGT("Kalibruj środek") + +#define MSG_INFO_MENU _UxGT("O drukarce") +#define MSG_INFO_PRINTER_MENU _UxGT("Info drukarki") +#define MSG_INFO_STATS_MENU _UxGT("Statystyki") +#define MSG_INFO_BOARD_MENU _UxGT("Board Info") +#define MSG_INFO_THERMISTOR_MENU _UxGT("Thermistory") +#define MSG_INFO_EXTRUDERS _UxGT("Ekstrudery") +#define MSG_INFO_BAUDRATE _UxGT("Predkość USB") +#define MSG_INFO_PROTOCOL _UxGT("Protokół") +#define MSG_CASE_LIGHT _UxGT("Oświetlenie") + +#if LCD_WIDTH >= 20 + #define MSG_INFO_PRINT_COUNT _UxGT("Wydrukowano") + #define MSG_INFO_COMPLETED_PRINTS _UxGT("Ukończono") + #define MSG_INFO_PRINT_TIME _UxGT("Czas druku") + #define MSG_INFO_PRINT_LONGEST _UxGT("Najdł. druk") + #define MSG_INFO_PRINT_FILAMENT _UxGT("Użyty fil.") +#else + #define MSG_INFO_PRINT_COUNT _UxGT("Wydrukowano") + #define MSG_INFO_COMPLETED_PRINTS _UxGT("Ukończono") + #define MSG_INFO_PRINT_TIME _UxGT("Razem") + #define MSG_INFO_PRINT_LONGEST _UxGT("Najdł. druk") + #define MSG_INFO_PRINT_FILAMENT _UxGT("Użyty fil.") +#endif + +#define MSG_INFO_MIN_TEMP _UxGT("Min Temp") +#define MSG_INFO_MAX_TEMP _UxGT("Max Temp") +#define MSG_INFO_PSU _UxGT("Zasilacz") + +#define MSG_DRIVE_STRENGTH _UxGT("Siła silnika") +#define MSG_DAC_PERCENT _UxGT("Siła %") +#define MSG_DAC_EEPROM_WRITE _UxGT("Zapisz DAC EEPROM") + +#define MSG_FILAMENT_CHANGE_HEADER _UxGT("ZMIEŃ FILAMENT") +#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("ZMIEŃ OPCJE:") +#define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("Ekstruduj więcej") +#define MSG_FILAMENT_CHANGE_OPTION_RESUME _UxGT("Wznów drukowanie") + +#if LCD_HEIGHT >= 4 + // Up to 3 lines allowed + #define MSG_FILAMENT_CHANGE_INIT_1 _UxGT("Czekam na ") + #define MSG_FILAMENT_CHANGE_INIT_2 _UxGT("zmianę filamentu") + #define MSG_FILAMENT_CHANGE_UNLOAD_1 _UxGT("Czekam na") + #define MSG_FILAMENT_CHANGE_UNLOAD_2 _UxGT("wyjęcie filamentu") + #define MSG_FILAMENT_CHANGE_INSERT_1 _UxGT("Włóz filament") + #define MSG_FILAMENT_CHANGE_INSERT_2 _UxGT("i naciśnij przycisk") + #define MSG_FILAMENT_CHANGE_INSERT_3 _UxGT("aby kontynuować...") + #define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Czekam na") + #define MSG_FILAMENT_CHANGE_LOAD_2 _UxGT("włożenie filamentu") + #define MSG_FILAMENT_CHANGE_EXTRUDE_1 _UxGT("Czekam na") + #define MSG_FILAMENT_CHANGE_EXTRUDE_2 _UxGT("ekstruzję filamentu") + #define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Czekam na") + #define MSG_FILAMENT_CHANGE_RESUME_2 _UxGT("wznowienie druku") +#else // LCD_HEIGHT < 4 + // Up to 2 lines allowed + #define MSG_FILAMENT_CHANGE_INIT_1 _UxGT("Proszę czekać...") + #define MSG_FILAMENT_CHANGE_UNLOAD_1 _UxGT("Wysuwanie...") + #define MSG_FILAMENT_CHANGE_INSERT_1 _UxGT("Włóż i naciśnij prz.") + #define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Ładowanie...") + #define MSG_FILAMENT_CHANGE_EXTRUDE_1 _UxGT("Ekstruzja...") + #define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Wznowienie...") +#endif // LCD_HEIGHT < 4 diff --git a/Marlin/language_pl-HD44780.h b/Marlin/language_pl-HD44780.h new file mode 100644 index 000000000..7c5ea0838 --- /dev/null +++ b/Marlin/language_pl-HD44780.h @@ -0,0 +1,265 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (C) 2016 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 . + * + */ + +/** + * Polish for HD44780 display - no accented characters + */ + +#define WELCOME_MSG MACHINE_NAME _UxGT(" gotowy.") +#define MSG_SD_INSERTED _UxGT("Karta wlozona") +#define MSG_SD_REMOVED _UxGT("Karta usunieta") +#define MSG_LCD_ENDSTOPS _UxGT("Krancow.") // Max length 8 characters +#define MSG_MAIN _UxGT("Menu glowne") +#define MSG_AUTOSTART _UxGT("Autostart") +#define MSG_DISABLE_STEPPERS _UxGT("Wylacz silniki") +#define MSG_AUTO_HOME _UxGT("Pozycja zerowa") +#define MSG_AUTO_HOME_X _UxGT("Zeruj X") +#define MSG_AUTO_HOME_Y _UxGT("Zeruj Y") +#define MSG_AUTO_HOME_Z _UxGT("Zeruj Z") +#define MSG_LEVEL_BED _UxGT("Poziom. stolu") +#define MSG_LEVEL_BED_HOMING _UxGT("Pozycja zerowa") +#define MSG_LEVEL_BED_WAITING _UxGT("Kliknij by rozp.") +#define MSG_LEVEL_BED_NEXT_POINT _UxGT("Nastepny punkt") +#define MSG_LEVEL_BED_DONE _UxGT("Wypoziomowano!") +#define MSG_SET_HOME_OFFSETS _UxGT("Ust. poz. zer.") +#define MSG_HOME_OFFSETS_APPLIED _UxGT("Poz. zerowa ust.") +#define MSG_SET_ORIGIN _UxGT("Ustaw punkt zero") +#define MSG_PREHEAT_1 _UxGT("Rozgrzej PLA") +#define MSG_PREHEAT_1_N MSG_PREHEAT_1 _UxGT(" ") +#define MSG_PREHEAT_1_ALL MSG_PREHEAT_1 _UxGT(" wsz.") +#define MSG_PREHEAT_1_BEDONLY _UxGT("Rozgrzej stol PLA") +#define MSG_PREHEAT_1_SETTINGS _UxGT("Ustaw. rozg. PLA") +#define MSG_PREHEAT_2 _UxGT("Rozgrzej ABS") +#define MSG_PREHEAT_2_N MSG_PREHEAT_2 _UxGT(" ") +#define MSG_PREHEAT_2_ALL MSG_PREHEAT_2 _UxGT(" wsz.") +#define MSG_PREHEAT_2_BEDONLY _UxGT("Rozgrzej stol ABS") +#define MSG_PREHEAT_2_SETTINGS _UxGT("Ustaw. rozg. ABS") +#define MSG_COOLDOWN _UxGT("Chlodzenie") +#define MSG_SWITCH_PS_ON _UxGT("Wlacz zasilacz") +#define MSG_SWITCH_PS_OFF _UxGT("Wylacz zasilacz") +#define MSG_EXTRUDE _UxGT("Ekstruzja") +#define MSG_RETRACT _UxGT("Wycofanie") +#define MSG_MOVE_AXIS _UxGT("Ruch osi") +#define MSG_BED_LEVELING _UxGT("Poziom. stolu") +#define MSG_MOVE_X _UxGT("Przesun w X") +#define MSG_MOVE_Y _UxGT("Przesun w Y") +#define MSG_MOVE_Z _UxGT("Przesun w Z") +#define MSG_MOVE_E _UxGT("Ekstruzja (os E)") +#define MSG_MOVE_01MM _UxGT("Przesun co .1mm") +#define MSG_MOVE_1MM _UxGT("Przesun co 1mm") +#define MSG_MOVE_10MM _UxGT("Przesun co 10mm") +#define MSG_SPEED _UxGT("Predkosc") +#define MSG_BED_Z _UxGT("Stol Z") +#define MSG_NOZZLE _UxGT("Dysza") +#define MSG_BED _UxGT("Stol") +#define MSG_FAN_SPEED _UxGT("Obroty wiatraka") +#define MSG_FLOW _UxGT("Przeplyw") +#define MSG_CONTROL _UxGT("Ustawienia") +#define MSG_MIN LCD_STR_THERMOMETER _UxGT(" Min") +#define MSG_MAX LCD_STR_THERMOMETER _UxGT(" Max") +#define MSG_FACTOR LCD_STR_THERMOMETER _UxGT(" Mnoznik") +#define MSG_AUTOTEMP _UxGT("Auto. temperatura") +#define MSG_ON _UxGT("Wl. ") +#define MSG_OFF _UxGT("Wyl.") +#define MSG_PID_P _UxGT("PID-P") +#define MSG_PID_I _UxGT("PID-I") +#define MSG_PID_D _UxGT("PID-D") +#define MSG_PID_C _UxGT("PID-C") +#define MSG_SELECT _UxGT("Select") +#define MSG_ACC _UxGT("Przyspieszenie") +#define MSG_JERK _UxGT("Zryw") +#define MSG_VX_JERK _UxGT("Zryw Vx") +#define MSG_VY_JERK _UxGT("Zryw Vy") +#define MSG_VZ_JERK _UxGT("Zryw Vz") +#define MSG_VE_JERK _UxGT("Zryw Ve") +#define MSG_VMAX _UxGT("Vmax ") +#define MSG_VMIN _UxGT("Vmin") +#define MSG_VTRAV_MIN _UxGT("Vskok min") +#define MSG_ACCELERATION MSG_ACC +#define MSG_AMAX _UxGT("Amax") +#define MSG_A_RETRACT _UxGT("A-wycofanie") +#define MSG_A_TRAVEL _UxGT("A-przesun.") +#define MSG_STEPS_PER_MM _UxGT("kroki/mm") +#define MSG_XSTEPS _UxGT("krokiX/mm") +#define MSG_YSTEPS _UxGT("krokiY/mm") +#define MSG_ZSTEPS _UxGT("krokiZ/mm") +#define MSG_ESTEPS _UxGT("krokiE/mm") +#define MSG_E1STEPS _UxGT("krokiE1/mm") +#define MSG_E2STEPS _UxGT("krokiE2/mm") +#define MSG_E3STEPS _UxGT("krokiE3/mm") +#define MSG_E4STEPS _UxGT("krokiE4/mm") +#define MSG_E5STEPS _UxGT("krokiE5/mm") +#define MSG_TEMPERATURE _UxGT("Temperatura") +#define MSG_MOTION _UxGT("Ruch") +#define MSG_FILAMENT _UxGT("Filament") +#define MSG_VOLUMETRIC_ENABLED _UxGT("E w mm3") +#define MSG_FILAMENT_DIAM _UxGT("Sr. fil.") +#define MSG_CONTRAST _UxGT("Kontrast LCD") +#define MSG_STORE_EEPROM _UxGT("Zapisz w pamieci") +#define MSG_LOAD_EEPROM _UxGT("Wczytaj z pamieci") +#define MSG_RESTORE_FAILSAFE _UxGT("Ustaw. fabryczne") +#define MSG_REFRESH _UxGT("Odswiez") +#define MSG_WATCH _UxGT("Ekran glowny") +#define MSG_PREPARE _UxGT("Przygotuj") +#define MSG_TUNE _UxGT("Strojenie") +#define MSG_PAUSE_PRINT _UxGT("Pauza") +#define MSG_RESUME_PRINT _UxGT("Wznowienie") +#define MSG_STOP_PRINT _UxGT("Stop") +#define MSG_CARD_MENU _UxGT("Karta SD") +#define MSG_NO_CARD _UxGT("Brak karty") +#define MSG_DWELL _UxGT("Uspij...") +#define MSG_USERWAIT _UxGT("Oczekiwanie...") +#define MSG_RESUMING _UxGT("Wznawianie druku") +#define MSG_PRINT_ABORTED _UxGT("Druk przerwany") +#define MSG_NO_MOVE _UxGT("Brak ruchu") +#define MSG_KILLED _UxGT("Ubity. ") +#define MSG_STOPPED _UxGT("Zatrzymany. ") +#define MSG_CONTROL_RETRACT _UxGT("Wycofaj mm") +#define MSG_CONTROL_RETRACT_SWAP _UxGT("Z Wycof. mm") +#define MSG_CONTROL_RETRACTF _UxGT("Wycofaj V") +#define MSG_CONTROL_RETRACT_ZLIFT _UxGT("Skok Z mm") +#define MSG_CONTROL_RETRACT_RECOVER _UxGT("Cof. wycof. mm") +#define MSG_CONTROL_RETRACT_RECOVER_SWAP _UxGT("Z Cof. wyc. mm") +#define MSG_CONTROL_RETRACT_RECOVERF _UxGT("Cof. wycof. V") +#define MSG_AUTORETRACT _UxGT("Auto. wycofanie") +#define MSG_FILAMENTCHANGE _UxGT("Zmien filament") +#define MSG_INIT_SDCARD _UxGT("Inicjal. karty SD") +#define MSG_CNG_SDCARD _UxGT("Zmiana karty SD") +#define MSG_ZPROBE_OUT _UxGT("Sonda Z za stolem") +#define MSG_BLTOUCH_SELFTEST _UxGT("BLTouch Self-Test") +#define MSG_BLTOUCH_RESET _UxGT("Reset BLTouch") +#define MSG_HOME _UxGT("Home") // Used as MSG_HOME " " MSG_X MSG_Y MSG_Z " " MSG_FIRST +#define MSG_FIRST _UxGT("first") +#define MSG_ZPROBE_ZOFFSET _UxGT("Offset Z") +#define MSG_BABYSTEP_X _UxGT("Babystep X") +#define MSG_BABYSTEP_Y _UxGT("Babystep Y") +#define MSG_BABYSTEP_Z _UxGT("Babystep Z") +#define MSG_ENDSTOP_ABORT _UxGT("Blad krancowki") +#define MSG_HEATING_FAILED_LCD _UxGT("Rozgrz. nieudane") +#define MSG_ERR_REDUNDANT_TEMP _UxGT("Blad temperatury") +#define MSG_THERMAL_RUNAWAY _UxGT("Zanik temp.") +#define MSG_ERR_MAXTEMP _UxGT("Err max temp") +#define MSG_ERR_MINTEMP _UxGT("Err min temp") +#define MSG_ERR_MAXTEMP_BED _UxGT("Err max temp stolu") +#define MSG_ERR_MINTEMP_BED _UxGT("Err min temp stolu") +#define MSG_ERR_Z_HOMING _UxGT("G28 Z Forbidden") +#define MSG_HALTED _UxGT("Drukarka zatrzym.") +#define MSG_PLEASE_RESET _UxGT("Prosze zresetowac") +#define MSG_SHORT_DAY _UxGT("d") // One character only +#define MSG_SHORT_HOUR _UxGT("g") // One character only +#define MSG_SHORT_MINUTE _UxGT("m") // One character only +#define MSG_HEATING _UxGT("Rozgrzewanie...") +#define MSG_HEATING_COMPLETE _UxGT("Rozgrzano") +#define MSG_BED_HEATING _UxGT("Rozgrzewanie stolu...") +#define MSG_BED_DONE _UxGT("Rozgrzano stol") +#define MSG_DELTA_CALIBRATE _UxGT("Kalibrowanie Delty") +#define MSG_DELTA_CALIBRATE_X _UxGT("Kalibruj X") +#define MSG_DELTA_CALIBRATE_Y _UxGT("Kalibruj Y") +#define MSG_DELTA_CALIBRATE_Z _UxGT("Kalibruj Z") +#define MSG_DELTA_CALIBRATE_CENTER _UxGT("Kalibruj srodek") + +#define MSG_INFO_MENU _UxGT("O drukarce") +#define MSG_INFO_PRINTER_MENU _UxGT("Info drukarki") +#define MSG_INFO_STATS_MENU _UxGT("Statystyki") +#define MSG_INFO_BOARD_MENU _UxGT("Board Info") +#define MSG_INFO_THERMISTOR_MENU _UxGT("Thermistory") +#define MSG_INFO_EXTRUDERS _UxGT("Ekstrudery") +#define MSG_INFO_BAUDRATE _UxGT("Predkosc USB") +#define MSG_INFO_PROTOCOL _UxGT("Protokol") +#define MSG_CASE_LIGHT _UxGT("Oswietlenie") + +#if LCD_WIDTH >= 20 + #define MSG_INFO_PRINT_COUNT _UxGT("Wydrukowano") + #define MSG_INFO_COMPLETED_PRINTS _UxGT("Ukonczono") + #define MSG_INFO_PRINT_TIME _UxGT("Czas druku") + #define MSG_INFO_PRINT_LONGEST _UxGT("Najdl. druk") + #define MSG_INFO_PRINT_FILAMENT _UxGT("Uzyty fil.") +#else + #define MSG_INFO_PRINT_COUNT _UxGT("Wydrukowano") + #define MSG_INFO_COMPLETED_PRINTS _UxGT("Ukonczono") + #define MSG_INFO_PRINT_TIME _UxGT("Razem") + #define MSG_INFO_PRINT_LONGEST _UxGT("Najdl. druk") + #define MSG_INFO_PRINT_FILAMENT _UxGT("Uzyty fil.") +#endif + +#define MSG_INFO_MIN_TEMP _UxGT("Min Temp") +#define MSG_INFO_MAX_TEMP _UxGT("Max Temp") +#define MSG_INFO_PSU _UxGT("Zasilacz") + +#define MSG_DRIVE_STRENGTH _UxGT("Sila silnika") +#define MSG_DAC_PERCENT _UxGT("Sila %") +#define MSG_DAC_EEPROM_WRITE _UxGT("Zapisz DAC EEPROM") + +#define MSG_FILAMENT_CHANGE_HEADER _UxGT("ZMIEN FILAMENT") +#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("ZMIEN OPCJE:") +#define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("Ekstruduj wiecej") +#define MSG_FILAMENT_CHANGE_OPTION_RESUME _UxGT("Wznow drukowanie") + +#if LCD_HEIGHT >= 4 + // Up to 3 lines allowed + #define MSG_FILAMENT_CHANGE_INIT_1 _UxGT("Czekam na ") + #define MSG_FILAMENT_CHANGE_INIT_2 _UxGT("zmiane filamentu") + #define MSG_FILAMENT_CHANGE_UNLOAD_1 _UxGT("Czekam na") + #define MSG_FILAMENT_CHANGE_UNLOAD_2 _UxGT("wyjecie filamentu") + #define MSG_FILAMENT_CHANGE_INSERT_1 _UxGT("Wloz filament") + #define MSG_FILAMENT_CHANGE_INSERT_2 _UxGT("i nacisnij przycisk") + #define MSG_FILAMENT_CHANGE_INSERT_3 _UxGT("aby kontynuowac...") + #define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Czekam na") + #define MSG_FILAMENT_CHANGE_LOAD_2 _UxGT("wlozenie filamentu") + #define MSG_FILAMENT_CHANGE_EXTRUDE_1 _UxGT("Czekam na") + #define MSG_FILAMENT_CHANGE_EXTRUDE_2 _UxGT("ekstruzje filamentu") + #define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Czekam na") + #define MSG_FILAMENT_CHANGE_RESUME_2 _UxGT("wznowienie druku") +#else // LCD_HEIGHT < 4 + // Up to 2 lines allowed + #define MSG_FILAMENT_CHANGE_INIT_1 _UxGT("Prosze czekac...") + #define MSG_FILAMENT_CHANGE_UNLOAD_1 _UxGT("Wysuwanie...") + #define MSG_FILAMENT_CHANGE_INSERT_1 _UxGT("Wloz i nacisnij prz.") + #define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Ladowanie...") + #define MSG_FILAMENT_CHANGE_EXTRUDE_1 _UxGT("Ekstruzja...") + #define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Wznowienie...") +#endif // LCD_HEIGHT < 4 + +#if LCD_HEIGHT >= 4 + // Up to 3 lines allowed + #define MSG_FILAMENT_CHANGE_INIT_1 _UxGT("Czekam na ") + #define MSG_FILAMENT_CHANGE_INIT_2 _UxGT("zmiane filamentu") + #define MSG_FILAMENT_CHANGE_UNLOAD_1 _UxGT("Czekam na") + #define MSG_FILAMENT_CHANGE_UNLOAD_2 _UxGT("wyjecie filamentu") + #define MSG_FILAMENT_CHANGE_INSERT_1 _UxGT("Wloz filament") + #define MSG_FILAMENT_CHANGE_INSERT_2 _UxGT("i nacisnij przycisk") + #define MSG_FILAMENT_CHANGE_INSERT_3 _UxGT("aby kontynuowac...") + #define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Czekam na") + #define MSG_FILAMENT_CHANGE_LOAD_2 _UxGT("wlozenie filamentu") + #define MSG_FILAMENT_CHANGE_EXTRUDE_1 _UxGT("Czekam na") + #define MSG_FILAMENT_CHANGE_EXTRUDE_2 _UxGT("ekstruzje filamentu") + #define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Czekam na") + #define MSG_FILAMENT_CHANGE_RESUME_2 _UxGT("wznowienie druku") +#else // LCD_HEIGHT < 4 + // Up to 2 lines allowed + #define MSG_FILAMENT_CHANGE_INIT_1 _UxGT("Prosze czekac...") + #define MSG_FILAMENT_CHANGE_UNLOAD_1 _UxGT("Wysuwanie...") + #define MSG_FILAMENT_CHANGE_INSERT_1 _UxGT("Wloz i nacisnij prz.") + #define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Ladowanie...") + #define MSG_FILAMENT_CHANGE_EXTRUDE_1 _UxGT("Ekstruzja...") + #define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Wznowienie...") +#endif // LCD_HEIGHT < 4 diff --git a/Marlin/language_pl.h b/Marlin/language_pl.h index 2794a1723..f4d1fbe4b 100644 --- a/Marlin/language_pl.h +++ b/Marlin/language_pl.h @@ -33,441 +33,13 @@ #define DISPLAY_CHARSET_ISO10646_PL #define MAPPER_C3C4C5_PL +/** + * One version with accented characters and one without + */ #if ENABLED(DOGLCD) - -#define WELCOME_MSG MACHINE_NAME _UxGT(" gotowy.") -#define MSG_SD_INSERTED _UxGT("Karta włożona") -#define MSG_SD_REMOVED _UxGT("Karta usunięta") -#define MSG_LCD_ENDSTOPS _UxGT("Kranców.") // Max length 8 characters -#define MSG_MAIN _UxGT("Menu główne") -#define MSG_AUTOSTART _UxGT("Autostart") -#define MSG_DISABLE_STEPPERS _UxGT("Wyłącz silniki") -#define MSG_AUTO_HOME _UxGT("Pozycja zerowa") -#define MSG_AUTO_HOME_X _UxGT("Zeruj X") -#define MSG_AUTO_HOME_Y _UxGT("Zeruj Y") -#define MSG_AUTO_HOME_Z _UxGT("Zeruj Z") -#define MSG_LEVEL_BED_HOMING _UxGT("Pozycja zerowa") -#define MSG_LEVEL_BED_WAITING _UxGT("Kliknij by rozp.") -#define MSG_LEVEL_BED_NEXT_POINT _UxGT("Następny punkt") -#define MSG_LEVEL_BED_DONE _UxGT("Wypoziomowano!") -#define MSG_SET_HOME_OFFSETS _UxGT("Ust. poz. zer.") -#define MSG_HOME_OFFSETS_APPLIED _UxGT("Poz. zerowa ust.") -#define MSG_SET_ORIGIN _UxGT("Ustaw punkt zero") -#define MSG_PREHEAT_1 _UxGT("Rozgrzej PLA") -#define MSG_PREHEAT_1_N MSG_PREHEAT_1 _UxGT(" ") -#define MSG_PREHEAT_1_ALL MSG_PREHEAT_1 _UxGT(" wsz.") -#define MSG_PREHEAT_1_BEDONLY _UxGT("Rozgrzej stół PLA") -#define MSG_PREHEAT_1_SETTINGS _UxGT("Ustaw. rozg. PLA") -#define MSG_PREHEAT_2 _UxGT("Rozgrzej ABS") -#define MSG_PREHEAT_2_N MSG_PREHEAT_2 _UxGT(" ") -#define MSG_PREHEAT_2_ALL MSG_PREHEAT_2 _UxGT(" wsz.") -#define MSG_PREHEAT_2_BEDONLY _UxGT("Rozgrzej stół ABS") -#define MSG_PREHEAT_2_SETTINGS _UxGT("Ustaw. rozg. ABS") -#define MSG_COOLDOWN _UxGT("Chłodzenie") -#define MSG_SWITCH_PS_ON _UxGT("Włącz zasilacz") -#define MSG_SWITCH_PS_OFF _UxGT("Wyłącz zasilacz") -#define MSG_EXTRUDE _UxGT("Ekstruzja") -#define MSG_RETRACT _UxGT("Wycofanie") -#define MSG_MOVE_AXIS _UxGT("Ruch osi") -#define MSG_BED_LEVELING _UxGT("Poziom. stołu") -#define MSG_LEVEL_BED _UxGT("Poziom. stołu") -#define MSG_MOVE_X _UxGT("Przesuń w X") -#define MSG_MOVE_Y _UxGT("Przesuń w Y") -#define MSG_MOVE_Z _UxGT("Przesuń w Z") -#define MSG_MOVE_E _UxGT("Ekstruzja (os E)") -#define MSG_MOVE_01MM _UxGT("Przesuń co .1mm") -#define MSG_MOVE_1MM _UxGT("Przesuń co 1mm") -#define MSG_MOVE_10MM _UxGT("Przesuń co 10mm") -#define MSG_SPEED _UxGT("Predkość") -#define MSG_BED_Z _UxGT("Stół Z") -#define MSG_NOZZLE _UxGT("Dysza") -#define MSG_BED _UxGT("Stół") -#define MSG_FAN_SPEED _UxGT("Obroty wiatraka") -#define MSG_FLOW _UxGT("Przepływ") -#define MSG_CONTROL _UxGT("Ustawienia") -#define MSG_MIN LCD_STR_THERMOMETER _UxGT(" Min") -#define MSG_MAX LCD_STR_THERMOMETER _UxGT(" Max") -#define MSG_FACTOR LCD_STR_THERMOMETER _UxGT(" Mnożnik") -#define MSG_AUTOTEMP _UxGT("Auto. temperatura") -#define MSG_ON _UxGT("Wł. ") -#define MSG_OFF _UxGT("Wył.") -#define MSG_PID_P _UxGT("PID-P") -#define MSG_PID_I _UxGT("PID-I") -#define MSG_PID_D _UxGT("PID-D") -#define MSG_PID_C _UxGT("PID-C") -#define MSG_SELECT _UxGT("Select") -#define MSG_ACC _UxGT("Przyśpieszenie") -#define MSG_JERK _UxGT("Zryw") -#define MSG_VX_JERK _UxGT("Zryw Vx") -#define MSG_VY_JERK _UxGT("Zryw Vy") -#define MSG_VZ_JERK _UxGT("Zryw Vz") -#define MSG_VE_JERK _UxGT("Zryw Ve") -#define MSG_VMAX _UxGT("Vmax ") -#define MSG_VMIN _UxGT("Vmin") -#define MSG_VTRAV_MIN _UxGT("Vskok min") -#define MSG_ACCELERATION MSG_ACC -#define MSG_AMAX _UxGT("Amax") -#define MSG_A_RETRACT _UxGT("A-wycofanie") -#define MSG_A_TRAVEL _UxGT("A-przesuń.") -#define MSG_STEPS_PER_MM _UxGT("kroki/mm") -#define MSG_XSTEPS _UxGT("krokiX/mm") -#define MSG_YSTEPS _UxGT("krokiY/mm") -#define MSG_ZSTEPS _UxGT("krokiZ/mm") -#define MSG_ESTEPS _UxGT("krokiE/mm") -#define MSG_E1STEPS _UxGT("krokiE1/mm") -#define MSG_E2STEPS _UxGT("krokiE2/mm") -#define MSG_E3STEPS _UxGT("krokiE3/mm") -#define MSG_E4STEPS _UxGT("krokiE4/mm") -#define MSG_E5STEPS _UxGT("krokiE5/mm") -#define MSG_TEMPERATURE _UxGT("Temperatura") -#define MSG_MOTION _UxGT("Ruch") -#define MSG_FILAMENT _UxGT("Filament") -#define MSG_VOLUMETRIC_ENABLED _UxGT("E w mm3") -#define MSG_FILAMENT_DIAM _UxGT("Śr. fil.") -#define MSG_CONTRAST _UxGT("Kontrast LCD") -#define MSG_STORE_EEPROM _UxGT("Zapisz w pamięci") -#define MSG_LOAD_EEPROM _UxGT("Wczytaj z pamięci") -#define MSG_RESTORE_FAILSAFE _UxGT("Ustaw. fabryczne") -#define MSG_REFRESH _UxGT("Odswież") -#define MSG_WATCH _UxGT("Ekran główny") -#define MSG_PREPARE _UxGT("Przygotuj") -#define MSG_TUNE _UxGT("Strojenie") -#define MSG_PAUSE_PRINT _UxGT("Pauza") -#define MSG_RESUME_PRINT _UxGT("Wznowienie") -#define MSG_STOP_PRINT _UxGT("Stop") -#define MSG_CARD_MENU _UxGT("Karta SD") -#define MSG_NO_CARD _UxGT("Brak karty") -#define MSG_DWELL _UxGT("Uśpij...") -#define MSG_USERWAIT _UxGT("Oczekiwanie...") -#define MSG_RESUMING _UxGT("Wznawianie druku") -#define MSG_PRINT_ABORTED _UxGT("Druk przerwany") -#define MSG_NO_MOVE _UxGT("Brak ruchu") -#define MSG_KILLED _UxGT("Ubity. ") -#define MSG_STOPPED _UxGT("Zatrzymany. ") -#define MSG_CONTROL_RETRACT _UxGT("Wycofaj mm") -#define MSG_CONTROL_RETRACT_SWAP _UxGT("Z Wycof. mm") -#define MSG_CONTROL_RETRACTF _UxGT("Wycofaj V") -#define MSG_CONTROL_RETRACT_ZLIFT _UxGT("Skok Z mm") -#define MSG_CONTROL_RETRACT_RECOVER _UxGT("Cof. wycof. mm") -#define MSG_CONTROL_RETRACT_RECOVER_SWAP _UxGT("Z Cof. wyc. mm") -#define MSG_CONTROL_RETRACT_RECOVERF _UxGT("Cof. wycof. V") -#define MSG_AUTORETRACT _UxGT("Auto. wycofanie") -#define MSG_FILAMENTCHANGE _UxGT("Zmień filament") -#define MSG_INIT_SDCARD _UxGT("Inicjal. karty SD") -#define MSG_CNG_SDCARD _UxGT("Zmiana karty SD") -#define MSG_ZPROBE_OUT _UxGT("Sonda Z za stołem") -#define MSG_BLTOUCH_SELFTEST _UxGT("BLTouch Self-Test") -#define MSG_BLTOUCH_RESET _UxGT("Reset BLTouch") -#define MSG_HOME _UxGT("Home") // Used as MSG_HOME " " MSG_X MSG_Y MSG_Z " " MSG_FIRST -#define MSG_FIRST _UxGT("first") -#define MSG_ZPROBE_ZOFFSET _UxGT("Offset Z") -#define MSG_BABYSTEP_X _UxGT("Babystep X") -#define MSG_BABYSTEP_Y _UxGT("Babystep Y") -#define MSG_BABYSTEP_Z _UxGT("Babystep Z") -#define MSG_ENDSTOP_ABORT _UxGT("Błąd krańcówki") -#define MSG_HEATING_FAILED_LCD _UxGT("Rozgrz. nieudane") -#define MSG_ERR_REDUNDANT_TEMP _UxGT("Błąd temperatury") -#define MSG_THERMAL_RUNAWAY _UxGT("Zanik temp.") -#define MSG_ERR_MAXTEMP _UxGT("Err max temp") -#define MSG_ERR_MINTEMP _UxGT("Err min temp") -#define MSG_ERR_MAXTEMP_BED _UxGT("Err max temp stołu") -#define MSG_ERR_MINTEMP_BED _UxGT("Err min temp stołu") -#define MSG_ERR_Z_HOMING _UxGT("G28 Z Forbidden") -#define MSG_HALTED _UxGT("Drukarka zatrzym.") -#define MSG_PLEASE_RESET _UxGT("Proszę zresetować") -#define MSG_SHORT_DAY _UxGT("d") // One character only -#define MSG_SHORT_HOUR _UxGT("g") // One character only -#define MSG_SHORT_MINUTE _UxGT("m") // One character only -#define MSG_HEATING _UxGT("Rozgrzewanie...") -#define MSG_HEATING_COMPLETE _UxGT("Rozgrzano") -#define MSG_BED_HEATING _UxGT("Rozgrzewanie stołu...") -#define MSG_BED_DONE _UxGT("Rozgrzano stół") -#define MSG_DELTA_CALIBRATE _UxGT("Kalibrowanie Delty") -#define MSG_DELTA_CALIBRATE_X _UxGT("Kalibruj X") -#define MSG_DELTA_CALIBRATE_Y _UxGT("Kalibruj Y") -#define MSG_DELTA_CALIBRATE_Z _UxGT("Kalibruj Z") -#define MSG_DELTA_CALIBRATE_CENTER _UxGT("Kalibruj środek") - -#define MSG_INFO_MENU _UxGT("O drukarce") -#define MSG_INFO_PRINTER_MENU _UxGT("Info drukarki") -#define MSG_INFO_STATS_MENU _UxGT("Statystyki") -#define MSG_INFO_BOARD_MENU _UxGT("Board Info") -#define MSG_INFO_THERMISTOR_MENU _UxGT("Thermistory") -#define MSG_INFO_EXTRUDERS _UxGT("Ekstrudery") -#define MSG_INFO_BAUDRATE _UxGT("Predkość USB") -#define MSG_INFO_PROTOCOL _UxGT("Protokół") -#define MSG_LIGHTS_ON _UxGT("Oświetlenie wl.") -#define MSG_LIGHTS_OFF _UxGT("Oświetlenie wyl.") - -#if LCD_WIDTH >= 20 - #define MSG_INFO_PRINT_COUNT _UxGT("Wydrukowano") - #define MSG_INFO_COMPLETED_PRINTS _UxGT("Ukończono") - #define MSG_INFO_PRINT_TIME _UxGT("Czas druku") - #define MSG_INFO_PRINT_LONGEST _UxGT("Najdł. druk") - #define MSG_INFO_PRINT_FILAMENT _UxGT("Użyty fil.") -#else - #define MSG_INFO_PRINT_COUNT _UxGT("Wydrukowano") - #define MSG_INFO_COMPLETED_PRINTS _UxGT("Ukończono") - #define MSG_INFO_PRINT_TIME _UxGT("Razem") - #define MSG_INFO_PRINT_LONGEST _UxGT("Najdł. druk") - #define MSG_INFO_PRINT_FILAMENT _UxGT("Użyty fil.") -#endif - -#define MSG_INFO_MIN_TEMP _UxGT("Min Temp") -#define MSG_INFO_MAX_TEMP _UxGT("Max Temp") -#define MSG_INFO_PSU _UxGT("Zasilacz") - -#define MSG_DRIVE_STRENGTH _UxGT("Siła silnika") -#define MSG_DAC_PERCENT _UxGT("Siła %") -#define MSG_DAC_EEPROM_WRITE _UxGT("Zapisz DAC EEPROM") - -#define MSG_FILAMENT_CHANGE_HEADER _UxGT("ZMIEŃ FILAMENT") -#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("ZMIEŃ OPCJE:") -#define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("Ekstruduj więcej") -#define MSG_FILAMENT_CHANGE_OPTION_RESUME _UxGT("Wznów drukowanie") - -#if LCD_HEIGHT >= 4 - // Up to 3 lines allowed - #define MSG_FILAMENT_CHANGE_INIT_1 _UxGT("Czekam na ") - #define MSG_FILAMENT_CHANGE_INIT_2 _UxGT("zmianę filamentu") - #define MSG_FILAMENT_CHANGE_UNLOAD_1 _UxGT("Czekam na") - #define MSG_FILAMENT_CHANGE_UNLOAD_2 _UxGT("wyjęcie filamentu") - #define MSG_FILAMENT_CHANGE_INSERT_1 _UxGT("Włóz filament") - #define MSG_FILAMENT_CHANGE_INSERT_2 _UxGT("i naciśnij przycisk") - #define MSG_FILAMENT_CHANGE_INSERT_3 _UxGT("aby kontynuować...") - #define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Czekam na") - #define MSG_FILAMENT_CHANGE_LOAD_2 _UxGT("włożenie filamentu") - #define MSG_FILAMENT_CHANGE_EXTRUDE_1 _UxGT("Czekam na") - #define MSG_FILAMENT_CHANGE_EXTRUDE_2 _UxGT("ekstruzję filamentu") - #define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Czekam na") - #define MSG_FILAMENT_CHANGE_RESUME_2 _UxGT("wznowienie druku") -#else // LCD_HEIGHT < 4 - // Up to 2 lines allowed - #define MSG_FILAMENT_CHANGE_INIT_1 _UxGT("Proszę czekać...") - #define MSG_FILAMENT_CHANGE_UNLOAD_1 _UxGT("Wysuwanie...") - #define MSG_FILAMENT_CHANGE_INSERT_1 _UxGT("Włóż i naciśnij prz.") - #define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Ładowanie...") - #define MSG_FILAMENT_CHANGE_EXTRUDE_1 _UxGT("Ekstruzja...") - #define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Wznowienie...") -#endif // LCD_HEIGHT < 4 - - #else - -#define WELCOME_MSG MACHINE_NAME _UxGT(" gotowy.") -#define MSG_SD_INSERTED _UxGT("Karta wlozona") -#define MSG_SD_REMOVED _UxGT("Karta usunieta") -#define MSG_LCD_ENDSTOPS _UxGT("Krancow.") // Max length 8 characters -#define MSG_MAIN _UxGT("Menu glowne") -#define MSG_AUTOSTART _UxGT("Autostart") -#define MSG_DISABLE_STEPPERS _UxGT("Wylacz silniki") -#define MSG_AUTO_HOME _UxGT("Pozycja zerowa") -#define MSG_AUTO_HOME_X _UxGT("Zeruj X") -#define MSG_AUTO_HOME_Y _UxGT("Zeruj Y") -#define MSG_AUTO_HOME_Z _UxGT("Zeruj Z") -#define MSG_LEVEL_BED_HOMING _UxGT("Pozycja zerowa") -#define MSG_LEVEL_BED_WAITING _UxGT("Kliknij by rozp.") -#define MSG_LEVEL_BED_NEXT_POINT _UxGT("Nastepny punkt") -#define MSG_LEVEL_BED_DONE _UxGT("Wypoziomowano!") -#define MSG_SET_HOME_OFFSETS _UxGT("Ust. poz. zer.") -#define MSG_HOME_OFFSETS_APPLIED _UxGT("Poz. zerowa ust.") -#define MSG_SET_ORIGIN _UxGT("Ustaw punkt zero") -#define MSG_PREHEAT_1 _UxGT("Rozgrzej PLA") -#define MSG_PREHEAT_1_N MSG_PREHEAT_1 _UxGT(" ") -#define MSG_PREHEAT_1_ALL MSG_PREHEAT_1 _UxGT(" wsz.") -#define MSG_PREHEAT_1_BEDONLY _UxGT("Rozgrzej stol PLA") -#define MSG_PREHEAT_1_SETTINGS _UxGT("Ustaw. rozg. PLA") -#define MSG_PREHEAT_2 _UxGT("Rozgrzej ABS") -#define MSG_PREHEAT_2_N MSG_PREHEAT_2 _UxGT(" ") -#define MSG_PREHEAT_2_ALL MSG_PREHEAT_2 _UxGT(" wsz.") -#define MSG_PREHEAT_2_BEDONLY _UxGT("Rozgrzej stol ABS") -#define MSG_PREHEAT_2_SETTINGS _UxGT("Ustaw. rozg. ABS") -#define MSG_COOLDOWN _UxGT("Chlodzenie") -#define MSG_SWITCH_PS_ON _UxGT("Wlacz zasilacz") -#define MSG_SWITCH_PS_OFF _UxGT("Wylacz zasilacz") -#define MSG_EXTRUDE _UxGT("Ekstruzja") -#define MSG_RETRACT _UxGT("Wycofanie") -#define MSG_MOVE_AXIS _UxGT("Ruch osi") -#define MSG_BED_LEVELING _UxGT("Poziom. stolu") -#define MSG_LEVEL_BED _UxGT("Poziom. stolu") -#define MSG_MOVE_X _UxGT("Przesun w X") -#define MSG_MOVE_Y _UxGT("Przesun w Y") -#define MSG_MOVE_Z _UxGT("Przesun w Z") -#define MSG_MOVE_E _UxGT("Ekstruzja (os E)") -#define MSG_MOVE_01MM _UxGT("Przesun co .1mm") -#define MSG_MOVE_1MM _UxGT("Przesun co 1mm") -#define MSG_MOVE_10MM _UxGT("Przesun co 10mm") -#define MSG_SPEED _UxGT("Predkosc") -#define MSG_BED_Z _UxGT("Stol Z") -#define MSG_NOZZLE _UxGT("Dysza") -#define MSG_BED _UxGT("Stol") -#define MSG_FAN_SPEED _UxGT("Obroty wiatraka") -#define MSG_FLOW _UxGT("Przeplyw") -#define MSG_CONTROL _UxGT("Ustawienia") -#define MSG_MIN LCD_STR_THERMOMETER _UxGT(" Min") -#define MSG_MAX LCD_STR_THERMOMETER _UxGT(" Max") -#define MSG_FACTOR LCD_STR_THERMOMETER _UxGT(" Mnoznik") -#define MSG_AUTOTEMP _UxGT("Auto. temperatura") -#define MSG_ON _UxGT("Wl. ") -#define MSG_OFF _UxGT("Wyl.") -#define MSG_PID_P _UxGT("PID-P") -#define MSG_PID_I _UxGT("PID-I") -#define MSG_PID_D _UxGT("PID-D") -#define MSG_PID_C _UxGT("PID-C") -#define MSG_SELECT _UxGT("Select") -#define MSG_ACC _UxGT("Przyspieszenie") -#define MSG_JERK _UxGT("Zryw") -#define MSG_VX_JERK _UxGT("Zryw Vx") -#define MSG_VY_JERK _UxGT("Zryw Vy") -#define MSG_VZ_JERK _UxGT("Zryw Vz") -#define MSG_VE_JERK _UxGT("Zryw Ve") -#define MSG_VMAX _UxGT("Vmax ") -#define MSG_VMIN _UxGT("Vmin") -#define MSG_VTRAV_MIN _UxGT("Vskok min") -#define MSG_ACCELERATION MSG_ACC -#define MSG_AMAX _UxGT("Amax") -#define MSG_A_RETRACT _UxGT("A-wycofanie") -#define MSG_A_TRAVEL _UxGT("A-przesun.") -#define MSG_STEPS_PER_MM _UxGT("kroki/mm") -#define MSG_XSTEPS _UxGT("krokiX/mm") -#define MSG_YSTEPS _UxGT("krokiY/mm") -#define MSG_ZSTEPS _UxGT("krokiZ/mm") -#define MSG_ESTEPS _UxGT("krokiE/mm") -#define MSG_E1STEPS _UxGT("krokiE1/mm") -#define MSG_E2STEPS _UxGT("krokiE2/mm") -#define MSG_E3STEPS _UxGT("krokiE3/mm") -#define MSG_E4STEPS _UxGT("krokiE4/mm") -#define MSG_E5STEPS _UxGT("krokiE5/mm") -#define MSG_TEMPERATURE _UxGT("Temperatura") -#define MSG_MOTION _UxGT("Ruch") -#define MSG_FILAMENT _UxGT("Filament") -#define MSG_VOLUMETRIC_ENABLED _UxGT("E w mm3") -#define MSG_FILAMENT_DIAM _UxGT("Sr. fil.") -#define MSG_CONTRAST _UxGT("Kontrast LCD") -#define MSG_STORE_EEPROM _UxGT("Zapisz w pamieci") -#define MSG_LOAD_EEPROM _UxGT("Wczytaj z pamieci") -#define MSG_RESTORE_FAILSAFE _UxGT("Ustaw. fabryczne") -#define MSG_REFRESH _UxGT("Odswiez") -#define MSG_WATCH _UxGT("Ekran glowny") -#define MSG_PREPARE _UxGT("Przygotuj") -#define MSG_TUNE _UxGT("Strojenie") -#define MSG_PAUSE_PRINT _UxGT("Pauza") -#define MSG_RESUME_PRINT _UxGT("Wznowienie") -#define MSG_STOP_PRINT _UxGT("Stop") -#define MSG_CARD_MENU _UxGT("Karta SD") -#define MSG_NO_CARD _UxGT("Brak karty") -#define MSG_DWELL _UxGT("Uspij...") -#define MSG_USERWAIT _UxGT("Oczekiwanie...") -#define MSG_RESUMING _UxGT("Wznawianie druku") -#define MSG_PRINT_ABORTED _UxGT("Druk przerwany") -#define MSG_NO_MOVE _UxGT("Brak ruchu") -#define MSG_KILLED _UxGT("Ubity. ") -#define MSG_STOPPED _UxGT("Zatrzymany. ") -#define MSG_CONTROL_RETRACT _UxGT("Wycofaj mm") -#define MSG_CONTROL_RETRACT_SWAP _UxGT("Z Wycof. mm") -#define MSG_CONTROL_RETRACTF _UxGT("Wycofaj V") -#define MSG_CONTROL_RETRACT_ZLIFT _UxGT("Skok Z mm") -#define MSG_CONTROL_RETRACT_RECOVER _UxGT("Cof. wycof. mm") -#define MSG_CONTROL_RETRACT_RECOVER_SWAP _UxGT("Z Cof. wyc. mm") -#define MSG_CONTROL_RETRACT_RECOVERF _UxGT("Cof. wycof. V") -#define MSG_AUTORETRACT _UxGT("Auto. wycofanie") -#define MSG_FILAMENTCHANGE _UxGT("Zmien filament") -#define MSG_INIT_SDCARD _UxGT("Inicjal. karty SD") -#define MSG_CNG_SDCARD _UxGT("Zmiana karty SD") -#define MSG_ZPROBE_OUT _UxGT("Sonda Z za stolem") -#define MSG_BLTOUCH_SELFTEST _UxGT("BLTouch Self-Test") -#define MSG_BLTOUCH_RESET _UxGT("Reset BLTouch") -#define MSG_HOME _UxGT("Home") // Used as MSG_HOME " " MSG_X MSG_Y MSG_Z " " MSG_FIRST -#define MSG_FIRST _UxGT("first") -#define MSG_ZPROBE_ZOFFSET _UxGT("Offset Z") -#define MSG_BABYSTEP_X _UxGT("Babystep X") -#define MSG_BABYSTEP_Y _UxGT("Babystep Y") -#define MSG_BABYSTEP_Z _UxGT("Babystep Z") -#define MSG_ENDSTOP_ABORT _UxGT("Blad krancowki") -#define MSG_HEATING_FAILED_LCD _UxGT("Rozgrz. nieudane") -#define MSG_ERR_REDUNDANT_TEMP _UxGT("Blad temperatury") -#define MSG_THERMAL_RUNAWAY _UxGT("Zanik temp.") -#define MSG_ERR_MAXTEMP _UxGT("Err max temp") -#define MSG_ERR_MINTEMP _UxGT("Err min temp") -#define MSG_ERR_MAXTEMP_BED _UxGT("Err max temp stolu") -#define MSG_ERR_MINTEMP_BED _UxGT("Err min temp stolu") -#define MSG_ERR_Z_HOMING _UxGT("G28 Z Forbidden") -#define MSG_HALTED _UxGT("Drukarka zatrzym.") -#define MSG_PLEASE_RESET _UxGT("Prosze zresetowac") -#define MSG_SHORT_DAY _UxGT("d") // One character only -#define MSG_SHORT_HOUR _UxGT("g") // One character only -#define MSG_SHORT_MINUTE _UxGT("m") // One character only -#define MSG_HEATING _UxGT("Rozgrzewanie...") -#define MSG_HEATING_COMPLETE _UxGT("Rozgrzano") -#define MSG_BED_HEATING _UxGT("Rozgrzewanie stolu...") -#define MSG_BED_DONE _UxGT("Rozgrzano stol") -#define MSG_DELTA_CALIBRATE _UxGT("Kalibrowanie Delty") -#define MSG_DELTA_CALIBRATE_X _UxGT("Kalibruj X") -#define MSG_DELTA_CALIBRATE_Y _UxGT("Kalibruj Y") -#define MSG_DELTA_CALIBRATE_Z _UxGT("Kalibruj Z") -#define MSG_DELTA_CALIBRATE_CENTER _UxGT("Kalibruj srodek") - -#define MSG_INFO_MENU _UxGT("O drukarce") -#define MSG_INFO_PRINTER_MENU _UxGT("Info drukarki") -#define MSG_INFO_STATS_MENU _UxGT("Statystyki") -#define MSG_INFO_BOARD_MENU _UxGT("Board Info") -#define MSG_INFO_THERMISTOR_MENU _UxGT("Thermistory") -#define MSG_INFO_EXTRUDERS _UxGT("Ekstrudery") -#define MSG_INFO_BAUDRATE _UxGT("Predkosc USB") -#define MSG_INFO_PROTOCOL _UxGT("Protokol") -#define MSG_LIGHTS_ON _UxGT("Oswietlenie wl.") -#define MSG_LIGHTS_OFF _UxGT("Oswietlenie wyl.") - -#if LCD_WIDTH >= 20 - #define MSG_INFO_PRINT_COUNT _UxGT("Wydrukowano") - #define MSG_INFO_COMPLETED_PRINTS _UxGT("Ukonczono") - #define MSG_INFO_PRINT_TIME _UxGT("Czas druku") - #define MSG_INFO_PRINT_LONGEST _UxGT("Najdl. druk") - #define MSG_INFO_PRINT_FILAMENT _UxGT("Uzyty fil.") + #include "language_pl-DOGM.h" #else - #define MSG_INFO_PRINT_COUNT _UxGT("Wydrukowano") - #define MSG_INFO_COMPLETED_PRINTS _UxGT("Ukonczono") - #define MSG_INFO_PRINT_TIME _UxGT("Razem") - #define MSG_INFO_PRINT_LONGEST _UxGT("Najdl. druk") - #define MSG_INFO_PRINT_FILAMENT _UxGT("Uzyty fil.") -#endif - -#define MSG_INFO_MIN_TEMP _UxGT("Min Temp") -#define MSG_INFO_MAX_TEMP _UxGT("Max Temp") -#define MSG_INFO_PSU _UxGT("Zasilacz") - -#define MSG_DRIVE_STRENGTH _UxGT("Sila silnika") -#define MSG_DAC_PERCENT _UxGT("Sila %") -#define MSG_DAC_EEPROM_WRITE _UxGT("Zapisz DAC EEPROM") - -#define MSG_FILAMENT_CHANGE_HEADER _UxGT("PRINT PAUSED") -#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("RESUME OPTIONS:") -#define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("Ekstruduj wiecej") -#define MSG_FILAMENT_CHANGE_OPTION_RESUME _UxGT("Wznow drukowanie") - -#if LCD_HEIGHT >= 4 - // Up to 3 lines allowed - #define MSG_FILAMENT_CHANGE_INIT_1 _UxGT("Czekam na ") - #define MSG_FILAMENT_CHANGE_INIT_2 _UxGT("zmiane filamentu") - #define MSG_FILAMENT_CHANGE_UNLOAD_1 _UxGT("Czekam na") - #define MSG_FILAMENT_CHANGE_UNLOAD_2 _UxGT("wyjecie filamentu") - #define MSG_FILAMENT_CHANGE_INSERT_1 _UxGT("Wloz filament") - #define MSG_FILAMENT_CHANGE_INSERT_2 _UxGT("i nacisnij przycisk") - #define MSG_FILAMENT_CHANGE_INSERT_3 _UxGT("aby kontynuowac...") - #define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Czekam na") - #define MSG_FILAMENT_CHANGE_LOAD_2 _UxGT("wlozenie filamentu") - #define MSG_FILAMENT_CHANGE_EXTRUDE_1 _UxGT("Czekam na") - #define MSG_FILAMENT_CHANGE_EXTRUDE_2 _UxGT("ekstruzje filamentu") - #define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Czekam na") - #define MSG_FILAMENT_CHANGE_RESUME_2 _UxGT("wznowienie druku") -#else // LCD_HEIGHT < 4 - // Up to 2 lines allowed - #define MSG_FILAMENT_CHANGE_INIT_1 _UxGT("Prosze czekac...") - #define MSG_FILAMENT_CHANGE_UNLOAD_1 _UxGT("Wysuwanie...") - #define MSG_FILAMENT_CHANGE_INSERT_1 _UxGT("Wloz i nacisnij prz.") - #define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Ladowanie...") - #define MSG_FILAMENT_CHANGE_EXTRUDE_1 _UxGT("Ekstruzja...") - #define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Wznowienie...") -#endif // LCD_HEIGHT < 4 + #include "language_pl-HD44780.h" #endif #endif // LANGUAGE_PL_H diff --git a/Marlin/language_tr.h b/Marlin/language_tr.h index edbea97d7..728bab096 100644 --- a/Marlin/language_tr.h +++ b/Marlin/language_tr.h @@ -206,8 +206,7 @@ #define MSG_INFO_EXTRUDERS _UxGT("Ekstruderler") // Ekstruderler #define MSG_INFO_BAUDRATE _UxGT("İletişim Hızı") // İletişim Hızı #define MSG_INFO_PROTOCOL _UxGT("Protokol") // Protokol -#define MSG_LIGHTS_ON _UxGT("Aydınlatmayı Aç") // Aydınlatmayı Aç -#define MSG_LIGHTS_OFF _UxGT("Aydınlatmayı Kapa") // Aydınlaymayı Kapa +#define MSG_CASE_LIGHT _UxGT("Aydınlatmayı") // Aydınlatmayı Aç #if LCD_WIDTH >= 20 #define MSG_INFO_PRINT_COUNT _UxGT("Baskı Sayısı") // Baskı Sayısı diff --git a/Marlin/language_uk.h b/Marlin/language_uk.h index 638961e93..06048470a 100644 --- a/Marlin/language_uk.h +++ b/Marlin/language_uk.h @@ -180,8 +180,7 @@ #define MSG_INFO_EXTRUDERS _UxGT("Екструдери") #define MSG_INFO_BAUDRATE _UxGT("біт/с") #define MSG_INFO_PROTOCOL _UxGT("Протокол") -#define MSG_LIGHTS_ON _UxGT("Підсвітка увік.") -#define MSG_LIGHTS_OFF _UxGT("Підсвітка вимк.") +#define MSG_CASE_LIGHT _UxGT("Підсвітка") #if LCD_WIDTH >= 20 #define MSG_INFO_PRINT_COUNT _UxGT("К-сть друків") diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 0ead6498f..4e21ba079 100755 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -708,19 +708,6 @@ void kill_screen(const char* lcd_msg) { #endif // SDSUPPORT - #if ENABLED(MENU_ITEM_CASE_LIGHT) - - extern bool case_light_on; - extern void update_case_light(); - - void toggle_case_light() { - case_light_on ^= true; - lcdDrawUpdate = LCDVIEW_KEEP_REDRAWING; - update_case_light(); - } - - #endif // MENU_ITEM_CASE_LIGHT - #if ENABLED(BLTOUCH) /** @@ -790,6 +777,11 @@ void kill_screen(const char* lcd_msg) { * */ + #if ENABLED(MENU_ITEM_CASE_LIGHT) + extern bool case_light_on; + extern void update_case_light(); + #endif + void lcd_main_menu() { START_MENU(); MENU_BACK(MSG_WATCH); @@ -805,10 +797,7 @@ void kill_screen(const char* lcd_msg) { // Switch case light on/off // #if ENABLED(MENU_ITEM_CASE_LIGHT) - if (case_light_on) - MENU_ITEM(function, MSG_LIGHTS_OFF, toggle_case_light); - else - MENU_ITEM(function, MSG_LIGHTS_ON, toggle_case_light); + MENU_ITEM_EDIT_CALLBACK(bool, MSG_CASE_LIGHT, case_light_on, update_case_light); #endif if (planner.movesplanned() || IS_SD_PRINTING) { From 6f89db11f02a61d79728bc586f2c629db93d055d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 29 May 2017 11:51:29 -0500 Subject: [PATCH 168/189] Allow lcd_setstatusPGM to reset the alert level --- Marlin/G26_Mesh_Validation_Tool.cpp | 30 +++++++++++++---------------- Marlin/ubl_G29.cpp | 2 +- Marlin/ultralcd.cpp | 11 ++++++----- Marlin/ultralcd.h | 6 +++--- 4 files changed, 23 insertions(+), 26 deletions(-) diff --git a/Marlin/G26_Mesh_Validation_Tool.cpp b/Marlin/G26_Mesh_Validation_Tool.cpp index a17adda10..56f2059bb 100644 --- a/Marlin/G26_Mesh_Validation_Tool.cpp +++ b/Marlin/G26_Mesh_Validation_Tool.cpp @@ -131,7 +131,7 @@ void set_destination_to_current(); void set_current_to_destination(); void prepare_move_to_destination(); - void lcd_setstatuspgm(const char* const message, const uint8_t level); + void lcd_setstatusPGM(const char* const message, const int8_t level); void sync_plan_position_e(); void chirp_at_user(); @@ -181,18 +181,17 @@ safe_delay(10); // Wait for click to settle #if ENABLED(ULTRA_LCD) - lcd_setstatuspgm(PSTR("Mesh Validation Stopped."), 99); + lcd_setstatusPGM(PSTR("Mesh Validation Stopped."), 99); lcd_quick_feedback(); #endif - lcd_reset_alert_level(); while (!ubl_lcd_clicked()) idle(); // Wait for button release // If the button is suddenly pressed again, // ask the user to resolve the issue - lcd_setstatuspgm(PSTR("Release button"), 99); // will never appear... + lcd_setstatusPGM(PSTR("Release button"), 99); // will never appear... while (ubl_lcd_clicked()) idle(); // unless this loop happens - lcd_setstatuspgm(PSTR("")); + lcd_setstatusPGM(PSTR(""), -1); return true; } @@ -351,8 +350,7 @@ } while (--g26_repeats && location.x_index >= 0 && location.y_index >= 0); LEAVE: - lcd_reset_alert_level(); - lcd_setstatuspgm(PSTR("Leaving G26")); + lcd_setstatusPGM(PSTR("Leaving G26"), -1); retract_filament(destination); destination[Z_AXIS] = Z_CLEARANCE_BETWEEN_PROBES; @@ -726,8 +724,7 @@ } bool unified_bed_leveling::exit_from_g26() { - lcd_reset_alert_level(); - lcd_setstatuspgm(PSTR("Leaving G26")); + lcd_setstatusPGM(PSTR("Leaving G26"), -1); while (ubl_lcd_clicked()) idle(); return UBL_ERR; } @@ -741,7 +738,7 @@ #if HAS_TEMP_BED #if ENABLED(ULTRA_LCD) if (g26_bed_temp > 25) { - lcd_setstatuspgm(PSTR("G26 Heating Bed."), 99); + lcd_setstatusPGM(PSTR("G26 Heating Bed."), 99); lcd_quick_feedback(); #endif has_control_of_lcd_panel = true; @@ -757,7 +754,7 @@ } #if ENABLED(ULTRA_LCD) } - lcd_setstatuspgm(PSTR("G26 Heating Nozzle."), 99); + lcd_setstatusPGM(PSTR("G26 Heating Nozzle."), 99); lcd_quick_feedback(); #endif #endif @@ -774,8 +771,7 @@ } #if ENABLED(ULTRA_LCD) - lcd_reset_alert_level(); - lcd_setstatuspgm(PSTR("")); + lcd_setstatusPGM(PSTR(""), -1); lcd_quick_feedback(); #endif @@ -792,7 +788,7 @@ has_control_of_lcd_panel = true; - lcd_setstatuspgm(PSTR("User-Controlled Prime"), 99); + lcd_setstatusPGM(PSTR("User-Controlled Prime"), 99); chirp_at_user(); set_destination_to_current(); @@ -819,9 +815,9 @@ while (ubl_lcd_clicked()) idle(); // Debounce Encoder Wheel #if ENABLED(ULTRA_LCD) - strcpy_P(lcd_status_message, PSTR("Done Priming")); // We can't do lcd_setstatuspgm() without having it continue; + strcpy_P(lcd_status_message, PSTR("Done Priming")); // We can't do lcd_setstatusPGM() without having it continue; // So... We cheat to get a message up. - lcd_setstatuspgm(PSTR("Done Priming"), 99); + lcd_setstatusPGM(PSTR("Done Priming"), 99); lcd_quick_feedback(); #endif @@ -830,7 +826,7 @@ } else { #if ENABLED(ULTRA_LCD) - lcd_setstatuspgm(PSTR("Fixed Length Prime."), 99); + lcd_setstatusPGM(PSTR("Fixed Length Prime."), 99); lcd_quick_feedback(); #endif set_destination_to_current(); diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index c9abfbd5c..c4f77dceb 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -58,7 +58,7 @@ typedef void (*screenFunc_t)(); extern void lcd_goto_screen(screenFunc_t screen, const uint32_t encoder = 0); extern void lcd_setstatus(const char* message, const bool persist); - extern void lcd_setstatuspgm(const char* message, const uint8_t level); + extern void lcd_setstatusPGM(const char* message, const int8_t level); int unified_bed_leveling::g29_verbose_level, unified_bed_leveling::g29_phase_value, diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 4e21ba079..340178835 100755 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -680,7 +680,7 @@ void kill_screen(const char* lcd_msg) { #if ENABLED(PARK_HEAD_ON_PAUSE) enqueue_and_echo_commands_P(PSTR("M125")); #endif - lcd_setstatuspgm(PSTR(MSG_PRINT_PAUSED), true); + lcd_setstatusPGM(PSTR(MSG_PRINT_PAUSED), -1); } void lcd_sdcard_resume() { @@ -690,7 +690,7 @@ void kill_screen(const char* lcd_msg) { card.startFileprint(); print_job_timer.start(); #endif - lcd_setstatuspgm(PSTR(""), true); + lcd_setstatusPGM(PSTR(""), -1); } void lcd_sdcard_stop() { @@ -703,7 +703,7 @@ void kill_screen(const char* lcd_msg) { for (uint8_t i = 0; i < FAN_COUNT; i++) fanSpeeds[i] = 0; #endif wait_for_heatup = false; - LCD_MESSAGEPGM(MSG_PRINT_ABORTED); + lcd_setstatusPGM(PSTR(MSG_PRINT_PAUSED), -1); } #endif // SDSUPPORT @@ -4095,7 +4095,8 @@ void lcd_setstatus(const char * const message, const bool persist) { lcd_finishstatus(persist); } -void lcd_setstatuspgm(const char * const message, const uint8_t level) { +void lcd_setstatusPGM(const char * const message, int8_t level) { + if (level < 0) level = lcd_status_message_level = 0; if (level < lcd_status_message_level) return; lcd_status_message_level = level; strncpy_P(lcd_status_message, message, 3 * (LCD_WIDTH)); @@ -4113,7 +4114,7 @@ void lcd_status_printf_P(const uint8_t level, const char * const fmt, ...) { } void lcd_setalertstatuspgm(const char * const message) { - lcd_setstatuspgm(message, 1); + lcd_setstatusPGM(message, 1); #if ENABLED(ULTIPANEL) lcd_return_to_status(); #endif diff --git a/Marlin/ultralcd.h b/Marlin/ultralcd.h index c6a11ee0b..36f3b7d65 100644 --- a/Marlin/ultralcd.h +++ b/Marlin/ultralcd.h @@ -38,7 +38,7 @@ void lcd_init(); bool lcd_hasstatus(); void lcd_setstatus(const char* message, const bool persist=false); - void lcd_setstatuspgm(const char* message, const uint8_t level=0); + void lcd_setstatusPGM(const char* message, const int8_t level=0); void lcd_status_printf_P(const uint8_t level, const char * const fmt, ...); void lcd_setalertstatuspgm(const char* message); void lcd_reset_alert_level(); @@ -61,7 +61,7 @@ void bootscreen(); #endif - #define LCD_MESSAGEPGM(x) lcd_setstatuspgm(PSTR(x)) + #define LCD_MESSAGEPGM(x) lcd_setstatusPGM(PSTR(x)) #define LCD_ALERTMESSAGEPGM(x) lcd_setalertstatuspgm(PSTR(x)) #define LCD_UPDATE_INTERVAL 100 @@ -153,7 +153,7 @@ inline void lcd_init() {} inline bool lcd_hasstatus() { return false; } inline void lcd_setstatus(const char* const message, const bool persist=false) { UNUSED(message); UNUSED(persist); } - inline void lcd_setstatuspgm(const char* const message, const uint8_t level=0) { UNUSED(message); UNUSED(level); } + inline void lcd_setstatusPGM(const char* const message, const int8_t level=0) { UNUSED(message); UNUSED(level); } inline void lcd_status_printf_P(const uint8_t level, const char * const fmt, ...) { UNUSED(level); UNUSED(fmt); } inline void lcd_buttons_update() {} inline void lcd_reset_alert_level() {} From 194f8b2f55ec4d7298de9e60793a313f59ef816e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 29 May 2017 11:52:02 -0500 Subject: [PATCH 169/189] Start at Z=0 in manual probing --- Marlin/Marlin_main.cpp | 2 +- Marlin/ultralcd.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 1d3c282ff..8335d0672 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -3839,7 +3839,7 @@ void home_all_axes() { gcode_G28(true); } #if MANUAL_PROBE_HEIGHT > 0 feedrate_mm_s = homing_feedrate_mm_s[Z_AXIS]; - current_position[Z_AXIS] = LOGICAL_Z_POSITION(Z_MIN_POS) + 0.2; // just slightly over the bed + current_position[Z_AXIS] = LOGICAL_Z_POSITION(Z_MIN_POS); // just slightly over the bed line_to_current_position(); #endif diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 340178835..a8c39f4d9 100755 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -1432,7 +1432,7 @@ void kill_screen(const char* lcd_msg) { current_position[Y_AXIS] = LOGICAL_Y_POSITION(y); planner.buffer_line_kinematic(current_position, MMM_TO_MMS(XY_PROBE_SPEED), active_extruder); #if MANUAL_PROBE_HEIGHT > 0 - current_position[Z_AXIS] = LOGICAL_Z_POSITION(Z_MIN_POS) + 0.2; + current_position[Z_AXIS] = LOGICAL_Z_POSITION(Z_MIN_POS); line_to_current(Z_AXIS); #endif lcd_synchronize(); From eb39d6e3e24245e474189e003a8d3acc635ca8da Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 29 May 2017 11:52:42 -0500 Subject: [PATCH 170/189] Don't draw progress bar until it has 1% --- Marlin/ultralcd_impl_HD44780.h | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/Marlin/ultralcd_impl_HD44780.h b/Marlin/ultralcd_impl_HD44780.h index b735baa8f..d650890d5 100644 --- a/Marlin/ultralcd_impl_HD44780.h +++ b/Marlin/ultralcd_impl_HD44780.h @@ -806,8 +806,10 @@ static void lcd_implementation_status_screen() { // Draw the progress bar if the message has shown long enough // or if there is no message set. - if (card.isFileOpen() && (ELAPSED(millis(), progress_bar_ms + PROGRESS_BAR_MSG_TIME) || !lcd_status_message[0])) - return lcd_draw_progress_bar(card.percentDone()); + if (card.isFileOpen() && (ELAPSED(millis(), progress_bar_ms + PROGRESS_BAR_MSG_TIME) || !lcd_status_message[0])) { + const uint8_t percent = card.percentDone(); + if (percent) return lcd_draw_progress_bar(percent); + } #elif ENABLED(FILAMENT_LCD_DISPLAY) && ENABLED(SDSUPPORT) From 78d8c598e1be6473c5d71feada47b9d3edef006a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 29 May 2017 12:19:02 -0500 Subject: [PATCH 171/189] Fix lcd_synchronize with message --- Marlin/ultralcd.cpp | 15 +++++++++++---- 1 file changed, 11 insertions(+), 4 deletions(-) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index a8c39f4d9..c6978d6f0 100755 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -481,21 +481,28 @@ uint16_t max_display_update_time = 0; /** * Show "Moving..." till moves are done, then revert to previous display. */ - inline void lcd_synchronize(const char * const msg=NULL) { + static const char moving[] PROGMEM = MSG_MOVING; + static const char *sync_message = moving; + + void _lcd_synchronize() { static bool no_reentry = false; - const static char moving[] PROGMEM = MSG_MOVING; - lcd_implementation_drawmenu_static(LCD_HEIGHT >= 4 ? 1 : 0, msg ? msg : moving); + if (lcdDrawUpdate) lcd_implementation_drawmenu_static(LCD_HEIGHT >= 4 ? 1 : 0, sync_message); if (no_reentry) return; // Make this the current handler till all moves are done no_reentry = true; screenFunc_t old_screen = currentScreen; - lcd_goto_screen(lcd_synchronize); + lcd_goto_screen(_lcd_synchronize); stepper.synchronize(); no_reentry = false; lcd_goto_screen(old_screen); } + void lcd_synchronize(const char * const msg=NULL) { + sync_message = msg ? msg : moving; + _lcd_synchronize(); + } + void lcd_return_to_status() { lcd_goto_screen(lcd_status_screen); } void lcd_save_previous_screen() { From f1e33afda4128aeb17f7ed937d1100fe28ad9ea5 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 29 May 2017 12:19:41 -0500 Subject: [PATCH 172/189] Return to Bed Leveling menu when done --- Marlin/ultralcd.cpp | 11 +++++++---- 1 file changed, 7 insertions(+), 4 deletions(-) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index c6978d6f0..07bc183b0 100755 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -1504,7 +1504,8 @@ void kill_screen(const char* lcd_msg) { #endif - lcd_return_to_status(); + lcd_goto_previous_menu(); // Return to the last clicked item ("Level Bed") + //LCD_MESSAGEPGM(MSG_LEVEL_BED_DONE); lcd_completion_feedback(); } @@ -1627,8 +1628,8 @@ void kill_screen(const char* lcd_msg) { /** * Step 1: Bed Level entry-point * - Cancel - * - Level Bed > * - Leveling On/Off (if there is leveling data) + * - Level Bed > * - Fade Height (Req: ENABLE_LEVELING_FADE_HEIGHT) * - Mesh Z Offset (Req: MESH_BED_LEVELING) * - Z Probe Offset (Req: HAS_BED_PROBE, Opt: BABYSTEP_ZPROBE_OFFSET) @@ -1638,8 +1639,8 @@ void kill_screen(const char* lcd_msg) { void lcd_level_bed() { START_MENU(); MENU_BACK(MSG_PREPARE); - MENU_ITEM(submenu, MSG_LEVEL_BED, _lcd_level_bed_continue); - if (leveling_is_valid()) { // Leveling data exists? Show more options. + + if (leveling_is_valid()) { _level_state = leveling_is_active(); MENU_ITEM_EDIT_CALLBACK(bool, MSG_BED_LEVELING, &_level_state, _lcd_toggle_bed_leveling); } @@ -1660,6 +1661,8 @@ void kill_screen(const char* lcd_msg) { MENU_ITEM_EDIT_CALLBACK(float32, MSG_ZPROBE_ZOFFSET, &zprobe_zoffset, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX, lcd_refresh_zprobe_zoffset); #endif + MENU_ITEM(submenu, MSG_LEVEL_BED, _lcd_level_bed_continue); + #if ENABLED(EEPROM_SETTINGS) MENU_ITEM(function, MSG_LOAD_EEPROM, lcd_load_settings); MENU_ITEM(function, MSG_STORE_EEPROM, lcd_store_settings); From 50ab9c2e04bcb378c1574cd8134cdf0a483530c0 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 29 May 2017 12:52:56 -0500 Subject: [PATCH 173/189] General cleanup of spacing, comments --- Marlin/Marlin.h | 4 ++-- Marlin/Marlin_main.cpp | 18 +++++++++--------- 2 files changed, 11 insertions(+), 11 deletions(-) diff --git a/Marlin/Marlin.h b/Marlin/Marlin.h index c18f5db53..c2e84e628 100644 --- a/Marlin/Marlin.h +++ b/Marlin/Marlin.h @@ -217,8 +217,8 @@ extern bool volumetric_enabled; extern int flow_percentage[EXTRUDERS]; // Extrusion factor for each extruder extern float filament_size[EXTRUDERS]; // cross-sectional area of filament (in millimeters), typically around 1.75 or 2.85, 0 disables the volumetric calculations for the extruder. extern float volumetric_multiplier[EXTRUDERS]; // reciprocal of cross-sectional area of filament (in square millimeters), stored this way to reduce computational burden in planner -extern bool axis_known_position[XYZ]; // axis[n].is_known -extern bool axis_homed[XYZ]; // axis[n].is_homed +extern bool axis_known_position[XYZ]; +extern bool axis_homed[XYZ]; extern volatile bool wait_for_heatup; #if HAS_RESUME_CONTINUE diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 8335d0672..b26f3ec27 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -1743,15 +1743,15 @@ static void clean_up_after_endstop_or_probe_move() { #if HAS_PROBING_PROCEDURE || HOTENDS > 1 || ENABLED(Z_PROBE_ALLEN_KEY) || ENABLED(Z_PROBE_SLED) || ENABLED(NOZZLE_CLEAN_FEATURE) || ENABLED(NOZZLE_PARK_FEATURE) || ENABLED(DELTA_AUTO_CALIBRATION) bool axis_unhomed_error(const bool x/*=true*/, const bool y/*=true*/, const bool z/*=true*/) { -#if ENABLED(HOME_AFTER_DEACTIVATE) - const bool xx = x && !axis_known_position[X_AXIS], - yy = y && !axis_known_position[Y_AXIS], - zz = z && !axis_known_position[Z_AXIS]; -#else - const bool xx = x && !axis_homed[X_AXIS], - yy = y && !axis_homed[Y_AXIS], - zz = z && !axis_homed[Z_AXIS]; -#endif + #if ENABLED(HOME_AFTER_DEACTIVATE) + const bool xx = x && !axis_known_position[X_AXIS], + yy = y && !axis_known_position[Y_AXIS], + zz = z && !axis_known_position[Z_AXIS]; + #else + const bool xx = x && !axis_homed[X_AXIS], + yy = y && !axis_homed[Y_AXIS], + zz = z && !axis_homed[Z_AXIS]; + #endif if (xx || yy || zz) { SERIAL_ECHO_START; SERIAL_ECHOPGM(MSG_HOME " "); From b2d3c8aedd458cd63090922bd8b86bba24bd1ed9 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 29 May 2017 15:15:13 -0500 Subject: [PATCH 174/189] Have G28 do a refresh of the display --- Marlin/Marlin_main.cpp | 2 ++ Marlin/ultralcd.h | 4 ++++ 2 files changed, 6 insertions(+) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index b26f3ec27..b742533c4 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -3798,6 +3798,8 @@ inline void gcode_G28(const bool always_home_all) { tool_change(old_tool_index, 0, true); #endif + lcd_refresh(); + report_current_position(); #if ENABLED(DEBUG_LEVELING_FEATURE) diff --git a/Marlin/ultralcd.h b/Marlin/ultralcd.h index 36f3b7d65..13da79e8a 100644 --- a/Marlin/ultralcd.h +++ b/Marlin/ultralcd.h @@ -46,6 +46,9 @@ void kill_screen(const char* lcd_msg); bool lcd_detected(void); + extern uint8_t lcdDrawUpdate; + inline void lcd_refresh() { lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; } + #if HAS_BUZZER void lcd_buzz(long duration, uint16_t freq); #endif @@ -158,6 +161,7 @@ inline void lcd_buttons_update() {} inline void lcd_reset_alert_level() {} inline bool lcd_detected() { return true; } + inline void lcd_refresh() {} #define LCD_MESSAGEPGM(x) NOOP #define LCD_ALERTMESSAGEPGM(x) NOOP From 2d715691384c5f1f54d9ea3433b9c061c218b342 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 29 May 2017 15:44:20 -0500 Subject: [PATCH 175/189] Fix spacing in JSON output --- Marlin/Marlin_main.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index b742533c4..bab6f8057 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -2467,7 +2467,7 @@ static void clean_up_after_endstop_or_probe_move() { #endif for (uint8_t y = 0; y < sy; y++) { #ifdef SCAD_MESH_OUTPUT - SERIAL_PROTOCOLLNPGM(" ["); // open sub-array + SERIAL_PROTOCOLPGM(" ["); // open sub-array #else if (y < 10) SERIAL_PROTOCOLCHAR(' '); SERIAL_PROTOCOL((int)y); @@ -2501,7 +2501,7 @@ static void clean_up_after_endstop_or_probe_move() { SERIAL_EOL; } #ifdef SCAD_MESH_OUTPUT - SERIAL_PROTOCOLPGM("\n];"); // close 2D array + SERIAL_PROTOCOLPGM("];"); // close 2D array #endif SERIAL_EOL; } From 4cece2d72e283d7c21be158cdde43b2c4495cdbb Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 29 May 2017 15:59:55 -0500 Subject: [PATCH 176/189] Use NAN for G29 W omitted parameters --- Marlin/Marlin_main.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index bab6f8057..6003b7881 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -4233,19 +4233,19 @@ void home_all_axes() { gcode_G28(true); } return; } - const float z = parser.seen('Z') && parser.has_value() ? parser.value_float() : 99999; - if (!WITHIN(z, -10, 10)) { + const float z = parser.seen('Z') && parser.has_value() ? parser.value_float() : NAN; + if (!isnan(z) || !WITHIN(z, -10, 10)) { SERIAL_ERROR_START; SERIAL_ERRORLNPGM("Bad Z value"); return; } - const float x = parser.seen('X') && parser.has_value() ? parser.value_float() : 99999, - y = parser.seen('Y') && parser.has_value() ? parser.value_float() : 99999; + const float x = parser.seen('X') && parser.has_value() ? parser.value_float() : NAN, + y = parser.seen('Y') && parser.has_value() ? parser.value_float() : NAN; int8_t i = parser.seen('I') && parser.has_value() ? parser.value_byte() : -1, j = parser.seen('J') && parser.has_value() ? parser.value_byte() : -1; - if (x < 99998 && y < 99998) { + if (!isnan(x) && !isnan(y)) { // Get nearest i / j from x / y i = (x - LOGICAL_X_POSITION(bilinear_start[X_AXIS]) + 0.5 * xGridSpacing) / xGridSpacing; j = (y - LOGICAL_Y_POSITION(bilinear_start[Y_AXIS]) + 0.5 * yGridSpacing) / yGridSpacing; From c6a7adc29359b135e77e0f0f2c171ab1dd3c99b3 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 29 May 2017 16:00:57 -0500 Subject: [PATCH 177/189] Patch G29 A and Q arguments to bypass setup --- Marlin/Marlin_main.cpp | 28 ++++++++++++++++++++++------ 1 file changed, 22 insertions(+), 6 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 6003b7881..158b552d3 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -4134,8 +4134,14 @@ void home_all_axes() { gcode_G28(true); } #endif #endif + #if ENABLED(PROBE_MANUALLY) + const bool seenA = parser.seen('A'), seenQ = parser.seen('Q'), no_action = seenA || seenQ; + #endif + #if ENABLED(DEBUG_LEVELING_FEATURE) && DISABLED(PROBE_MANUALLY) const bool faux = parser.seen('C') && parser.value_bool(); + #elif ENABLED(PROBE_MANUALLY) + const bool faux = no_action; #else bool constexpr faux = false; #endif @@ -4281,7 +4287,11 @@ void home_all_axes() { gcode_G28(true); } return; } - dryrun = parser.seen('D') && parser.value_bool(); + dryrun = (parser.seen('D') && parser.value_bool()) + #if ENABLED(PROBE_MANUALLY) + || no_action + #endif + ; #if ENABLED(AUTO_BED_LEVELING_LINEAR) @@ -4426,16 +4436,14 @@ void home_all_axes() { gcode_G28(true); } #if ENABLED(PROBE_MANUALLY) - const bool seenA = parser.seen('A'), seenQ = parser.seen('Q'); - // For manual probing, get the next index to probe now. // On the first probe this will be incremented to 0. - if (!seenA && !seenQ) { + if (!no_action) { ++abl_probe_index; g29_in_progress = true; } - // Abort current G29 procedure, go back to ABLStart + // Abort current G29 procedure, go back to idle state if (seenA && g29_in_progress) { SERIAL_PROTOCOLLNPGM("Manual G29 aborted"); #if HAS_SOFTWARE_ENDSTOPS @@ -4459,7 +4467,7 @@ void home_all_axes() { gcode_G28(true); } SERIAL_PROTOCOLLNPGM("idle"); } - if (seenA || seenQ) return; + if (no_action) return; if (abl_probe_index == 0) { // For the initial G29 save software endstop state @@ -4484,6 +4492,14 @@ void home_all_axes() { gcode_G28(true); } z_values[xCount][yCount] = measured_z + zoffset; + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (DEBUGGING(LEVELING)) { + SERIAL_PROTOCOLPAIR("Save X", xCount); + SERIAL_PROTOCOLPAIR(" Y", yCount); + SERIAL_PROTOCOLLNPAIR(" Z", measured_z + zoffset); + } + #endif + #elif ENABLED(AUTO_BED_LEVELING_3POINT) points[i].z = measured_z; From fc2eaab7f368aca6699a3c28ebb55a1ffeb0b7a6 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 29 May 2017 12:47:35 -0500 Subject: [PATCH 178/189] Show home option in level bed menu --- Marlin/ultralcd.cpp | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 07bc183b0..fc3d27881 100755 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -1636,11 +1636,13 @@ void kill_screen(const char* lcd_msg) { * - Load Settings (Req: EEPROM_SETTINGS) * - Save Settings (Req: EEPROM_SETTINGS) */ - void lcd_level_bed() { + void lcd_bed_leveling() { START_MENU(); MENU_BACK(MSG_PREPARE); - if (leveling_is_valid()) { + if (!(axis_known_position[X_AXIS] && axis_known_position[Y_AXIS] && axis_known_position[Z_AXIS])) + MENU_ITEM(gcode, MSG_AUTO_HOME, PSTR("G28")); + else if (leveling_is_valid()) { _level_state = leveling_is_active(); MENU_ITEM_EDIT_CALLBACK(bool, MSG_BED_LEVELING, &_level_state, _lcd_toggle_bed_leveling); } @@ -1650,7 +1652,9 @@ void kill_screen(const char* lcd_msg) { MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float62, MSG_Z_FADE_HEIGHT, &planner.z_fade_height, 0.0, 100.0, _lcd_set_z_fade_height); #endif - // Manual bed leveling, Bed Z: + // + // MBL Z Offset + // #if ENABLED(MESH_BED_LEVELING) MENU_ITEM_EDIT(float43, MSG_BED_Z, &mbl.z_offset, -1, 1); #endif @@ -2073,7 +2077,7 @@ void kill_screen(const char* lcd_msg) { #if ENABLED(PROBE_MANUALLY) if (!g29_in_progress) #endif - MENU_ITEM(submenu, MSG_BED_LEVELING, lcd_level_bed); + MENU_ITEM(submenu, MSG_BED_LEVELING, lcd_bed_leveling); #endif #if HAS_M206_COMMAND From 9677f3f2f559b47b670ea276210da588c8c6568c Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 29 May 2017 16:01:17 -0500 Subject: [PATCH 179/189] Patch up LCD Bed Leveling menu --- Marlin/Marlin_main.cpp | 2 +- Marlin/ultralcd.cpp | 122 +++++++++++++++++++++++++---------------- 2 files changed, 77 insertions(+), 47 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 158b552d3..c62fd7db7 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -4460,7 +4460,7 @@ void home_all_axes() { gcode_G28(true); } if (verbose_level || seenQ) { SERIAL_PROTOCOLPGM("Manual G29 "); if (g29_in_progress) { - SERIAL_PROTOCOLPAIR("point ", abl_probe_index + 1); + SERIAL_PROTOCOLPAIR("point ", min(abl_probe_index + 1, abl2)); SERIAL_PROTOCOLLNPAIR(" of ", abl2); } else diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index fc3d27881..b8d3380e8 100755 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -484,6 +484,11 @@ uint16_t max_display_update_time = 0; static const char moving[] PROGMEM = MSG_MOVING; static const char *sync_message = moving; + // + // Display the synchronize screen until moves are + // finished, and don't return to the caller until + // done. ** This blocks the command queue! ** + // void _lcd_synchronize() { static bool no_reentry = false; if (lcdDrawUpdate) lcd_implementation_drawmenu_static(LCD_HEIGHT >= 4 ? 1 : 0, sync_message); @@ -498,6 +503,8 @@ uint16_t max_display_update_time = 0; lcd_goto_screen(old_screen); } + // Display the synchronize screen with a custom message + // ** This blocks the command queue! ** void lcd_synchronize(const char * const msg=NULL) { sync_message = msg ? msg : moving; _lcd_synchronize(); @@ -1427,6 +1434,26 @@ void kill_screen(const char* lcd_msg) { #endif ); + // + // Raise Z to the "manual probe height" + // Don't return until done. + // ** This blocks the command queue! ** + // + void _lcd_after_probing() { + #if MANUAL_PROBE_HEIGHT > 0 + current_position[Z_AXIS] = LOGICAL_Z_POSITION(Z_MIN_POS) + MANUAL_PROBE_HEIGHT; + line_to_current(Z_AXIS); + #endif + // Display "Done" screen and wait for moves to complete + #if MANUAL_PROBE_HEIGHT > 0 || ENABLED(MESH_BED_LEVELING) + lcd_synchronize(PSTR(MSG_LEVEL_BED_DONE)); + #endif + lcd_goto_previous_menu(); + lcd_completion_feedback(); + defer_return_to_status = false; + //LCD_MESSAGEPGM(MSG_LEVEL_BED_DONE); + } + #if ENABLED(MESH_BED_LEVELING) // Utility to go to the next mesh point @@ -1445,12 +1472,22 @@ void kill_screen(const char* lcd_msg) { lcd_synchronize(); } - #endif // MESH_BED_LEVELING + #elif ENABLED(PROBE_MANUALLY) - void _lcd_level_bed_done() { - if (lcdDrawUpdate) lcd_implementation_drawedit(PSTR(MSG_LEVEL_BED_DONE)); - lcdDrawUpdate = LCDVIEW_CALL_REDRAW_NEXT; - } + bool lcd_wait_for_move; + + // + // Bed leveling is done. Wait for G29 to complete. + // A flag is used so that this can release control + // and allow the command queue to be processed. + // + void _lcd_level_bed_done() { + if (!lcd_wait_for_move) _lcd_after_probing(); + if (lcdDrawUpdate) lcd_implementation_drawedit(PSTR(MSG_LEVEL_BED_DONE)); + lcdDrawUpdate = LCDVIEW_CALL_REDRAW_NEXT; + } + + #endif void _lcd_level_goto_next_point(); @@ -1462,60 +1499,55 @@ void kill_screen(const char* lcd_msg) { if (lcd_clicked) { - // Use a hook to set the probe point z + // + // Save the current Z position + // + #if ENABLED(MESH_BED_LEVELING) + // // MBL records the position but doesn't move to the next one - mbl.set_zigzag_z(manual_probe_index, current_position[Z_AXIS]); - - #elif ENABLED(PROBE_MANUALLY) + // - // The last G29 will record but not move - if (manual_probe_index == total_probe_points - 1) - enqueue_and_echo_commands_P(PSTR("G29 V1")); + mbl.set_zigzag_z(manual_probe_index, current_position[Z_AXIS]); #endif // If done... if (++manual_probe_index >= total_probe_points) { - // Say "Done!" - lcd_goto_screen(_lcd_level_bed_done); + #if ENABLED(PROBE_MANUALLY) - // Raise Z to the "manual probe height" - #if MANUAL_PROBE_HEIGHT > 0 - current_position[Z_AXIS] = LOGICAL_Z_POSITION(Z_MIN_POS) + MANUAL_PROBE_HEIGHT; - line_to_current(Z_AXIS); - #endif + // + // The last G29 will record and enable but not move. + // Since G29 is deferred, + // + lcd_wait_for_move = true; + enqueue_and_echo_commands_P(PSTR("G29 V1")); + lcd_goto_screen(_lcd_level_bed_done); - #if MANUAL_PROBE_HEIGHT > 0 || ENABLED(MESH_BED_LEVELING) - lcd_synchronize(PSTR(MSG_LEVEL_BED_DONE)); - #endif + #elif ENABLED(MESH_BED_LEVELING) - // Enable leveling, if needed - #if ENABLED(MESH_BED_LEVELING) + _lcd_after_probing(); mbl.set_has_mesh(true); mesh_probing_done(); - #elif ENABLED(PROBE_MANUALLY) - - // ABL will be enabled due to "G29". - #endif - lcd_goto_previous_menu(); // Return to the last clicked item ("Level Bed") - - //LCD_MESSAGEPGM(MSG_LEVEL_BED_DONE); - lcd_completion_feedback(); } - else + else { + // MESH_BED_LEVELING: Z already stored, just move + // PROBE_MANUALLY: Send G29 to record Z, then move _lcd_level_goto_next_point(); + } return; } + // // Encoder knob or keypad buttons adjust the Z position + // if (encoderPosition) { refresh_cmd_timeout(); current_position[Z_AXIS] += float((int32_t)encoderPosition) * (MBL_Z_STEP); @@ -1526,8 +1558,9 @@ void kill_screen(const char* lcd_msg) { encoderPosition = 0; } - // Update on first display, then only on updates to Z position - // Show message above on clicks instead + // + // Draw on first display, then only on Z change + // if (lcdDrawUpdate) { const float v = current_position[Z_AXIS]; lcd_implementation_drawedit(PSTR(MSG_MOVE_Z), ftostr43sign(v + (v < 0 ? -0.0001 : 0.0001), '+')); @@ -1538,10 +1571,6 @@ void kill_screen(const char* lcd_msg) { * Step 6: Display "Next point: 1 / 9" while waiting for move to finish */ - #if ENABLED(PROBE_MANUALLY) - bool lcd_wait_for_move; - #endif - void _lcd_level_bed_moving() { if (lcdDrawUpdate) { char msg[10]; @@ -1578,7 +1607,7 @@ void kill_screen(const char* lcd_msg) { #elif ENABLED(PROBE_MANUALLY) - // G29 will signal when it's done + // G29 Records Z, moves, and signals when it pauses lcd_wait_for_move = true; enqueue_and_echo_commands_P(PSTR("G29 V1")); @@ -1628,13 +1657,14 @@ void kill_screen(const char* lcd_msg) { /** * Step 1: Bed Level entry-point * - Cancel - * - Leveling On/Off (if there is leveling data) + * - Auto Home (if homing needed) + * - Leveling On/Off (if data exists, and homed) * - Level Bed > - * - Fade Height (Req: ENABLE_LEVELING_FADE_HEIGHT) - * - Mesh Z Offset (Req: MESH_BED_LEVELING) - * - Z Probe Offset (Req: HAS_BED_PROBE, Opt: BABYSTEP_ZPROBE_OFFSET) - * - Load Settings (Req: EEPROM_SETTINGS) - * - Save Settings (Req: EEPROM_SETTINGS) + * - Fade Height (Req: ENABLE_LEVELING_FADE_HEIGHT) + * - Mesh Z Offset (Req: MESH_BED_LEVELING) + * - Z Probe Offset (Req: HAS_BED_PROBE, Opt: BABYSTEP_ZPROBE_OFFSET) + * - Load Settings (Req: EEPROM_SETTINGS) + * - Save Settings (Req: EEPROM_SETTINGS) */ void lcd_bed_leveling() { START_MENU(); From 51587c4b43d9b6cad4307873d9a89b9aa4a505c4 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 29 May 2017 17:48:08 -0500 Subject: [PATCH 180/189] Rename Feedrate to Velocity to match prior naming --- Marlin/language_en.h | 4 ++-- Marlin/ultralcd.cpp | 15 ++++++++------- 2 files changed, 10 insertions(+), 9 deletions(-) diff --git a/Marlin/language_en.h b/Marlin/language_en.h index 32690ebde..8de63f436 100644 --- a/Marlin/language_en.h +++ b/Marlin/language_en.h @@ -394,8 +394,8 @@ #ifndef MSG_VE_JERK #define MSG_VE_JERK _UxGT("Ve-jerk") #endif -#ifndef MSG_FEEDRATE - #define MSG_FEEDRATE _UxGT("Feedrate") +#ifndef MSG_VELOCITY + #define MSG_VELOCITY _UxGT("Velocity") #endif #ifndef MSG_VMAX #define MSG_VMAX _UxGT("Vmax ") diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index b8d3380e8..67dc2c6af 100755 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -2870,8 +2870,8 @@ void kill_screen(const char* lcd_msg) { static void lcd_refresh_zprobe_zoffset() { refresh_zprobe_zoffset(); } #endif - // M203 / M205 Feedrates - void lcd_control_motion_feedrate_menu() { + // M203 / M205 Velocity options + void lcd_control_motion_velocity_menu() { START_MENU(); MENU_BACK(MSG_MOTION); @@ -3001,18 +3001,19 @@ void kill_screen(const char* lcd_msg) { MENU_ITEM_EDIT_CALLBACK(float32, MSG_ZPROBE_ZOFFSET, &zprobe_zoffset, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX, lcd_refresh_zprobe_zoffset); #endif - // M203 / M205 Feedrate items - MENU_ITEM(submenu, MSG_FEEDRATE, lcd_control_motion_feedrate_menu); + // M203 / M205 - Feedrate items + MENU_ITEM(submenu, MSG_VELOCITY, lcd_control_motion_velocity_menu); - // M201 Acceleration items + // M201 - Acceleration items MENU_ITEM(submenu, MSG_ACCELERATION, lcd_control_motion_acceleration_menu); - // M205 Max Jerk + // M205 - Max Jerk MENU_ITEM(submenu, MSG_JERK, lcd_control_motion_jerk_menu); - // M92 Steps Per mm + // M92 - Steps Per mm MENU_ITEM(submenu, MSG_STEPS_PER_MM, lcd_control_motion_steps_per_mm_menu); + // M540 S - Abort on endstop hit when SD printing #if ENABLED(ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED) MENU_ITEM_EDIT(bool, MSG_ENDSTOP_ABORT, &stepper.abort_on_endstop_hit); #endif From 0f1e8c195de60908fa7e2b4bd374028fb5cf2b79 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 29 May 2017 19:09:38 -0500 Subject: [PATCH 181/189] Draw on LCD after value has changed --- Marlin/ultralcd.cpp | 21 +++++++++++---------- 1 file changed, 11 insertions(+), 10 deletions(-) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 67dc2c6af..68e403578 100755 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -236,23 +236,23 @@ uint16_t max_display_update_time = 0; * menu_action_setting_edit_int3(PSTR(MSG_SPEED), &feedrate_percentage, 10, 999) * */ - #define _MENU_ITEM_PART_1(TYPE, LABEL, ...) \ + #define _MENU_ITEM_PART_1(TYPE, ...) \ if (_menuLineNr == _thisItemNr) { \ - if (lcdDrawUpdate) \ - lcd_implementation_drawmenu_ ## TYPE(encoderLine == _thisItemNr, _lcdLineNr, PSTR(LABEL), ## __VA_ARGS__); \ if (lcd_clicked && encoderLine == _thisItemNr) { - #define _MENU_ITEM_PART_2(TYPE, ...) \ + #define _MENU_ITEM_PART_2(TYPE, LABEL, ...) \ menu_action_ ## TYPE(__VA_ARGS__); \ if (screen_changed) return; \ } \ + if (lcdDrawUpdate) \ + lcd_implementation_drawmenu_ ## TYPE(encoderLine == _thisItemNr, _lcdLineNr, PSTR(LABEL), ## __VA_ARGS__); \ } \ ++_thisItemNr #define MENU_ITEM(TYPE, LABEL, ...) do { \ _skipStatic = false; \ - _MENU_ITEM_PART_1(TYPE, LABEL, ## __VA_ARGS__); \ - _MENU_ITEM_PART_2(TYPE, ## __VA_ARGS__); \ + _MENU_ITEM_PART_1(TYPE, ## __VA_ARGS__); \ + _MENU_ITEM_PART_2(TYPE, LABEL, ## __VA_ARGS__); \ } while(0) #define MENU_BACK(LABEL) MENU_ITEM(back, LABEL, 0) @@ -281,10 +281,10 @@ uint16_t max_display_update_time = 0; * MENU_MULTIPLIER_ITEM generates drawing and handling code for a multiplier menu item */ #define MENU_MULTIPLIER_ITEM(type, label, ...) do { \ - _MENU_ITEM_PART_1(type, label, ## __VA_ARGS__); \ + _MENU_ITEM_PART_1(type, ## __VA_ARGS__); \ encoderRateMultiplierEnabled = true; \ lastEncoderMovementMillis = 0; \ - _MENU_ITEM_PART_2(type, ## __VA_ARGS__); \ + _MENU_ITEM_PART_2(type, label, ## __VA_ARGS__); \ } while(0) #else // !ENCODER_RATE_MULTIPLIER @@ -581,8 +581,6 @@ void lcd_status_screen() { #endif #endif // LCD_PROGRESS_BAR - lcd_implementation_status_screen(); - #if ENABLED(ULTIPANEL) if (lcd_clicked) { @@ -595,6 +593,7 @@ void lcd_status_screen() { #endif ); lcd_goto_screen(lcd_main_menu); + return; } #if ENABLED(ULTIPANEL_FEEDMULTIPLY) @@ -623,6 +622,8 @@ void lcd_status_screen() { feedrate_percentage = constrain(feedrate_percentage, 10, 999); #endif // ULTIPANEL + + lcd_implementation_status_screen(); } /** From 2c7a39bc0e8b33faf7ede260473ccafef99c4bb4 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 29 May 2017 19:50:53 -0500 Subject: [PATCH 182/189] Fix LCD print aborted message --- Marlin/ultralcd.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 68e403578..17e656fc1 100755 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -718,7 +718,8 @@ void kill_screen(const char* lcd_msg) { for (uint8_t i = 0; i < FAN_COUNT; i++) fanSpeeds[i] = 0; #endif wait_for_heatup = false; - lcd_setstatusPGM(PSTR(MSG_PRINT_PAUSED), -1); + lcd_setstatusPGM(PSTR(MSG_PRINT_ABORTED), -1); + lcd_return_to_status(); } #endif // SDSUPPORT From ca99d67ede743d1d9ada4dccedde7c7da2e3857f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 29 May 2017 19:55:26 -0500 Subject: [PATCH 183/189] Fix UBL "Info screen" menu items --- Marlin/ultralcd.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 17e656fc1..c27784438 100755 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -1766,7 +1766,7 @@ void kill_screen(const char* lcd_msg) { MENU_BACK(MSG_UBL_EDIT_MESH_MENU); MENU_ITEM_EDIT(int3, MSG_UBL_MESH_HEIGHT_AMOUNT, &ubl_height_amount, -9, 9); MENU_ITEM(function, MSG_UBL_MESH_HEIGHT_ADJUST, _lcd_ubl_adjust_height_cmd); - MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); + MENU_ITEM(function, MSG_WATCH, lcd_return_to_status); END_MENU(); } @@ -1780,7 +1780,7 @@ void kill_screen(const char* lcd_msg) { MENU_ITEM(gcode, MSG_UBL_FINE_TUNE_ALL, PSTR("G29 P4 R T")); MENU_ITEM(gcode, MSG_UBL_FINE_TUNE_CLOSEST, PSTR("G29 P4 T")); MENU_ITEM(submenu, MSG_UBL_MESH_HEIGHT_ADJUST, _lcd_ubl_height_adjust_menu); - MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); + MENU_ITEM(function, MSG_WATCH, lcd_return_to_status); END_MENU(); } @@ -1814,7 +1814,7 @@ void kill_screen(const char* lcd_msg) { MENU_ITEM(gcode, MSG_UBL_VALIDATE_ABS_MESH, PSTR("G28\nG26 C B0 H" STRINGIFY(PREHEAT_2_TEMP_HOTEND) " P")); #endif MENU_ITEM(function, MSG_UBL_VALIDATE_CUSTOM_MESH, _lcd_ubl_validate_custom_mesh); - MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); + MENU_ITEM(function, MSG_WATCH, lcd_return_to_status); END_MENU(); } @@ -1846,7 +1846,7 @@ void kill_screen(const char* lcd_msg) { MENU_BACK(MSG_UBL_TOOLS); MENU_ITEM(gcode, MSG_UBL_3POINT_MESH_LEVELING, PSTR("G29 J0")); MENU_ITEM(submenu, MSG_UBL_GRID_MESH_LEVELING, _lcd_ubl_grid_level); - MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); + MENU_ITEM(function, MSG_WATCH, lcd_return_to_status); END_MENU(); } @@ -1878,7 +1878,7 @@ void kill_screen(const char* lcd_msg) { MENU_ITEM(function, MSG_UBL_FILLIN_MESH, _lcd_ubl_fillin_amount_cmd); MENU_ITEM(function, MSG_UBL_SMART_FILLIN, _lcd_ubl_smart_fillin_cmd); MENU_ITEM(gcode, MSG_UBL_MANUAL_FILLIN, PSTR("G29 P2 B T0")); - MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); + MENU_ITEM(function, MSG_WATCH, lcd_return_to_status); END_MENU(); } @@ -1930,7 +1930,7 @@ void kill_screen(const char* lcd_msg) { MENU_ITEM(gcode, MSG_UBL_CONTINUE_MESH, PSTR("G29 P1 C")); MENU_ITEM(function, MSG_UBL_INVALIDATE_ALL, _lcd_ubl_invalidate); MENU_ITEM(gcode, MSG_UBL_INVALIDATE_CLOSEST, PSTR("G29 I")); - MENU_ITEM(submenu, MSG_WATCH, lcd_status_screen); + MENU_ITEM(function, MSG_WATCH, lcd_return_to_status); END_MENU(); } From 46b32e45484bf7d8229a41f787b851a5f9cb57a4 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 29 May 2017 20:12:10 -0500 Subject: [PATCH 184/189] Cleanup LCD interface, add lcd_reset_status --- Marlin/G26_Mesh_Validation_Tool.cpp | 4 ++-- Marlin/ubl_G29.cpp | 20 ++++++-------------- Marlin/ultralcd.cpp | 8 +++++--- Marlin/ultralcd.h | 15 ++++++++------- 4 files changed, 21 insertions(+), 26 deletions(-) diff --git a/Marlin/G26_Mesh_Validation_Tool.cpp b/Marlin/G26_Mesh_Validation_Tool.cpp index 56f2059bb..23bb34198 100644 --- a/Marlin/G26_Mesh_Validation_Tool.cpp +++ b/Marlin/G26_Mesh_Validation_Tool.cpp @@ -191,7 +191,7 @@ // ask the user to resolve the issue lcd_setstatusPGM(PSTR("Release button"), 99); // will never appear... while (ubl_lcd_clicked()) idle(); // unless this loop happens - lcd_setstatusPGM(PSTR(""), -1); + lcd_reset_status(); return true; } @@ -771,7 +771,7 @@ } #if ENABLED(ULTRA_LCD) - lcd_setstatusPGM(PSTR(""), -1); + lcd_reset_status(); lcd_quick_feedback(); #endif diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index c4f77dceb..d6453a948 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -40,8 +40,6 @@ extern float destination[XYZE], current_position[XYZE]; void lcd_return_to_status(); - bool lcd_clicked(); - void lcd_implementation_clear(); void lcd_mesh_edit_setup(float initial); float lcd_mesh_edit(); void lcd_z_offset_edit_setup(float); @@ -54,12 +52,6 @@ #define SIZE_OF_LITTLE_RAISE 1 #define BIG_RAISE_NOT_NEEDED 0 - extern void lcd_status_screen(); - typedef void (*screenFunc_t)(); - extern void lcd_goto_screen(screenFunc_t screen, const uint32_t encoder = 0); - extern void lcd_setstatus(const char* message, const bool persist); - extern void lcd_setstatusPGM(const char* message, const int8_t level); - int unified_bed_leveling::g29_verbose_level, unified_bed_leveling::g29_phase_value, unified_bed_leveling::g29_repetition_cnt, @@ -662,7 +654,7 @@ do_blocking_move_to_z(measured_z); // Get close to the bed, but leave some space so we don't damage anything // The user is not going to be locking in a new Z-Offset very often so // it won't be that painful to spin the Encoder Wheel for 1.5mm - lcd_implementation_clear(); + lcd_refresh(); lcd_z_offset_edit_setup(measured_z); KEEPALIVE_STATE(PAUSED_FOR_USER); @@ -698,7 +690,7 @@ state.z_offset = measured_z; - lcd_implementation_clear(); + lcd_refresh(); restore_ubl_active_state_and_leave(); } } @@ -940,7 +932,7 @@ SERIAL_PROTOCOLPGM("Place shim under nozzle"); LCD_MESSAGEPGM("Place shim & measure"); // TODO: Make translatable string - lcd_goto_screen(lcd_status_screen); + lcd_return_to_status(); echo_and_take_a_measurement(); const float z1 = measure_point_with_encoder(); @@ -979,7 +971,7 @@ do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); do_blocking_move_to_xy(lx, ly); - lcd_goto_screen(lcd_status_screen); + lcd_return_to_status(); mesh_index_pair location; do { location = find_closest_mesh_point_of_type(INVALID, lx, ly, USE_NOZZLE_AS_REFERENCE, NULL, false); @@ -1456,7 +1448,7 @@ if (do_ubl_mesh_map) display_map(g29_map_type); // show the user which point is being adjusted - lcd_implementation_clear(); + lcd_refresh(); lcd_mesh_edit_setup(new_z); @@ -1497,7 +1489,7 @@ z_values[location.x_index][location.y_index] = new_z; - lcd_implementation_clear(); + lcd_refresh(); } while (location.x_index >= 0 && --g29_repetition_cnt > 0); diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index c27784438..e5eebff05 100755 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -626,6 +626,8 @@ void lcd_status_screen() { lcd_implementation_status_screen(); } +void lcd_reset_status() { lcd_setstatusPGM(PSTR(""), -1); } + /** * * draw the kill screen @@ -633,7 +635,7 @@ void lcd_status_screen() { */ void kill_screen(const char* lcd_msg) { lcd_init(); - lcd_setalertstatuspgm(lcd_msg); + lcd_setalertstatusPGM(lcd_msg); #if ENABLED(DOGLCD) u8g.firstPage(); do { @@ -705,7 +707,7 @@ void kill_screen(const char* lcd_msg) { card.startFileprint(); print_job_timer.start(); #endif - lcd_setstatusPGM(PSTR(""), -1); + lcd_reset_status(); } void lcd_sdcard_stop() { @@ -4160,7 +4162,7 @@ void lcd_status_printf_P(const uint8_t level, const char * const fmt, ...) { lcd_finishstatus(level > 0); } -void lcd_setalertstatuspgm(const char * const message) { +void lcd_setalertstatusPGM(const char * const message) { lcd_setstatusPGM(message, 1); #if ENABLED(ULTIPANEL) lcd_return_to_status(); diff --git a/Marlin/ultralcd.h b/Marlin/ultralcd.h index 13da79e8a..a6226652e 100644 --- a/Marlin/ultralcd.h +++ b/Marlin/ultralcd.h @@ -39,8 +39,8 @@ bool lcd_hasstatus(); void lcd_setstatus(const char* message, const bool persist=false); void lcd_setstatusPGM(const char* message, const int8_t level=0); + void lcd_setalertstatusPGM(const char* message); void lcd_status_printf_P(const uint8_t level, const char * const fmt, ...); - void lcd_setalertstatuspgm(const char* message); void lcd_reset_alert_level(); void lcd_kill_screen(); void kill_screen(const char* lcd_msg); @@ -64,9 +64,6 @@ void bootscreen(); #endif - #define LCD_MESSAGEPGM(x) lcd_setstatusPGM(PSTR(x)) - #define LCD_ALERTMESSAGEPGM(x) lcd_setalertstatuspgm(PSTR(x)) - #define LCD_UPDATE_INTERVAL 100 #if ENABLED(ULTIPANEL) @@ -152,22 +149,26 @@ #endif #else // no LCD + inline void lcd_update() {} inline void lcd_init() {} inline bool lcd_hasstatus() { return false; } inline void lcd_setstatus(const char* const message, const bool persist=false) { UNUSED(message); UNUSED(persist); } inline void lcd_setstatusPGM(const char* const message, const int8_t level=0) { UNUSED(message); UNUSED(level); } + inline void lcd_setalertstatusPGM(const char* message) { UNUSED(message); } inline void lcd_status_printf_P(const uint8_t level, const char * const fmt, ...) { UNUSED(level); UNUSED(fmt); } inline void lcd_buttons_update() {} inline void lcd_reset_alert_level() {} inline bool lcd_detected() { return true; } inline void lcd_refresh() {} - #define LCD_MESSAGEPGM(x) NOOP - #define LCD_ALERTMESSAGEPGM(x) NOOP - #endif // ULTRA_LCD +#define LCD_MESSAGEPGM(x) lcd_setstatusPGM(PSTR(x)) +#define LCD_ALERTMESSAGEPGM(x) lcd_setalertstatusPGM(PSTR(x)) + +void lcd_reset_status(); + #if ENABLED(AUTO_BED_LEVELING_UBL) void lcd_mesh_edit_setup(float initial); float lcd_mesh_edit(); From d9c80720378199449178e141d7408f908f3d6aa9 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 30 May 2017 01:17:22 -0500 Subject: [PATCH 185/189] Edit PROPORTIONAL_FONT_RATIO comment --- Marlin/Configuration_adv.h | 9 ++++----- .../example_configurations/Cartesio/Configuration_adv.h | 9 ++++----- Marlin/example_configurations/Felix/Configuration_adv.h | 9 ++++----- .../FolgerTech-i3-2020/Configuration_adv.h | 9 ++++----- .../example_configurations/Hephestos/Configuration_adv.h | 9 ++++----- .../Hephestos_2/Configuration_adv.h | 9 ++++----- Marlin/example_configurations/K8200/Configuration_adv.h | 9 ++++----- Marlin/example_configurations/K8400/Configuration_adv.h | 9 ++++----- .../example_configurations/RigidBot/Configuration_adv.h | 9 ++++----- Marlin/example_configurations/SCARA/Configuration_adv.h | 9 ++++----- Marlin/example_configurations/TAZ4/Configuration_adv.h | 9 ++++----- .../example_configurations/TinyBoy2/Configuration_adv.h | 9 ++++----- Marlin/example_configurations/WITBOX/Configuration_adv.h | 9 ++++----- .../delta/FLSUN/auto_calibrate/Configuration_adv.h | 9 ++++----- .../delta/FLSUN/kossel_mini/Configuration_adv.h | 9 ++++----- .../delta/generic/Configuration_adv.h | 9 ++++----- .../delta/kossel_mini/Configuration_adv.h | 9 ++++----- .../delta/kossel_pro/Configuration_adv.h | 9 ++++----- .../delta/kossel_xl/Configuration_adv.h | 9 ++++----- .../gCreate_gMax1.5+/Configuration_adv.h | 9 ++++----- .../example_configurations/makibox/Configuration_adv.h | 9 ++++----- .../tvrrug/Round2/Configuration_adv.h | 9 ++++----- Marlin/example_configurations/wt150/Configuration_adv.h | 9 ++++----- 23 files changed, 92 insertions(+), 115 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index d593ed095..2f9297df5 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1221,12 +1221,11 @@ //#define NO_WORKSPACE_OFFSETS /** - * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number - * of spaces to be output by the ratio set below. This allows for better alignment of output for commands - * like G29 O, which renders a mesh/grid. + * Set the number of proportional font spaces required to fill up a typical character space. + * This can help to better align the output of commands like `G29 O` Mesh Output. * - * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust - * accordingly for your client and font. + * For clients that use a fixed-width font (like OctoPrint), leave this set to 1.0. + * Otherwise, adjust according to your client and font. */ #define PROPORTIONAL_FONT_RATIO 1.0 diff --git a/Marlin/example_configurations/Cartesio/Configuration_adv.h b/Marlin/example_configurations/Cartesio/Configuration_adv.h index a8f4c3166..6a0ee92dd 100644 --- a/Marlin/example_configurations/Cartesio/Configuration_adv.h +++ b/Marlin/example_configurations/Cartesio/Configuration_adv.h @@ -1214,12 +1214,11 @@ //#define NO_WORKSPACE_OFFSETS /** - * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number - * of spaces to be output by the ratio set below. This allows for better alignment of output for commands - * like G29 O, which renders a mesh/grid. + * Set the number of proportional font spaces required to fill up a typical character space. + * This can help to better align the output of commands like `G29 O` Mesh Output. * - * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust - * accordingly for your client and font. + * For clients that use a fixed-width font (like OctoPrint), leave this set to 1.0. + * Otherwise, adjust according to your client and font. */ #define PROPORTIONAL_FONT_RATIO 1.0 diff --git a/Marlin/example_configurations/Felix/Configuration_adv.h b/Marlin/example_configurations/Felix/Configuration_adv.h index 3132bf9ff..bee2707d6 100644 --- a/Marlin/example_configurations/Felix/Configuration_adv.h +++ b/Marlin/example_configurations/Felix/Configuration_adv.h @@ -1214,12 +1214,11 @@ //#define NO_WORKSPACE_OFFSETS /** - * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number - * of spaces to be output by the ratio set below. This allows for better alignment of output for commands - * like G29 O, which renders a mesh/grid. + * Set the number of proportional font spaces required to fill up a typical character space. + * This can help to better align the output of commands like `G29 O` Mesh Output. * - * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust - * accordingly for your client and font. + * For clients that use a fixed-width font (like OctoPrint), leave this set to 1.0. + * Otherwise, adjust according to your client and font. */ #define PROPORTIONAL_FONT_RATIO 1.0 diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h index 142cd1d24..3500114a1 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h @@ -1227,12 +1227,11 @@ //#define NO_WORKSPACE_OFFSETS /** - * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number - * of spaces to be output by the ratio set below. This allows for better alignment of output for commands - * like G29 O, which renders a mesh/grid. + * Set the number of proportional font spaces required to fill up a typical character space. + * This can help to better align the output of commands like `G29 O` Mesh Output. * - * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust - * accordingly for your client and font. + * For clients that use a fixed-width font (like OctoPrint), leave this set to 1.0. + * Otherwise, adjust according to your client and font. */ #define PROPORTIONAL_FONT_RATIO 1.5 diff --git a/Marlin/example_configurations/Hephestos/Configuration_adv.h b/Marlin/example_configurations/Hephestos/Configuration_adv.h index 171ab3e4d..c9b0574eb 100644 --- a/Marlin/example_configurations/Hephestos/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos/Configuration_adv.h @@ -1214,12 +1214,11 @@ //#define NO_WORKSPACE_OFFSETS /** - * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number - * of spaces to be output by the ratio set below. This allows for better alignment of output for commands - * like G29 O, which renders a mesh/grid. + * Set the number of proportional font spaces required to fill up a typical character space. + * This can help to better align the output of commands like `G29 O` Mesh Output. * - * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust - * accordingly for your client and font. + * For clients that use a fixed-width font (like OctoPrint), leave this set to 1.0. + * Otherwise, adjust according to your client and font. */ #define PROPORTIONAL_FONT_RATIO 1.0 diff --git a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h index fb7869435..b60370fe5 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h @@ -1198,12 +1198,11 @@ //#define NO_WORKSPACE_OFFSETS /** - * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number - * of spaces to be output by the ratio set below. This allows for better alignment of output for commands - * like G29 O, which renders a mesh/grid. + * Set the number of proportional font spaces required to fill up a typical character space. + * This can help to better align the output of commands like `G29 O` Mesh Output. * - * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust - * accordingly for your client and font. + * For clients that use a fixed-width font (like OctoPrint), leave this set to 1.0. + * Otherwise, adjust according to your client and font. */ #define PROPORTIONAL_FONT_RATIO 1.0 diff --git a/Marlin/example_configurations/K8200/Configuration_adv.h b/Marlin/example_configurations/K8200/Configuration_adv.h index 44aae82fa..645a97d4c 100644 --- a/Marlin/example_configurations/K8200/Configuration_adv.h +++ b/Marlin/example_configurations/K8200/Configuration_adv.h @@ -1227,12 +1227,11 @@ //#define NO_WORKSPACE_OFFSETS /** - * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number - * of spaces to be output by the ratio set below. This allows for better alignment of output for commands - * like G29 O, which renders a mesh/grid. + * Set the number of proportional font spaces required to fill up a typical character space. + * This can help to better align the output of commands like `G29 O` Mesh Output. * - * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust - * accordingly for your client and font. + * For clients that use a fixed-width font (like OctoPrint), leave this set to 1.0. + * Otherwise, adjust according to your client and font. */ #define PROPORTIONAL_FONT_RATIO 1.0 diff --git a/Marlin/example_configurations/K8400/Configuration_adv.h b/Marlin/example_configurations/K8400/Configuration_adv.h index a04d83baf..9c7555d6b 100644 --- a/Marlin/example_configurations/K8400/Configuration_adv.h +++ b/Marlin/example_configurations/K8400/Configuration_adv.h @@ -1214,12 +1214,11 @@ //#define NO_WORKSPACE_OFFSETS /** - * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number - * of spaces to be output by the ratio set below. This allows for better alignment of output for commands - * like G29 O, which renders a mesh/grid. + * Set the number of proportional font spaces required to fill up a typical character space. + * This can help to better align the output of commands like `G29 O` Mesh Output. * - * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust - * accordingly for your client and font. + * For clients that use a fixed-width font (like OctoPrint), leave this set to 1.0. + * Otherwise, adjust according to your client and font. */ #define PROPORTIONAL_FONT_RATIO 1.0 diff --git a/Marlin/example_configurations/RigidBot/Configuration_adv.h b/Marlin/example_configurations/RigidBot/Configuration_adv.h index 3605da6a7..d7a156b45 100644 --- a/Marlin/example_configurations/RigidBot/Configuration_adv.h +++ b/Marlin/example_configurations/RigidBot/Configuration_adv.h @@ -1214,12 +1214,11 @@ //#define NO_WORKSPACE_OFFSETS /** - * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number - * of spaces to be output by the ratio set below. This allows for better alignment of output for commands - * like G29 O, which renders a mesh/grid. + * Set the number of proportional font spaces required to fill up a typical character space. + * This can help to better align the output of commands like `G29 O` Mesh Output. * - * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust - * accordingly for your client and font. + * For clients that use a fixed-width font (like OctoPrint), leave this set to 1.0. + * Otherwise, adjust according to your client and font. */ #define PROPORTIONAL_FONT_RATIO 1.0 diff --git a/Marlin/example_configurations/SCARA/Configuration_adv.h b/Marlin/example_configurations/SCARA/Configuration_adv.h index 6bfee737d..836b31f60 100644 --- a/Marlin/example_configurations/SCARA/Configuration_adv.h +++ b/Marlin/example_configurations/SCARA/Configuration_adv.h @@ -1214,12 +1214,11 @@ //#define NO_WORKSPACE_OFFSETS /** - * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number - * of spaces to be output by the ratio set below. This allows for better alignment of output for commands - * like G29 O, which renders a mesh/grid. + * Set the number of proportional font spaces required to fill up a typical character space. + * This can help to better align the output of commands like `G29 O` Mesh Output. * - * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust - * accordingly for your client and font. + * For clients that use a fixed-width font (like OctoPrint), leave this set to 1.0. + * Otherwise, adjust according to your client and font. */ #define PROPORTIONAL_FONT_RATIO 1.0 diff --git a/Marlin/example_configurations/TAZ4/Configuration_adv.h b/Marlin/example_configurations/TAZ4/Configuration_adv.h index 05caf958e..caa32a8a0 100644 --- a/Marlin/example_configurations/TAZ4/Configuration_adv.h +++ b/Marlin/example_configurations/TAZ4/Configuration_adv.h @@ -1214,12 +1214,11 @@ //#define NO_WORKSPACE_OFFSETS /** - * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number - * of spaces to be output by the ratio set below. This allows for better alignment of output for commands - * like G29 O, which renders a mesh/grid. + * Set the number of proportional font spaces required to fill up a typical character space. + * This can help to better align the output of commands like `G29 O` Mesh Output. * - * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust - * accordingly for your client and font. + * For clients that use a fixed-width font (like OctoPrint), leave this set to 1.0. + * Otherwise, adjust according to your client and font. */ #define PROPORTIONAL_FONT_RATIO 1.0 diff --git a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h index 488da0e2b..3ffa32eeb 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h @@ -1217,12 +1217,11 @@ //#define NO_WORKSPACE_OFFSETS /** - * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number - * of spaces to be output by the ratio set below. This allows for better alignment of output for commands - * like G29 O, which renders a mesh/grid. + * Set the number of proportional font spaces required to fill up a typical character space. + * This can help to better align the output of commands like `G29 O` Mesh Output. * - * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust - * accordingly for your client and font. + * For clients that use a fixed-width font (like OctoPrint), leave this set to 1.0. + * Otherwise, adjust according to your client and font. */ #define PROPORTIONAL_FONT_RATIO 1.0 diff --git a/Marlin/example_configurations/WITBOX/Configuration_adv.h b/Marlin/example_configurations/WITBOX/Configuration_adv.h index 171ab3e4d..c9b0574eb 100644 --- a/Marlin/example_configurations/WITBOX/Configuration_adv.h +++ b/Marlin/example_configurations/WITBOX/Configuration_adv.h @@ -1214,12 +1214,11 @@ //#define NO_WORKSPACE_OFFSETS /** - * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number - * of spaces to be output by the ratio set below. This allows for better alignment of output for commands - * like G29 O, which renders a mesh/grid. + * Set the number of proportional font spaces required to fill up a typical character space. + * This can help to better align the output of commands like `G29 O` Mesh Output. * - * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust - * accordingly for your client and font. + * For clients that use a fixed-width font (like OctoPrint), leave this set to 1.0. + * Otherwise, adjust according to your client and font. */ #define PROPORTIONAL_FONT_RATIO 1.0 diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h index eb44f9e09..95f6ddcb3 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h @@ -1219,12 +1219,11 @@ //#define NO_WORKSPACE_OFFSETS /** - * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number - * of spaces to be output by the ratio set below. This allows for better alignment of output for commands - * like G29 O, which renders a mesh/grid. + * Set the number of proportional font spaces required to fill up a typical character space. + * This can help to better align the output of commands like `G29 O` Mesh Output. * - * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust - * accordingly for your client and font. + * For clients that use a fixed-width font (like OctoPrint), leave this set to 1.0. + * Otherwise, adjust according to your client and font. */ #define PROPORTIONAL_FONT_RATIO 1.0 diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h index 6eed64c6f..79e9f1d45 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h @@ -1218,12 +1218,11 @@ //#define NO_WORKSPACE_OFFSETS /** - * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number - * of spaces to be output by the ratio set below. This allows for better alignment of output for commands - * like G29 O, which renders a mesh/grid. + * Set the number of proportional font spaces required to fill up a typical character space. + * This can help to better align the output of commands like `G29 O` Mesh Output. * - * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust - * accordingly for your client and font. + * For clients that use a fixed-width font (like OctoPrint), leave this set to 1.0. + * Otherwise, adjust according to your client and font. */ #define PROPORTIONAL_FONT_RATIO 1.0 diff --git a/Marlin/example_configurations/delta/generic/Configuration_adv.h b/Marlin/example_configurations/delta/generic/Configuration_adv.h index 6f45736b6..cd8302aea 100644 --- a/Marlin/example_configurations/delta/generic/Configuration_adv.h +++ b/Marlin/example_configurations/delta/generic/Configuration_adv.h @@ -1216,12 +1216,11 @@ //#define NO_WORKSPACE_OFFSETS /** - * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number - * of spaces to be output by the ratio set below. This allows for better alignment of output for commands - * like G29 O, which renders a mesh/grid. + * Set the number of proportional font spaces required to fill up a typical character space. + * This can help to better align the output of commands like `G29 O` Mesh Output. * - * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust - * accordingly for your client and font. + * For clients that use a fixed-width font (like OctoPrint), leave this set to 1.0. + * Otherwise, adjust according to your client and font. */ #define PROPORTIONAL_FONT_RATIO 1.0 diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h index 6f45736b6..cd8302aea 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h @@ -1216,12 +1216,11 @@ //#define NO_WORKSPACE_OFFSETS /** - * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number - * of spaces to be output by the ratio set below. This allows for better alignment of output for commands - * like G29 O, which renders a mesh/grid. + * Set the number of proportional font spaces required to fill up a typical character space. + * This can help to better align the output of commands like `G29 O` Mesh Output. * - * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust - * accordingly for your client and font. + * For clients that use a fixed-width font (like OctoPrint), leave this set to 1.0. + * Otherwise, adjust according to your client and font. */ #define PROPORTIONAL_FONT_RATIO 1.0 diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h index 8f7ae5496..d1821c5ff 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h @@ -1221,12 +1221,11 @@ //#define NO_WORKSPACE_OFFSETS /** - * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number - * of spaces to be output by the ratio set below. This allows for better alignment of output for commands - * like G29 O, which renders a mesh/grid. + * Set the number of proportional font spaces required to fill up a typical character space. + * This can help to better align the output of commands like `G29 O` Mesh Output. * - * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust - * accordingly for your client and font. + * For clients that use a fixed-width font (like OctoPrint), leave this set to 1.0. + * Otherwise, adjust according to your client and font. */ #define PROPORTIONAL_FONT_RATIO 1.0 diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h index 779dbe9a9..0f258e03a 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h @@ -1216,12 +1216,11 @@ //#define NO_WORKSPACE_OFFSETS /** - * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number - * of spaces to be output by the ratio set below. This allows for better alignment of output for commands - * like G29 O, which renders a mesh/grid. + * Set the number of proportional font spaces required to fill up a typical character space. + * This can help to better align the output of commands like `G29 O` Mesh Output. * - * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust - * accordingly for your client and font. + * For clients that use a fixed-width font (like OctoPrint), leave this set to 1.0. + * Otherwise, adjust according to your client and font. */ #define PROPORTIONAL_FONT_RATIO 1.0 diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h index 71a3d90e0..e0da01ead 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h @@ -1223,12 +1223,11 @@ #define NO_WORKSPACE_OFFSETS /** - * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number - * of spaces to be output by the ratio set below. This allows for better alignment of output for commands - * like G29 O, which renders a mesh/grid. + * Set the number of proportional font spaces required to fill up a typical character space. + * This can help to better align the output of commands like `G29 O` Mesh Output. * - * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust - * accordingly for your client and font. + * For clients that use a fixed-width font (like OctoPrint), leave this set to 1.0. + * Otherwise, adjust according to your client and font. */ #define PROPORTIONAL_FONT_RATIO 1.5 diff --git a/Marlin/example_configurations/makibox/Configuration_adv.h b/Marlin/example_configurations/makibox/Configuration_adv.h index 9aa560794..aecf3c2af 100644 --- a/Marlin/example_configurations/makibox/Configuration_adv.h +++ b/Marlin/example_configurations/makibox/Configuration_adv.h @@ -1214,12 +1214,11 @@ //#define NO_WORKSPACE_OFFSETS /** - * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number - * of spaces to be output by the ratio set below. This allows for better alignment of output for commands - * like G29 O, which renders a mesh/grid. + * Set the number of proportional font spaces required to fill up a typical character space. + * This can help to better align the output of commands like `G29 O` Mesh Output. * - * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust - * accordingly for your client and font. + * For clients that use a fixed-width font (like OctoPrint), leave this set to 1.0. + * Otherwise, adjust according to your client and font. */ #define PROPORTIONAL_FONT_RATIO 1.0 diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h index 660d479b5..bf5264a0e 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h @@ -1214,12 +1214,11 @@ //#define NO_WORKSPACE_OFFSETS /** - * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number - * of spaces to be output by the ratio set below. This allows for better alignment of output for commands - * like G29 O, which renders a mesh/grid. + * Set the number of proportional font spaces required to fill up a typical character space. + * This can help to better align the output of commands like `G29 O` Mesh Output. * - * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust - * accordingly for your client and font. + * For clients that use a fixed-width font (like OctoPrint), leave this set to 1.0. + * Otherwise, adjust according to your client and font. */ #define PROPORTIONAL_FONT_RATIO 1.0 diff --git a/Marlin/example_configurations/wt150/Configuration_adv.h b/Marlin/example_configurations/wt150/Configuration_adv.h index bf586bdba..83daabe77 100644 --- a/Marlin/example_configurations/wt150/Configuration_adv.h +++ b/Marlin/example_configurations/wt150/Configuration_adv.h @@ -1217,12 +1217,11 @@ //#define NO_WORKSPACE_OFFSETS /** - * This affects the way Marlin outputs blacks of spaces via serial connection by multiplying the number - * of spaces to be output by the ratio set below. This allows for better alignment of output for commands - * like G29 O, which renders a mesh/grid. + * Set the number of proportional font spaces required to fill up a typical character space. + * This can help to better align the output of commands like `G29 O` Mesh Output. * - * For clients that use a fixed-width font (like OctoPrint), leave this at 1.0; otherwise, adjust - * accordingly for your client and font. + * For clients that use a fixed-width font (like OctoPrint), leave this set to 1.0. + * Otherwise, adjust according to your client and font. */ #define PROPORTIONAL_FONT_RATIO 1.0 From 74d6dee920b09aaa47839ee5a19de3129ea2125f Mon Sep 17 00:00:00 2001 From: Tannoo Date: Sat, 27 May 2017 17:49:18 -0600 Subject: [PATCH 186/189] User Command (Script) Menu The menu (commands / scripts) is configurable in `Configuration_adv.h`. - Added conditionals. - Changed script handling. - Slimmed and working! - Added Status message. - Returning to lcd status screen now! - Example Configs Updated. - Cleanups by @thinkyhead --- .travis.yml | 1 + Marlin/Configuration_adv.h | 23 ++++++++ .../Cartesio/Configuration_adv.h | 23 ++++++++ .../Felix/Configuration_adv.h | 23 ++++++++ .../FolgerTech-i3-2020/Configuration_adv.h | 23 ++++++++ .../Hephestos/Configuration_adv.h | 23 ++++++++ .../Hephestos_2/Configuration_adv.h | 23 ++++++++ .../K8200/Configuration_adv.h | 23 ++++++++ .../K8400/Configuration_adv.h | 23 ++++++++ .../RigidBot/Configuration_adv.h | 23 ++++++++ .../SCARA/Configuration_adv.h | 23 ++++++++ .../TAZ4/Configuration_adv.h | 23 ++++++++ .../TinyBoy2/Configuration_adv.h | 23 ++++++++ .../WITBOX/Configuration_adv.h | 23 ++++++++ .../FLSUN/auto_calibrate/Configuration_adv.h | 23 ++++++++ .../FLSUN/kossel_mini/Configuration_adv.h | 23 ++++++++ .../delta/generic/Configuration_adv.h | 23 ++++++++ .../delta/kossel_mini/Configuration_adv.h | 23 ++++++++ .../delta/kossel_pro/Configuration_adv.h | 23 ++++++++ .../delta/kossel_xl/Configuration_adv.h | 23 ++++++++ .../gCreate_gMax1.5+/Configuration_adv.h | 23 ++++++++ .../makibox/Configuration_adv.h | 23 ++++++++ .../tvrrug/Round2/Configuration_adv.h | 23 ++++++++ .../wt150/Configuration_adv.h | 23 ++++++++ Marlin/language_en.h | 3 + Marlin/ultralcd.cpp | 56 +++++++++++++++++++ 26 files changed, 589 insertions(+) diff --git a/.travis.yml b/.travis.yml index 20a507510..03f7585d0 100644 --- a/.travis.yml +++ b/.travis.yml @@ -126,6 +126,7 @@ script: # - restore_configs - opt_enable AUTO_BED_LEVELING_UBL UBL_G26_MESH_EDITING ENABLE_LEVELING_FADE_HEIGHT FIX_MOUNTED_PROBE EEPROM_SETTINGS G3D_PANEL + - opt_enable_adv CUSTOM_USER_MENUS - build_marlin # # Test a Sled Z Probe diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 2f9297df5..a23e90bc7 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1234,4 +1234,27 @@ */ #define FASTER_GCODE_PARSER +/** + * User-defined menu items that execute custom GCode + */ +//#define CUSTOM_USER_MENUS +#if ENABLED(CUSTOM_USER_MENUS) + #define USER_SCRIPT_DONE "M117 User Script Done" + + #define USER_DESC_1 "Home & UBL Info" + #define USER_GCODE_1 "G28\nG29 W" + + #define USER_DESC_2 "Preheat for PLA" + #define USER_GCODE_2 "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) + + #define USER_DESC_3 "Preheat for ABS" + #define USER_GCODE_3 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) + + #define USER_DESC_4 "Heat Bed/Home/Level" + #define USER_GCODE_4 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nG28\nG29" + + #define USER_DESC_5 "Home & Info" + #define USER_GCODE_5 "G28\nM503" +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/Cartesio/Configuration_adv.h b/Marlin/example_configurations/Cartesio/Configuration_adv.h index 6a0ee92dd..caba55f7e 100644 --- a/Marlin/example_configurations/Cartesio/Configuration_adv.h +++ b/Marlin/example_configurations/Cartesio/Configuration_adv.h @@ -1227,4 +1227,27 @@ */ #define FASTER_GCODE_PARSER +/** + * User-defined menu items that execute custom GCode + */ +//#define CUSTOM_USER_MENUS +#if ENABLED(CUSTOM_USER_MENUS) + #define USER_SCRIPT_DONE "M117 User Script Done" + + #define USER_DESC_1 "Home & UBL Info" + #define USER_GCODE_1 "G28\nG29 W" + + #define USER_DESC_2 "Preheat for PLA" + #define USER_GCODE_2 "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) + + #define USER_DESC_3 "Preheat for ABS" + #define USER_GCODE_3 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) + + #define USER_DESC_4 "Heat Bed/Home/Level" + #define USER_GCODE_4 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nG28\nG29" + + #define USER_DESC_5 "Home & Info" + #define USER_GCODE_5 "G28\nM503" +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/Felix/Configuration_adv.h b/Marlin/example_configurations/Felix/Configuration_adv.h index bee2707d6..6b5718d51 100644 --- a/Marlin/example_configurations/Felix/Configuration_adv.h +++ b/Marlin/example_configurations/Felix/Configuration_adv.h @@ -1227,4 +1227,27 @@ */ #define FASTER_GCODE_PARSER +/** + * User-defined menu items that execute custom GCode + */ +//#define CUSTOM_USER_MENUS +#if ENABLED(CUSTOM_USER_MENUS) + #define USER_SCRIPT_DONE "M117 User Script Done" + + #define USER_DESC_1 "Home & UBL Info" + #define USER_GCODE_1 "G28\nG29 W" + + #define USER_DESC_2 "Preheat for PLA" + #define USER_GCODE_2 "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) + + #define USER_DESC_3 "Preheat for ABS" + #define USER_GCODE_3 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) + + #define USER_DESC_4 "Heat Bed/Home/Level" + #define USER_GCODE_4 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nG28\nG29" + + //#define USER_DESC_5 "Home & Info" + //#define USER_GCODE_5 "G28\nM503" +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h index 3500114a1..013518b78 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h @@ -1240,4 +1240,27 @@ */ #define FASTER_GCODE_PARSER +/** + * User-defined menu items that execute custom GCode + */ +//#define CUSTOM_USER_MENUS +#if ENABLED(CUSTOM_USER_MENUS) + #define USER_SCRIPT_DONE "M117 User Script Done" + + #define USER_DESC_1 "Home & UBL Info" + #define USER_GCODE_1 "G28\nG29 W" + + #define USER_DESC_2 "Preheat for PLA" + #define USER_GCODE_2 "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) + + #define USER_DESC_3 "Preheat for ABS" + #define USER_GCODE_3 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) + + #define USER_DESC_4 "Heat Bed/Home/Level" + #define USER_GCODE_4 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nG28\nG29" + + //#define USER_DESC_5 "Home & Info" + //#define USER_GCODE_5 "G28\nM503" +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/Hephestos/Configuration_adv.h b/Marlin/example_configurations/Hephestos/Configuration_adv.h index c9b0574eb..bcef1672e 100644 --- a/Marlin/example_configurations/Hephestos/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos/Configuration_adv.h @@ -1227,4 +1227,27 @@ */ #define FASTER_GCODE_PARSER +/** + * User-defined menu items that execute custom GCode + */ +//#define CUSTOM_USER_MENUS +#if ENABLED(CUSTOM_USER_MENUS) + #define USER_SCRIPT_DONE "M117 User Script Done" + + #define USER_DESC_1 "Home & UBL Info" + #define USER_GCODE_1 "G28\nG29 W" + + #define USER_DESC_2 "Preheat for PLA" + #define USER_GCODE_2 "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) + + #define USER_DESC_3 "Preheat for ABS" + #define USER_GCODE_3 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) + + #define USER_DESC_4 "Heat Bed/Home/Level" + #define USER_GCODE_4 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nG28\nG29" + + //#define USER_DESC_5 "Home & Info" + //#define USER_GCODE_5 "G28\nM503" +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h index b60370fe5..cb227fd8f 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h @@ -1211,4 +1211,27 @@ */ #define FASTER_GCODE_PARSER +/** + * User-defined menu items that execute custom GCode + */ +//#define CUSTOM_USER_MENUS +#if ENABLED(CUSTOM_USER_MENUS) + #define USER_SCRIPT_DONE "M117 User Script Done" + + #define USER_DESC_1 "Home & UBL Info" + #define USER_GCODE_1 "G28\nG29 W" + + #define USER_DESC_2 "Preheat for PLA" + #define USER_GCODE_2 "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) + + #define USER_DESC_3 "Preheat for ABS" + #define USER_GCODE_3 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) + + #define USER_DESC_4 "Heat Bed/Home/Level" + #define USER_GCODE_4 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nG28\nG29" + + //#define USER_DESC_5 "Home & Info" + //#define USER_GCODE_5 "G28\nM503" +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/K8200/Configuration_adv.h b/Marlin/example_configurations/K8200/Configuration_adv.h index 645a97d4c..692af7fab 100644 --- a/Marlin/example_configurations/K8200/Configuration_adv.h +++ b/Marlin/example_configurations/K8200/Configuration_adv.h @@ -1240,4 +1240,27 @@ */ #define FASTER_GCODE_PARSER +/** + * User-defined menu items that execute custom GCode + */ +//#define CUSTOM_USER_MENUS +#if ENABLED(CUSTOM_USER_MENUS) + #define USER_SCRIPT_DONE "M117 User Script Done" + + #define USER_DESC_1 "Home & UBL Info" + #define USER_GCODE_1 "G28\nG29 W" + + #define USER_DESC_2 "Preheat for PLA" + #define USER_GCODE_2 "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) + + #define USER_DESC_3 "Preheat for ABS" + #define USER_GCODE_3 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) + + #define USER_DESC_4 "Heat Bed/Home/Level" + #define USER_GCODE_4 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nG28\nG29" + + //#define USER_DESC_5 "Home & Info" + //#define USER_GCODE_5 "G28\nM503" +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/K8400/Configuration_adv.h b/Marlin/example_configurations/K8400/Configuration_adv.h index 9c7555d6b..7999653d2 100644 --- a/Marlin/example_configurations/K8400/Configuration_adv.h +++ b/Marlin/example_configurations/K8400/Configuration_adv.h @@ -1227,4 +1227,27 @@ */ #define FASTER_GCODE_PARSER +/** + * User-defined menu items that execute custom GCode + */ +//#define CUSTOM_USER_MENUS +#if ENABLED(CUSTOM_USER_MENUS) + #define USER_SCRIPT_DONE "M117 User Script Done" + + #define USER_DESC_1 "Home & UBL Info" + #define USER_GCODE_1 "G28\nG29 W" + + #define USER_DESC_2 "Preheat for PLA" + #define USER_GCODE_2 "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) + + #define USER_DESC_3 "Preheat for ABS" + #define USER_GCODE_3 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) + + #define USER_DESC_4 "Heat Bed/Home/Level" + #define USER_GCODE_4 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nG28\nG29" + + //#define USER_DESC_5 "Home & Info" + //#define USER_GCODE_5 "G28\nM503" +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/RigidBot/Configuration_adv.h b/Marlin/example_configurations/RigidBot/Configuration_adv.h index d7a156b45..5f84cd820 100644 --- a/Marlin/example_configurations/RigidBot/Configuration_adv.h +++ b/Marlin/example_configurations/RigidBot/Configuration_adv.h @@ -1227,4 +1227,27 @@ */ #define FASTER_GCODE_PARSER +/** + * User-defined menu items that execute custom GCode + */ +//#define CUSTOM_USER_MENUS +#if ENABLED(CUSTOM_USER_MENUS) + #define USER_SCRIPT_DONE "M117 User Script Done" + + #define USER_DESC_1 "Home & UBL Info" + #define USER_GCODE_1 "G28\nG29 W" + + #define USER_DESC_2 "Preheat for PLA" + #define USER_GCODE_2 "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) + + #define USER_DESC_3 "Preheat for ABS" + #define USER_GCODE_3 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) + + #define USER_DESC_4 "Heat Bed/Home/Level" + #define USER_GCODE_4 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nG28\nG29" + + //#define USER_DESC_5 "Home & Info" + //#define USER_GCODE_5 "G28\nM503" +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/SCARA/Configuration_adv.h b/Marlin/example_configurations/SCARA/Configuration_adv.h index 836b31f60..fa1c96532 100644 --- a/Marlin/example_configurations/SCARA/Configuration_adv.h +++ b/Marlin/example_configurations/SCARA/Configuration_adv.h @@ -1227,4 +1227,27 @@ */ #define FASTER_GCODE_PARSER +/** + * User-defined menu items that execute custom GCode + */ +//#define CUSTOM_USER_MENUS +#if ENABLED(CUSTOM_USER_MENUS) + #define USER_SCRIPT_DONE "M117 User Script Done" + + #define USER_DESC_1 "Home & UBL Info" + #define USER_GCODE_1 "G28\nG29 W" + + #define USER_DESC_2 "Preheat for PLA" + #define USER_GCODE_2 "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) + + #define USER_DESC_3 "Preheat for ABS" + #define USER_GCODE_3 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) + + #define USER_DESC_4 "Heat Bed/Home/Level" + #define USER_GCODE_4 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nG28\nG29" + + //#define USER_DESC_5 "Home & Info" + //#define USER_GCODE_5 "G28\nM503" +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/TAZ4/Configuration_adv.h b/Marlin/example_configurations/TAZ4/Configuration_adv.h index caa32a8a0..9a50d0971 100644 --- a/Marlin/example_configurations/TAZ4/Configuration_adv.h +++ b/Marlin/example_configurations/TAZ4/Configuration_adv.h @@ -1227,4 +1227,27 @@ */ #define FASTER_GCODE_PARSER +/** + * User-defined menu items that execute custom GCode + */ +//#define CUSTOM_USER_MENUS +#if ENABLED(CUSTOM_USER_MENUS) + #define USER_SCRIPT_DONE "M117 User Script Done" + + #define USER_DESC_1 "Home & UBL Info" + #define USER_GCODE_1 "G28\nG29 W" + + #define USER_DESC_2 "Preheat for PLA" + #define USER_GCODE_2 "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) + + #define USER_DESC_3 "Preheat for ABS" + #define USER_GCODE_3 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) + + #define USER_DESC_4 "Heat Bed/Home/Level" + #define USER_GCODE_4 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nG28\nG29" + + //#define USER_DESC_5 "Home & Info" + //#define USER_GCODE_5 "G28\nM503" +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h index 3ffa32eeb..0a498ac62 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h @@ -1230,4 +1230,27 @@ */ #define FASTER_GCODE_PARSER +/** + * User-defined menu items that execute custom GCode + */ +//#define CUSTOM_USER_MENUS +#if ENABLED(CUSTOM_USER_MENUS) + #define USER_SCRIPT_DONE "M117 User Script Done" + + #define USER_DESC_1 "Home & UBL Info" + #define USER_GCODE_1 "G28\nG29 W" + + #define USER_DESC_2 "Preheat for PLA" + #define USER_GCODE_2 "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) + + #define USER_DESC_3 "Preheat for ABS" + #define USER_GCODE_3 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) + + #define USER_DESC_4 "Heat Bed/Home/Level" + #define USER_GCODE_4 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nG28\nG29" + + //#define USER_DESC_5 "Home & Info" + //#define USER_GCODE_5 "G28\nM503" +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/WITBOX/Configuration_adv.h b/Marlin/example_configurations/WITBOX/Configuration_adv.h index c9b0574eb..bcef1672e 100644 --- a/Marlin/example_configurations/WITBOX/Configuration_adv.h +++ b/Marlin/example_configurations/WITBOX/Configuration_adv.h @@ -1227,4 +1227,27 @@ */ #define FASTER_GCODE_PARSER +/** + * User-defined menu items that execute custom GCode + */ +//#define CUSTOM_USER_MENUS +#if ENABLED(CUSTOM_USER_MENUS) + #define USER_SCRIPT_DONE "M117 User Script Done" + + #define USER_DESC_1 "Home & UBL Info" + #define USER_GCODE_1 "G28\nG29 W" + + #define USER_DESC_2 "Preheat for PLA" + #define USER_GCODE_2 "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) + + #define USER_DESC_3 "Preheat for ABS" + #define USER_GCODE_3 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) + + #define USER_DESC_4 "Heat Bed/Home/Level" + #define USER_GCODE_4 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nG28\nG29" + + //#define USER_DESC_5 "Home & Info" + //#define USER_GCODE_5 "G28\nM503" +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h index 95f6ddcb3..e60b421a9 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h @@ -1232,4 +1232,27 @@ */ #define FASTER_GCODE_PARSER +/** + * User-defined menu items that execute custom GCode + */ +//#define CUSTOM_USER_MENUS +#if ENABLED(CUSTOM_USER_MENUS) + #define USER_SCRIPT_DONE "M117 User Script Done" + + #define USER_DESC_1 "Home & UBL Info" + #define USER_GCODE_1 "G28\nG29 W" + + #define USER_DESC_2 "Preheat for PLA" + #define USER_GCODE_2 "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) + + #define USER_DESC_3 "Preheat for ABS" + #define USER_GCODE_3 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) + + #define USER_DESC_4 "Heat Bed/Home/Level" + #define USER_GCODE_4 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nG28\nG29" + + #define USER_DESC_5 "Home & Info" + #define USER_GCODE_5 "G28\nM503" +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h index 79e9f1d45..05aefb8ba 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h @@ -1231,4 +1231,27 @@ */ #define FASTER_GCODE_PARSER +/** + * User-defined menu items that execute custom GCode + */ +//#define CUSTOM_USER_MENUS +#if ENABLED(CUSTOM_USER_MENUS) + #define USER_SCRIPT_DONE "M117 User Script Done" + + #define USER_DESC_1 "Home & UBL Info" + #define USER_GCODE_1 "G28\nG29 W" + + #define USER_DESC_2 "Preheat for PLA" + #define USER_GCODE_2 "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) + + #define USER_DESC_3 "Preheat for ABS" + #define USER_GCODE_3 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) + + #define USER_DESC_4 "Heat Bed/Home/Level" + #define USER_GCODE_4 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nG28\nG29" + + #define USER_DESC_5 "Home & Info" + #define USER_GCODE_5 "G28\nM503" +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/delta/generic/Configuration_adv.h b/Marlin/example_configurations/delta/generic/Configuration_adv.h index cd8302aea..a37cc5572 100644 --- a/Marlin/example_configurations/delta/generic/Configuration_adv.h +++ b/Marlin/example_configurations/delta/generic/Configuration_adv.h @@ -1229,4 +1229,27 @@ */ #define FASTER_GCODE_PARSER +/** + * User-defined menu items that execute custom GCode + */ +//#define CUSTOM_USER_MENUS +#if ENABLED(CUSTOM_USER_MENUS) + #define USER_SCRIPT_DONE "M117 User Script Done" + + #define USER_DESC_1 "Home & UBL Info" + #define USER_GCODE_1 "G28\nG29 W" + + #define USER_DESC_2 "Preheat for PLA" + #define USER_GCODE_2 "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) + + #define USER_DESC_3 "Preheat for ABS" + #define USER_GCODE_3 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) + + #define USER_DESC_4 "Heat Bed/Home/Level" + #define USER_GCODE_4 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nG28\nG29" + + #define USER_DESC_5 "Home & Info" + #define USER_GCODE_5 "G28\nM503" +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h index cd8302aea..a37cc5572 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h @@ -1229,4 +1229,27 @@ */ #define FASTER_GCODE_PARSER +/** + * User-defined menu items that execute custom GCode + */ +//#define CUSTOM_USER_MENUS +#if ENABLED(CUSTOM_USER_MENUS) + #define USER_SCRIPT_DONE "M117 User Script Done" + + #define USER_DESC_1 "Home & UBL Info" + #define USER_GCODE_1 "G28\nG29 W" + + #define USER_DESC_2 "Preheat for PLA" + #define USER_GCODE_2 "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) + + #define USER_DESC_3 "Preheat for ABS" + #define USER_GCODE_3 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) + + #define USER_DESC_4 "Heat Bed/Home/Level" + #define USER_GCODE_4 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nG28\nG29" + + #define USER_DESC_5 "Home & Info" + #define USER_GCODE_5 "G28\nM503" +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h index d1821c5ff..0e428fe65 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h @@ -1234,4 +1234,27 @@ */ #define FASTER_GCODE_PARSER +/** + * User-defined menu items that execute custom GCode + */ +//#define CUSTOM_USER_MENUS +#if ENABLED(CUSTOM_USER_MENUS) + #define USER_SCRIPT_DONE "M117 User Script Done" + + #define USER_DESC_1 "Home & UBL Info" + #define USER_GCODE_1 "G28\nG29 W" + + #define USER_DESC_2 "Preheat for PLA" + #define USER_GCODE_2 "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) + + #define USER_DESC_3 "Preheat for ABS" + #define USER_GCODE_3 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) + + #define USER_DESC_4 "Heat Bed/Home/Level" + #define USER_GCODE_4 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nG28\nG29" + + #define USER_DESC_5 "Home & Info" + #define USER_GCODE_5 "G28\nM503" +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h index 0f258e03a..99be30bf0 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h @@ -1229,4 +1229,27 @@ */ #define FASTER_GCODE_PARSER +/** + * User-defined menu items that execute custom GCode + */ +//#define CUSTOM_USER_MENUS +#if ENABLED(CUSTOM_USER_MENUS) + #define USER_SCRIPT_DONE "M117 User Script Done" + + #define USER_DESC_1 "Home & UBL Info" + #define USER_GCODE_1 "G28\nG29 W" + + #define USER_DESC_2 "Preheat for PLA" + #define USER_GCODE_2 "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) + + #define USER_DESC_3 "Preheat for ABS" + #define USER_GCODE_3 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) + + #define USER_DESC_4 "Heat Bed/Home/Level" + #define USER_GCODE_4 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nG28\nG29" + + //#define USER_DESC_5 "Home & Info" + //#define USER_GCODE_5 "G28\nM503" +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h index e0da01ead..c18723ee6 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h @@ -1236,4 +1236,27 @@ */ #define FASTER_GCODE_PARSER +/** + * User-defined menu items that execute custom GCode + */ +//#define CUSTOM_USER_MENUS +#if ENABLED(CUSTOM_USER_MENUS) + #define USER_SCRIPT_DONE "M117 User Script Done" + + #define USER_DESC_1 "Home & UBL Info" + #define USER_GCODE_1 "G28\nG29 W" + + #define USER_DESC_2 "Preheat for PLA" + #define USER_GCODE_2 "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) + + #define USER_DESC_3 "Preheat for ABS" + #define USER_GCODE_3 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) + + #define USER_DESC_4 "Heat Bed/Home/Level" + #define USER_GCODE_4 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nG28\nG29" + + //#define USER_DESC_5 "Home & Info" + //#define USER_GCODE_5 "G28\nM503" +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/makibox/Configuration_adv.h b/Marlin/example_configurations/makibox/Configuration_adv.h index aecf3c2af..f667868f1 100644 --- a/Marlin/example_configurations/makibox/Configuration_adv.h +++ b/Marlin/example_configurations/makibox/Configuration_adv.h @@ -1227,4 +1227,27 @@ */ #define FASTER_GCODE_PARSER +/** + * User-defined menu items that execute custom GCode + */ +//#define CUSTOM_USER_MENUS +#if ENABLED(CUSTOM_USER_MENUS) + #define USER_SCRIPT_DONE "M117 User Script Done" + + #define USER_DESC_1 "Home & UBL Info" + #define USER_GCODE_1 "G28\nG29 W" + + #define USER_DESC_2 "Preheat for PLA" + #define USER_GCODE_2 "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) + + #define USER_DESC_3 "Preheat for ABS" + #define USER_GCODE_3 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) + + #define USER_DESC_4 "Heat Bed/Home/Level" + #define USER_GCODE_4 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nG28\nG29" + + //#define USER_DESC_5 "Home & Info" + //#define USER_GCODE_5 "G28\nM503" +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h index bf5264a0e..3076378f9 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h @@ -1227,4 +1227,27 @@ */ #define FASTER_GCODE_PARSER +/** + * User-defined menu items that execute custom GCode + */ +//#define CUSTOM_USER_MENUS +#if ENABLED(CUSTOM_USER_MENUS) + #define USER_SCRIPT_DONE "M117 User Script Done" + + #define USER_DESC_1 "Home & UBL Info" + #define USER_GCODE_1 "G28\nG29 W" + + #define USER_DESC_2 "Preheat for PLA" + #define USER_GCODE_2 "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) + + #define USER_DESC_3 "Preheat for ABS" + #define USER_GCODE_3 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) + + #define USER_DESC_4 "Heat Bed/Home/Level" + #define USER_GCODE_4 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nG28\nG29" + + //#define USER_DESC_5 "Home & Info" + //#define USER_GCODE_5 "G28\nM503" +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/wt150/Configuration_adv.h b/Marlin/example_configurations/wt150/Configuration_adv.h index 83daabe77..1c0a28083 100644 --- a/Marlin/example_configurations/wt150/Configuration_adv.h +++ b/Marlin/example_configurations/wt150/Configuration_adv.h @@ -1230,4 +1230,27 @@ */ #define FASTER_GCODE_PARSER +/** + * User-defined menu items that execute custom GCode + */ +//#define CUSTOM_USER_MENUS +#if ENABLED(CUSTOM_USER_MENUS) + #define USER_SCRIPT_DONE "M117 User Script Done" + + #define USER_DESC_1 "Home & UBL Info" + #define USER_GCODE_1 "G28\nG29 W" + + #define USER_DESC_2 "Preheat for PLA" + #define USER_GCODE_2 "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) + + #define USER_DESC_3 "Preheat for ABS" + #define USER_GCODE_3 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) + + #define USER_DESC_4 "Heat Bed/Home/Level" + #define USER_GCODE_4 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nG28\nG29" + + //#define USER_DESC_5 "Home & Info" + //#define USER_GCODE_5 "G28\nM503" +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/language_en.h b/Marlin/language_en.h index 8de63f436..3190a12a5 100644 --- a/Marlin/language_en.h +++ b/Marlin/language_en.h @@ -156,6 +156,9 @@ #ifndef MSG_LEVEL_BED #define MSG_LEVEL_BED _UxGT("Level bed") #endif +#ifndef MSG_USER_MENU + #define MSG_USER_MENU _UxGT("Custom Commands") +#endif #if ENABLED(AUTO_BED_LEVELING_UBL) #ifndef MSG_UBL_UNHOMED diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index e5eebff05..3958d5908 100755 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -789,6 +789,58 @@ void kill_screen(const char* lcd_msg) { #endif // HAS_DEBUG_MENU + #if ENABLED(CUSTOM_USER_MENUS) + + #ifdef USER_SCRIPT_DONE + #define _DONE_SCRIPT "\n" USER_SCRIPT_DONE + #else + #define _DONE_SCRIPT "" + #endif + + void _lcd_user_gcode(const char * const cmd) { + lcd_return_to_status(); + enqueue_and_echo_commands_P(cmd); + } + + #if defined(USER_DESC_1) && defined(USER_GCODE_1) + void lcd_user_gcode_1() { _lcd_user_gcode(PSTR(USER_GCODE_1 _DONE_SCRIPT)); } + #endif + #if defined(USER_DESC_2) && defined(USER_GCODE_2) + void lcd_user_gcode_2() { _lcd_user_gcode(PSTR(USER_GCODE_2 _DONE_SCRIPT)); } + #endif + #if defined(USER_DESC_3) && defined(USER_GCODE_3) + void lcd_user_gcode_3() { _lcd_user_gcode(PSTR(USER_GCODE_3 _DONE_SCRIPT)); } + #endif + #if defined(USER_DESC_4) && defined(USER_GCODE_4) + void lcd_user_gcode_4() { _lcd_user_gcode(PSTR(USER_GCODE_4 _DONE_SCRIPT)); } + #endif + #if defined(USER_DESC_5) && defined(USER_GCODE_5) + void lcd_user_gcode_5() { _lcd_user_gcode(PSTR(USER_GCODE_5 _DONE_SCRIPT)); } + #endif + + void _lcd_user_menu() { + START_MENU(); + MENU_BACK(MSG_MAIN); + #if defined(USER_DESC_1) && defined(USER_GCODE_1) + MENU_ITEM(function, USER_DESC_1, lcd_user_gcode_1); + #endif + #if defined(USER_DESC_2) && defined(USER_GCODE_2) + MENU_ITEM(function, USER_DESC_2, lcd_user_gcode_2); + #endif + #if defined(USER_DESC_3) && defined(USER_GCODE_3) + MENU_ITEM(function, USER_DESC_3, lcd_user_gcode_3); + #endif + #if defined(USER_DESC_4) && defined(USER_GCODE_4) + MENU_ITEM(function, USER_DESC_4, lcd_user_gcode_4); + #endif + #if defined(USER_DESC_5) && defined(USER_GCODE_5) + MENU_ITEM(function, USER_DESC_5, lcd_user_gcode_5); + #endif + END_MENU(); + } + + #endif + /** * * "Main" menu @@ -804,6 +856,10 @@ void kill_screen(const char* lcd_msg) { START_MENU(); MENU_BACK(MSG_WATCH); + #if ENABLED(CUSTOM_USER_MENUS) + MENU_ITEM(submenu, MSG_USER_MENU, _lcd_user_menu); + #endif + // // Debug Menu when certain options are enabled // From 6b9ca16f3682043dcf263dbadb54db076bd8cc12 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 30 May 2017 02:47:15 -0500 Subject: [PATCH 187/189] Patch lcd_print edge limit code --- Marlin/macros.h | 1 + Marlin/ultralcd.cpp | 6 +++--- Marlin/ultralcd_impl_DOGM.h | 2 +- Marlin/ultralcd_impl_HD44780.h | 2 +- 4 files changed, 6 insertions(+), 5 deletions(-) diff --git a/Marlin/macros.h b/Marlin/macros.h index 0fb057441..c37416b47 100644 --- a/Marlin/macros.h +++ b/Marlin/macros.h @@ -127,6 +127,7 @@ #define DECIMAL(a) (NUMERIC(a) || a == '.') #define NUMERIC_SIGNED(a) (NUMERIC(a) || (a) == '-' || (a) == '+') #define DECIMAL_SIGNED(a) (DECIMAL(a) || (a) == '-' || (a) == '+') +#define PRINTABLE(C) (((C) & 0xC0u) != 0x80u) #define COUNT(a) (sizeof(a)/sizeof(*a)) #define ZERO(a) memset(a,0,sizeof(a)) #define COPY(a,b) memcpy(a,b,min(sizeof(a),sizeof(b))) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index e5eebff05..cd1701481 100755 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -3814,7 +3814,7 @@ int lcd_strlen(const char* s) { #if ENABLED(MAPPER_NON) j++; #else - if ((s[i] & 0xC0u) != 0x80u) j++; + if (PRINTABLE(s[i])) j++; #endif i++; } @@ -3827,7 +3827,7 @@ int lcd_strlen_P(const char* s) { #if ENABLED(MAPPER_NON) j++; #else - if ((pgm_read_byte(s) & 0xC0u) != 0x80u) j++; + if (PRINTABLE(pgm_read_byte(s))) j++; #endif s++; } @@ -4096,7 +4096,7 @@ void lcd_update() { #if ENABLED(MAPPER_NON) j++; #else - if ((s[i] & 0xC0u) != 0x80u) j++; + if (PRINTABLE(s[i])) j++; #endif i++; } diff --git a/Marlin/ultralcd_impl_DOGM.h b/Marlin/ultralcd_impl_DOGM.h index ac6fedabb..c7c5eb309 100644 --- a/Marlin/ultralcd_impl_DOGM.h +++ b/Marlin/ultralcd_impl_DOGM.h @@ -412,7 +412,7 @@ inline void lcd_implementation_status_message() { const uint8_t slen = lcd_strlen(lcd_status_message); if (slen > LCD_WIDTH) { // Skip any non-printing bytes - while (!charset_mapper(lcd_status_message[status_scroll_pos])) ++status_scroll_pos; + while (!PRINTABLE(lcd_status_message[status_scroll_pos])) ++status_scroll_pos; if (++status_scroll_pos > slen - LCD_WIDTH) status_scroll_pos = 0; } #else diff --git a/Marlin/ultralcd_impl_HD44780.h b/Marlin/ultralcd_impl_HD44780.h index d650890d5..6c7389571 100644 --- a/Marlin/ultralcd_impl_HD44780.h +++ b/Marlin/ultralcd_impl_HD44780.h @@ -831,7 +831,7 @@ static void lcd_implementation_status_screen() { const uint8_t slen = lcd_strlen(lcd_status_message); if (slen > LCD_WIDTH) { // Skip any non-printing bytes - while (!charset_mapper(lcd_status_message[status_scroll_pos])) ++status_scroll_pos; + while (!PRINTABLE(lcd_status_message[status_scroll_pos])) ++status_scroll_pos; if (++status_scroll_pos > slen - LCD_WIDTH) status_scroll_pos = 0; } #else From 266ae8912a9fe30381bea7f33eae65f8d4ad4451 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 30 May 2017 03:20:10 -0500 Subject: [PATCH 188/189] Formatting in _draw_heater_status --- Marlin/ultralcd_impl_HD44780.h | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/Marlin/ultralcd_impl_HD44780.h b/Marlin/ultralcd_impl_HD44780.h index 6c7389571..909271d77 100644 --- a/Marlin/ultralcd_impl_HD44780.h +++ b/Marlin/ultralcd_impl_HD44780.h @@ -582,8 +582,8 @@ FORCE_INLINE void _draw_axis_label(const AxisEnum axis, const char* const pstr, FORCE_INLINE void _draw_heater_status(const int8_t heater, const char prefix, const bool blink) { const bool isBed = heater < 0; - const float t1 = (isBed ? thermalManager.degBed() : thermalManager.degHotend(heater)); - const float t2 = (isBed ? thermalManager.degTargetBed() : thermalManager.degTargetHotend(heater)); + const float t1 = (isBed ? thermalManager.degBed() : thermalManager.degHotend(heater)), + t2 = (isBed ? thermalManager.degTargetBed() : thermalManager.degTargetHotend(heater)); if (prefix >= 0) lcd.print(prefix); @@ -592,11 +592,11 @@ FORCE_INLINE void _draw_heater_status(const int8_t heater, const char prefix, co #if ENABLED(ADVANCED_PAUSE_FEATURE) const bool is_idle = (!isBed ? thermalManager.is_heater_idle(heater) : - #if HAS_TEMP_BED - thermalManager.is_bed_idle() - #else - false - #endif + #if HAS_TEMP_BED + thermalManager.is_bed_idle() + #else + false + #endif ); if (!blink && is_idle) { @@ -606,7 +606,7 @@ FORCE_INLINE void _draw_heater_status(const int8_t heater, const char prefix, co } else #endif - lcd.print(itostr3left(t2 + 0.5)); + lcd.print(itostr3left(t2 + 0.5)); if (prefix >= 0) { lcd_printPGM(PSTR(LCD_STR_DEGREE " ")); From be17033762572bfbdf8f935a55ec47d4e67253f5 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 30 May 2017 14:03:45 -0500 Subject: [PATCH 189/189] Fix case light menu toggle --- Marlin/ultralcd.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index fb24ac3c2..7ce08055c 100755 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -871,7 +871,7 @@ void kill_screen(const char* lcd_msg) { // Switch case light on/off // #if ENABLED(MENU_ITEM_CASE_LIGHT) - MENU_ITEM_EDIT_CALLBACK(bool, MSG_CASE_LIGHT, case_light_on, update_case_light); + MENU_ITEM_EDIT_CALLBACK(bool, MSG_CASE_LIGHT, &case_light_on, update_case_light); #endif if (planner.movesplanned() || IS_SD_PRINTING) {